From b7699024e22be7642788c8d47ec40bd28e7b29c8 Mon Sep 17 00:00:00 2001 From: AlexanderPolyakov Date: Tue, 7 Oct 2014 19:10:35 +0400 Subject: [PATCH 01/66] Fix for use of uninitialized variables. m_implicitShapeDimensions was used in setMargin, called from setSafeMargin from constructors of btBoxShape, btCylinerShape and btBox2dShape, effectively using uninitialized variable and leading to floating point exceptions. It was working correctly only because in the same constructor m_implicitShapeDimensions was reinitialized after setSafeMargin. Properly initialize variable before use by first setting it up and only then using it in setSafeMargin. --- src/BulletCollision/CollisionShapes/btBox2dShape.h | 3 ++- src/BulletCollision/CollisionShapes/btBoxShape.cpp | 4 ++-- src/BulletCollision/CollisionShapes/btCylinderShape.cpp | 5 +++-- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/src/BulletCollision/CollisionShapes/btBox2dShape.h b/src/BulletCollision/CollisionShapes/btBox2dShape.h index ce333783e..22bee4f2c 100644 --- a/src/BulletCollision/CollisionShapes/btBox2dShape.h +++ b/src/BulletCollision/CollisionShapes/btBox2dShape.h @@ -103,11 +103,12 @@ public: btScalar minDimension = boxHalfExtents.getX(); if (minDimension>boxHalfExtents.getY()) minDimension = boxHalfExtents.getY(); - setSafeMargin(minDimension); m_shapeType = BOX_2D_SHAPE_PROXYTYPE; btVector3 margin(getMargin(),getMargin(),getMargin()); m_implicitShapeDimensions = (boxHalfExtents * m_localScaling) - margin; + + setSafeMargin(minDimension); }; virtual void setMargin(btScalar collisionMargin) diff --git a/src/BulletCollision/CollisionShapes/btBoxShape.cpp b/src/BulletCollision/CollisionShapes/btBoxShape.cpp index 3859138f1..72eeb3891 100644 --- a/src/BulletCollision/CollisionShapes/btBoxShape.cpp +++ b/src/BulletCollision/CollisionShapes/btBoxShape.cpp @@ -19,10 +19,10 @@ btBoxShape::btBoxShape( const btVector3& boxHalfExtents) { m_shapeType = BOX_SHAPE_PROXYTYPE; - setSafeMargin(boxHalfExtents); - btVector3 margin(getMargin(),getMargin(),getMargin()); m_implicitShapeDimensions = (boxHalfExtents * m_localScaling) - margin; + + setSafeMargin(boxHalfExtents); }; diff --git a/src/BulletCollision/CollisionShapes/btCylinderShape.cpp b/src/BulletCollision/CollisionShapes/btCylinderShape.cpp index 6cfe43be4..604b3fc77 100644 --- a/src/BulletCollision/CollisionShapes/btCylinderShape.cpp +++ b/src/BulletCollision/CollisionShapes/btCylinderShape.cpp @@ -19,10 +19,11 @@ btCylinderShape::btCylinderShape (const btVector3& halfExtents) :btConvexInternalShape(), m_upAxis(1) { - setSafeMargin(halfExtents); - btVector3 margin(getMargin(),getMargin(),getMargin()); m_implicitShapeDimensions = (halfExtents * m_localScaling) - margin; + + setSafeMargin(halfExtents); + m_shapeType = CYLINDER_SHAPE_PROXYTYPE; } From 44b140dd38cde7c8a33fcab27f81d267e6f30a0a Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sat, 4 Mar 2017 12:59:21 -0800 Subject: [PATCH 02/66] disable the gMaxNumCmdPer1ms experiment by default (-1) fix minitaur_evaluate.py script, quadruped.py --- .../PhysicsServerCommandProcessor.cpp | 2 +- .../SharedMemory/PhysicsServerExample.cpp | 14 ++- examples/pybullet/minitaur_evaluate.py | 2 +- examples/pybullet/pybullet.c | 5 +- examples/pybullet/quadruped.py | 117 ++++++++++++------ 5 files changed, 95 insertions(+), 45 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 312691872..1c46d1d1d 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -48,7 +48,7 @@ bool gResetSimulation = 0; int gVRTrackingObjectUniqueId = -1; btTransform gVRTrackingObjectTr = btTransform::getIdentity(); -int gMaxNumCmdPer1ms = 10;//experiment: add some delay to avoid threads starving other threads +int gMaxNumCmdPer1ms = -1;//experiment: add some delay to avoid threads starving other threads int gCreateObjectSimVR = -1; int gEnableKukaControl = 0; btVector3 gVRTeleportPos1(0,0,0); diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index ed15aa1b1..5b0a02237 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -313,13 +313,15 @@ void MotionThreadFunc(void* userPtr,void* lsMemory) b3Clock::usleep(0); } - if (numCmdSinceSleep1ms>gMaxNumCmdPer1ms) + if (gMaxNumCmdPer1ms>0) { - BT_PROFILE("usleep(1000)"); - b3Clock::usleep(1000); - numCmdSinceSleep1ms = 0; - sleepClock.reset(); - } + if (numCmdSinceSleep1ms>gMaxNumCmdPer1ms) + { + BT_PROFILE("usleep(10)"); + b3Clock::usleep(10); + numCmdSinceSleep1ms = 0; + sleepClock.reset(); + } if (sleepClock.getTimeMilliseconds()>1) { sleepClock.reset(); diff --git a/examples/pybullet/minitaur_evaluate.py b/examples/pybullet/minitaur_evaluate.py index 3c3e65280..716723a22 100644 --- a/examples/pybullet/minitaur_evaluate.py +++ b/examples/pybullet/minitaur_evaluate.py @@ -18,7 +18,7 @@ def current_position(): def is_fallen(): global minitaur orientation = minitaur.getBaseOrientation() - rotMat = p.getMatrixFromQuaterion(orientation) + rotMat = p.getMatrixFromQuaternion(orientation) localUp = rotMat[6:] return np.dot(np.asarray([0, 0, 1]), np.asarray(localUp)) < 0 diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 24234c53b..f1a51a712 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -606,7 +606,7 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar int numSubSteps = -1; int collisionFilterMode = -1; double contactBreakingThreshold = -1; - int maxNumCmdPer1ms = -1; + int maxNumCmdPer1ms = -2; b3PhysicsClientHandle sm = 0; int physicsClientId = 0; @@ -658,7 +658,8 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar { b3PhysicsParamSetContactBreakingThreshold(command,contactBreakingThreshold); } - if (maxNumCmdPer1ms>=0) + //-1 is disables the maxNumCmdPer1ms feature, allow it + if (maxNumCmdPer1ms>=-1) { b3PhysicsParamSetMaxNumCommandsPer1ms(command,maxNumCmdPer1ms); } diff --git a/examples/pybullet/quadruped.py b/examples/pybullet/quadruped.py index 0d8f32b47..5e4eade4f 100644 --- a/examples/pybullet/quadruped.py +++ b/examples/pybullet/quadruped.py @@ -2,19 +2,59 @@ import pybullet as p import time import math -useRealTime = 0 +useRealTime = 1 fixedTimeStep = 0.001 +speed = 10 +amplitude = 1.3 +jump_amp = 0.5 +maxForce = 3.5 +kp = .6 +kd = 1 + physId = p.connect(p.SHARED_MEMORY) if (physId<0): p.connect(p.GUI) p.loadURDF("plane.urdf") -p.setGravity(0,0,-1) +p.setGravity(0,0,-10) p.setTimeStep(fixedTimeStep) -p.setRealTimeSimulation(0) -quadruped = p.loadURDF("quadruped/quadruped.urdf",1,-2,1) +p.setRealTimeSimulation(1) +quadruped = p.loadURDF("quadruped/quadruped.urdf",1,-2,0.3) +nJoints = p.getNumJoints(quadruped) + +jointNameToId = {} +for i in range(nJoints): + jointInfo = p.getJointInfo(quadruped, i) + jointNameToId[jointInfo[1].decode('UTF-8')] = jointInfo[0] + +motor_front_rightR_joint = jointNameToId['motor_front_rightR_joint'] +hip_front_rightR_link = jointNameToId['hip_front_rightR_link'] +knee_front_rightR_link = jointNameToId['knee_front_rightR_link'] +motor_front_rightL_joint = jointNameToId['motor_front_rightL_joint'] +motor_front_rightL_link = jointNameToId['motor_front_rightL_link'] +knee_front_rightL_link = jointNameToId['knee_front_rightL_link'] +motor_front_leftR_joint = jointNameToId['motor_front_leftR_joint'] +hip_front_leftR_link = jointNameToId['hip_front_leftR_link'] +knee_front_leftR_link = jointNameToId['knee_front_leftR_link'] +motor_front_leftL_joint = jointNameToId['motor_front_leftL_joint'] +motor_front_leftL_link = jointNameToId['motor_front_leftL_link'] +knee_front_leftL_link = jointNameToId['knee_front_leftL_link'] +motor_back_rightR_joint = jointNameToId['motor_back_rightR_joint'] +hip_rightR_link = jointNameToId['hip_rightR_link'] +knee_back_rightR_link = jointNameToId['knee_back_rightR_link'] +motor_back_rightL_joint = jointNameToId['motor_back_rightL_joint'] +motor_back_rightL_link = jointNameToId['motor_back_rightL_link'] +knee_back_rightL_link = jointNameToId['knee_back_rightL_link'] +motor_back_leftR_joint = jointNameToId['motor_back_leftR_joint'] +hip_leftR_link = jointNameToId['hip_leftR_link'] +knee_back_leftR_link = jointNameToId['knee_back_leftR_link'] +motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint'] +motor_back_leftL_link = jointNameToId['motor_back_leftL_link'] +knee_back_leftL_link = jointNameToId['knee_back_leftL_link'] + + #p.getNumJoints(1) #right front leg p.resetJointState(quadruped,0,1.57) @@ -74,10 +114,16 @@ p.setJointMotorControl(quadruped,22,p.VELOCITY_CONTROL,0,0) p.setJointMotorControl(quadruped,23,p.VELOCITY_CONTROL,0,0) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + -p_gain =1 -speed = 10 -amplitude = 1.3 #stand still p.setRealTimeSimulation(useRealTime) @@ -92,12 +138,11 @@ while t < t_end: p.stepSimulation() else: t = time.time()-ref_time - p.setGravity(0,0,-1) + p.setGravity(0,0,-10) p.setGravity(0,0,-10) -jump_amp = 0.5 - + #jump t = 0.0 t_end = t + 10 @@ -110,18 +155,18 @@ while t < t_end: else: t = t+fixedTimeStep - p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain) - p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain) - p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain) - p.setJointMotorControl(quadruped,9,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain) - p.setJointMotorControl(quadruped,12,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain) - p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain) - p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain) - p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*jump_amp+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-math.sin(t*speed)*jump_amp-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*jump_amp+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-math.sin(t*speed)*jump_amp-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*jump_amp+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-math.sin(t*speed)*jump_amp-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*jump_amp+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-math.sin(t*speed)*jump_amp-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + if (useRealTime==0): p.stepSimulation() - #hop forward t_end = 20 i=0 @@ -131,14 +176,15 @@ while t < t_end: else: t = t+fixedTimeStep - p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*speed)*amplitude+1.57,p_gain) - p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-1.57,p_gain) - p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*speed)*amplitude+1.57,p_gain) - p.setJointMotorControl(quadruped,9,p.POSITION_CONTROL,-1.57,p_gain) - p.setJointMotorControl(quadruped,12,p.POSITION_CONTROL,math.sin(t*speed+3.14)*amplitude+1.57,p_gain) - p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-1.57,p_gain) - p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,math.sin(t*speed+3.14)*amplitude+1.57,p_gain) - p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,p_gain) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed+3.14)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed+3.14)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + if (useRealTime==0): p.stepSimulation() @@ -151,14 +197,15 @@ while t < t_end: else: t = t+fixedTimeStep - p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*3)*.3+1.57,1) - p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-1.57,1) - p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*3+0.5*3.14)*.3+1.57,1) - p.setJointMotorControl(quadruped,9,p.POSITION_CONTROL,-1.57,1) - p.setJointMotorControl(quadruped,12,p.POSITION_CONTROL,math.sin(t*3+3.14)*.3+1.57,1) - p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-1.57,1) - p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,math.sin(t*3+1.5*3.14)*.3+1.57,1) - p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,1) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3+0.5*3.14)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3+3.14)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3+1.5*3.14)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + p.stepSimulation() p.setRealTimeSimulation(1) From c7579d7b82551ba723b79c481a8f536df4049d87 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sat, 4 Mar 2017 15:30:57 -0800 Subject: [PATCH 03/66] fix quadruped, allow user to pick the maximum number of dofs to log --- examples/SharedMemory/PhysicsClientC_API.cpp | 14 ++++++++++++++ examples/SharedMemory/PhysicsClientC_API.h | 4 ++++ .../SharedMemory/PhysicsServerCommandProcessor.cpp | 8 +++++++- examples/SharedMemory/PhysicsServerExample.cpp | 1 + examples/SharedMemory/SharedMemoryCommands.h | 2 ++ examples/pybullet/kuka_with_cube_playback.py | 6 +++--- examples/pybullet/pybullet.c | 11 ++++++++--- 7 files changed, 39 insertions(+), 7 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 0ec231e4a..a7d23f68c 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -2585,6 +2585,20 @@ int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHa } return 0; } + +int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int maxLogDof) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_STATE_LOGGING); + if (command->m_type == CMD_STATE_LOGGING) + { + command->m_updateFlags |= STATE_LOGGING_MAX_LOG_DOF; + command->m_stateLoggingArguments.m_maxLogDof = maxLogDof; + } + return 0; +} + int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index e71203700..01eb55cc1 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -356,9 +356,13 @@ void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3Keyboard b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient); int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName); int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId); +int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int maxLogDof); + int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle); int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUniqueId); + + void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds); double b3GetTimeOut(b3PhysicsClientHandle physClient); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 1c46d1d1d..68ca59fbf 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1856,6 +1856,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm std::string fileName = clientCmd.m_stateLoggingArguments.m_fileName; int loggerUid = m_data->m_stateLoggersUniqueId++; + int maxLogDof = 12; + if ((clientCmd.m_updateFlags & STATE_LOGGING_MAX_LOG_DOF)) + { + maxLogDof = clientCmd.m_stateLoggingArguments.m_maxLogDof; + } GenericRobotStateLogger* logger = new GenericRobotStateLogger(loggerUid,fileName,m_data->m_dynamicsWorld); if ((clientCmd.m_updateFlags & STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID) && (clientCmd.m_stateLoggingArguments.m_numBodyUniqueIds>0)) @@ -1863,7 +1868,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm logger->m_filterObjectUniqueId = true; for (int i = 0; i < clientCmd.m_stateLoggingArguments.m_numBodyUniqueIds; ++i) { - logger->m_bodyIdList.push_back(clientCmd.m_stateLoggingArguments.m_bodyUniqueIds[i]); + int objectUniqueId = clientCmd.m_stateLoggingArguments.m_bodyUniqueIds[i]; + logger->m_bodyIdList.push_back(objectUniqueId); } } diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 5b0a02237..dc3390c4e 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -322,6 +322,7 @@ void MotionThreadFunc(void* userPtr,void* lsMemory) numCmdSinceSleep1ms = 0; sleepClock.reset(); } + } if (sleepClock.getTimeMilliseconds()>1) { sleepClock.reset(); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 725849d20..1c119c4d1 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -626,6 +626,7 @@ enum eStateLoggingEnums STATE_LOGGING_START_LOG=1, STATE_LOGGING_STOP_LOG=2, STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID=4, + STATE_LOGGING_MAX_LOG_DOF=8 }; struct VRCameraState @@ -644,6 +645,7 @@ struct StateLoggingRequest int m_numBodyUniqueIds;////only if ROBOT_LOGGING_FILTER_OBJECT_UNIQUE_ID flag is set int m_bodyUniqueIds[MAX_SDF_BODIES]; int m_loggingUniqueId; + int m_maxLogDof; }; struct StateLoggingResultArgs diff --git a/examples/pybullet/kuka_with_cube_playback.py b/examples/pybullet/kuka_with_cube_playback.py index c3a5ad445..9975b27c5 100644 --- a/examples/pybullet/kuka_with_cube_playback.py +++ b/examples/pybullet/kuka_with_cube_playback.py @@ -16,8 +16,8 @@ def readLogFile(filename, verbose = True): print('Opened'), print(filename) - keys = f.readline().rstrip('\n').split(',') - fmt = f.readline().rstrip('\n') + keys = f.readline().decode('utf8').rstrip('\n').split(',') + fmt = f.readline().decode('utf8').rstrip('\n') # The byte number of one record sz = struct.calcsize(fmt) @@ -37,7 +37,7 @@ def readLogFile(filename, verbose = True): # Read data wholeFile = f.read() # split by alignment word - chunks = wholeFile.split('\xaa\xbb') + chunks = wholeFile.split(b'\xaa\xbb') log = list() for chunk in chunks: if len(chunk) == sz: diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index f1a51a712..8f72dfe77 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -2625,12 +2625,13 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb int loggingType = -1; char* fileName = 0; PyObject* objectUniqueIdsObj = 0; + int maxLogDof=-1; - static char *kwlist[] = { "loggingType", "fileName", "objectUniqueIds", "physicsClientId", NULL }; + static char *kwlist[] = { "loggingType", "fileName", "objectUniqueIds", "maxLogDof", "physicsClientId", NULL }; int physicsClientId = 0; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|Oi", kwlist, - &loggingType, &fileName, &objectUniqueIdsObj,&physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|Oii", kwlist, + &loggingType, &fileName, &objectUniqueIdsObj,&maxLogDof, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); @@ -2661,6 +2662,10 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb } } + if (maxLogDof>0) + { + b3StateLoggingSetMaxLogDof(commandHandle, maxLogDof); + } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); From 00361afea58c67592bffa79d2aeceebb87c8ba2a Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sun, 5 Mar 2017 21:49:20 -0800 Subject: [PATCH 04/66] allow user to specify the maximum number of dofs to log in GenericRobotStateLogger (default = 12) add minitaur quadruped playback of minitaur log files (real robot and simulated create the same log files) add improved minitaur.urdf file, see https://youtu.be/lv7lybtOzeo for a preview. --- data/plane.urdf | 2 +- data/quadruped/LOG00076.TXT | Bin 0 -> 1704957 bytes data/quadruped/minitaur.urdf | 913 ++++++++++++++++++ data/quadruped/t-motor.jpg | Bin 0 -> 156770 bytes data/quadruped/tmotor.blend | Bin 0 -> 475716 bytes data/quadruped/tmotor3.mtl | 19 + data/quadruped/tmotor3.obj | 325 +++++++ .../PhysicsServerCommandProcessor.cpp | 59 +- examples/pybullet/quadruped.py | 206 ++-- examples/pybullet/quadruped_playback.py | 126 +++ examples/pybullet/quadruped_setup_playback.py | 21 + 11 files changed, 1509 insertions(+), 162 deletions(-) create mode 100644 data/quadruped/LOG00076.TXT create mode 100644 data/quadruped/minitaur.urdf create mode 100644 data/quadruped/t-motor.jpg create mode 100644 data/quadruped/tmotor.blend create mode 100644 data/quadruped/tmotor3.mtl create mode 100644 data/quadruped/tmotor3.obj create mode 100644 examples/pybullet/quadruped_playback.py create mode 100644 examples/pybullet/quadruped_setup_playback.py diff --git a/data/plane.urdf b/data/plane.urdf index ad10aeedf..1b3d09682 100644 --- a/data/plane.urdf +++ b/data/plane.urdf @@ -2,7 +2,7 @@ - + diff --git a/data/quadruped/LOG00076.TXT b/data/quadruped/LOG00076.TXT new file mode 100644 index 0000000000000000000000000000000000000000..c1912b4e0450e7b08b333e638dde09a8ae8d3798 GIT binary patch literal 1704957 zcmagmd00(f`#ApQN%KgBC{v=rSo`dCZ)0Q%MP^N8%9Od%Jf}HhA{B3nG;8nEZW1EZ zX+Rk&MI}@Uh5Yu}`|*C>&*$@bzQ1!_E*F3Fy6&~^b+3D^y-#jNhl~ywoiIA&WOTsE z=!BEeK@+2crbY+Nj1JB)Iylql;4GtqvyBeUF*;&mbi~x?h?&um8AeBD8XcKsbY!;C zkvT@kos8Bw8136Hw{*vU`OKHQNiG2qktAL+RY@t5!%nqy$9nIAD@I}#E???-2g=-0 z$LD&q{p~d5^=uGXyWK}udK{6poeWre8X$k319G}|-$Gt&1Tvjef?rhd!=rfKsGzry zl3BS7i7+2olkoW>H_0^&lOvx@Nt7v*rw`WB%{z(;n$-p@`mM!rB9vo_4jZ$~$h0yf z;_ZwitYknr!2m^#aX@xibr!30*I) zm>mq`HX@m_o1sAt9;l_=kK2%}a7*A0Q!pm__bgGS{ws%{xgEop|4loRVRWe0{jwBy#sih6R28 zB)+GXo{X80gtY&?pIa6FgXx(1pV0_YK;h~Zbp5n5mPyN?N9j-Sp^hNj@~a2RY0al5 zhjEMn$M`YKch6+XU0sj#*-%SoG)y&rGC`NzxJv48MkM`z51NoM+_42|%yq+3J7v(} zj3@Yuts!{kVGp!YA&)w>oMRe|*-SgbFkecav`p?`f7TC~)q0FB-$q^`BuM(ec>yOXd=z$LXyhUyM z%rVQk6nM=rucDKw!oPsbYiFuJs=y+0*5Lw&b?ez^gp6<_5Z1JRG8yvvNHBQ|TA5O4 zQQsnmR9q@?UB7wW++I@=t#*El|57=E({sGhi%~Vy)(noh z%FRt5!$|gAqXci}lbQ9kG{w)vbk{4A1tq6gMi`CAS|c_ZAtT(@gpAjgacEZKc2suj zp84A*CG_oZDc-&M2wrIHjlT80qyiFGv(ad9(fnkXr&iY})m0107Y}M_<s$AlcRN135kW<+m?8vzn(WyxI4$lbBq+h z%uRg~HSPK$GN`DQ9#V|PineVfV_rsb(YQZDR~ihFj9?JyeJe-Ab_X^ZlghCu{bge9Xw(4w&MgxRyp$lg|jFn<2N@LQo0|MyBIVxGo$`tn8v zmYHS9G6u{)lzNs?iC5*xcZIdI=)Fkz>vCeD)xbwF+$1CqVUs zX0$zF5gcD!gj{<=z#w=4ZmnjnQ&?s?!>lt^ zpo}ec&an-zrIWOb@yLr;3*UV@jxVtv4HCzez;P2baBsAO?c>a$jV}Ys7jFQUMZ>5; zVGNWu4e~!2454?=qQLO6f8p5|YvD_|3N)Qw%Q8KaSY|H6q)xd=1_f3WjAI(8q=0Jt z{OKFuBX99t5Nv%tpb=0%RtsD9=)(|3CLJwqKq4k zY&51Evz%eh*3^@oeFGL@vbA)}8+Crh_blF4e=k&a(gpf|?FGA^R`4^#9h^2efX(6s zP-eLwcmuOx{^V20f9(`>7-=FG{VY_TV~nQGt4Ds%HzFBnKA#CjB$;E@G0d}Yb?Qo% z8Ajh0(0b@e;ch2;bhIxRxsBcjemf6>iRvcsaq@?S3%5X6w++1f>o~|?TLOzFO@}d7 z&rukDA77F+2A>+0flBCB{)JxuLY1_LLLswcGCMch8K%?RoRZnH52Kv~wDI@ps3GYz zf20nM{C>HCo8Tz)$8Uw`^#P#nz8Pi)Z-eZXW1zg>5-QanArZrPT>B%5_Kr%xjKu zW0-cidQ#1K7q;wu4gE!L0QpLo;E&$&SjMK?jb+|_^Mxfp)`45jc9xmDXDJZ2BpQ8S z2+z?rMxi?kQPs|QVE#e_ww+Xj*&|=Gj4iirJQ=1u^*p&FIuKh^Q9~DJsPTU##^RSx zSh9?I)B#Zcu@%nj^a15dHY{WC`~VwGrA7;CbErb*bK;QAj&EpMnHl6CdymBV;$So^ z!e-hgE}9^QStpfC>Rb)Qo@Le0izZGlj0wHRcTecRg>z$b#ue(GZULLz)38u$H6(l3 zgP)Eo%k*#4f?b0jkl`Ikn0m|>J|AvHW_2b=&hicFn7N6KCYH;zXolG$sY_|h^v7hP zYG{p9`Gu>=C|+;37;-z$4A{cGurPHqEX?x&kq@gt{g5NOZiIv8pQ!`Z`$Zx4fGnu) z2H4%L26j4HNJH#3`b5uXnS749#4rn+O{t*CKG@O2HMBmVLG|>RTDa}w;p$aKAiHJ{ zw3%%Mr(f=HW8+HLE9MM--Mhi2YAM|P*oVeX|AcPETteF>jsvmsv5*z&iXvBjL-fTY zmXYU}REC*0Uy^E^6^+UJ*3jl5kCCH)5O3$*YMzbHah7rWydBg(yMvzCa(LqA3{N^; z!2PTh2)b;M!^|*b-&T*i%@T$65gXvzp-iMxYz7mmm}F-@&nB|#CWB!LFJ31bhGH?X zYc=%uWuB;cf~7_7p=he?=t(Y`(+(^ne|Z@gNbUsn?=B$Hvm92-TA{Rkm(i7=$tXcp z1SD^qlO#+G9W7^ZLFI$59^jA^9T(C0j=3eEQa#Siq2=R3{tU>S)e zj%=|JMpHLoH_I&4T?z9q`l8~5VZFpPji9{7>KB|%x{hP*zn^lV)=eQJRo`B9;l0Sg1VAZ&>yk_7HaQhnV==BKzieK zv?J{^T3i^0I^QmX`VTWwj^3X|ek6r<8t$RTt)&(x5t%3<{p(rOy8n&EUfo5pVf@7ho zuxA5_8#Mn$=3m#bj3385XP84HMo9VGPggv>;T;5M{j6f(P^bSmrdxd=(Db zgLcv<$Q4^b3h2wKV+%zl#}`PhZDN_aj-3#DcPH%4I1byVb93{D>DP-zuEk2w@xTGO z8oGeqIkRY`QM>la#I%C+ht93wJML}aFkJaxF+4Ko`M&^O->^M6?$r#|nx%{O%L zhBCjMY&7!dIGbt06!^nL>xQF-JV{vSaT*=BvVbH)1b7QZqA#i9a2WQm(bRK{9K+Zd zD^c$fk6?}BweDRVGwu5g`*ZfJyA$KfXUZnzCAH|~|;tH_0;ug#NtFsxyFs}nz$dxvpn2m8Q zz0f-v&%TjO>Tb*-|1V}{?jCl~3>sF#0%l-3{oW#(2ev41xjrnh6oJU|;V3dv79?(7 zWtqcVG?N*o-?fiiKl3P-tyfDw%Bd-QtudA#v!a{#he_7pq7hbTAtOv^x3-nA|H^eV zhx&$M&%`1x+d1&t@&U@4umn9C=tQRl!7L-oZEI!>vqM*z>i0d0eUq!DM{<#P&rJBSt{jQZScY68E0JyRb(UGj zMZ;qli_5AMec~uq-y@)7dN$z}79l)|qWidTc?wfNxIBe(BV=sQ9uP9Z(s|OX6b;q1 zpry(|Xl(vC2;TY*WvQkiCA)TXB`b?%esGz#m|t^ym;bzMu9f(m_=ml|`P0{^c%gg%&cxOcQQv z!i_-47^Sx(%hRPu$%{sl-Q{6LcmbuF=c8o>+}xbjXQOdt7{?k}O6ODzX1Y&6 zue>12i(fl~w?TUt7w$JUB^={scJgmVxJe5c!P?iz_Y5=TeYq%cq9ois*MxTLNJCG& z`6z&2!A7%_V~#V7X}%a0kZ=)O4+8qJ(MsH>UgUWpqS zR`C3LF5}7DJi$O?7YG^MO{drj{ZFPeB z16D%+!%oz(;Sx$HEk-8$e(Z+R8SY{;0#52tAWk1MSBd%kH(*(4o z{0V-LxgO6zS_T)k9Dkw_GQ!>S53|{8CD>jNg>Ky>)L&hJjH^UpOhXeI=uSgVjWf`7 ztEVh8hhwfVj1MJFod~&(nJ*O37cP}jZGz9L)uSDQLn@| zB(vc&>NL5B4hP&r$EM}5OgzWj6b{-mF{-KjHkO48=+GVKaR<3PEX~rM5;DR~S~xet zXoP*5FdBnl7Z7d)*VhlA5W9=$X*7+_8h=E`Ukso&-(nPehC)>tbu9CSW3m}0?dLbr zv?&Waxkx|g%w}8 z-z+q8hS(WQb|oE$CkOwFuLfu0}Z z7+;R*VVD~7NJ%x<$L?G4v{;Ioq<0U?U0zFHZ`7lXf6BM;Gy6bBf8iLX z*?XW&g=4}N?*p5|&Mcg|8szPS%{Z#jW= z2(t_5w*r0Q%deFT< z7RIg*L|d;8qG@|Lrki8NGt5QTVe(Zli7kd&deVm7lvz&|>0`7MFCcxuZ;B%bnM+HL zg8cp^@Z^vy^tU>Kd)!)ZPC1Jlqd%bf6Z;UEU;rMsWnlV-!)U4t$NUM)kBPwC;0fnFfv_80KS~ z7-iH%Vw=a;(lUm=yy;u!@)laf@jc5gs>3E~j`>;fCjEsn8a zm_s>3C~rhB(g%@)V;IX^;|6Uj!^m#^P3CpyVW|QE?PW<*7j&|)%Vqv7Q#Z#Egv?&= zBOqjWJGp4Q8f;+Vq;p8??mHBFeGhX>s1N!{%FuUk4XPaZ69wsU2X-%xabcJQm!IU2 zaxQi%UqBakQ@ocB@mP)G_Wy_`JL2DrlawO}qv^hO9{n8Gg;Gv#MSrrtVb?DxUNjt(xqHCSM){xzCm1){adm>Xrz6xERewBg-)X43paTlRV*^hef3e z=*AbG)Pc)W3PL|d{8y$;j~ldoThF2T#qZIv?xX1BoN;g~TnR?2twqX8Kaij`oMkp} z&21#Zm`@O;zDws}uM-9Ix`m09^--CENL6WGw1F>MI)w@Se?_x}PDk1^UZHKd$B0gk7BNz@n7nx|MqQ31g;hXUp@o_D z&lC`@8)2q-2c@A?KbsKm_W?9vU@Y*}lpra56XNgsfy}JAO!FPj9z2p6=Dmw3wfjyk zcC$o4^K5OY?P>0${DRGtuyiJeID)XI38N8K0bxQ5tAH>C4)Sgw8=Yn}gCBxAUXF#y zO5#wq(G87~??H);TnfA$$1=AW#{ZBQwFGi7<3a&F*D{;Z^$sJCObufhVKi;)xhf#6 zX~JS7tk5&p+rX^Z*AcI=84ZS=M~kOu!K-beV7kyBMO3z-2UEFA$WvT2`3!S0Oq5E} z&cUA43TU&Qi#+8AX9}t%&r$!}Z-f>4Pw7mq<4R|v&26Ns+k}4e0#Q6uHkVHtMEn|g(%3D#Y=s*r;&?}%Dyv@nsyS>=DNtrCu|NB4po3;j5kg#-O zD|D4Ng(`>Y(FM~$WPL;nA{E6!jfg^*qFT@bYp$jxaLf~ik)9?=U4Ea7H7L~5PbQ9` z3@%Q^yxw1=Dz^HtEr)QE7H(_8-BZZ$?mDsC+M?e%Na@@Qlw%)@?CxuW=!rqJLo5I# zkE=sfQrw-*JdSB#n43GLsPAL)Fl**&NXcJ2Uv+~N&+4!bCF})+osE$Bvq}3oxw5@L z^PIKtaegssORhz_pCXZmiV7^~76I?DGss=`75cV~>(h>K%d?qb;F<)LRFH>-X)@0} zuQ`xoCamD`4y2J6CisAG(A+NUfuH2RdjVm~A?yX3)bi1sN%iPPYb4rrM-y~c4kJmI zIJDmSC9)gOMRS;Ax)|oYy*RZnFAv+qY-lM!f4bd|2vvLosBS> zc=LPc*ShDZ=)_s{a-Ie(b?HJ%tCCP&YZH1!{>7$1J(p?y4DClb}KpNNgpuNw2rMK)ulR;Wf5o|Nkjc8)_T`cP9gS`#^K9+SW8^;&g?7Y9!Gp~r@QzGC4TUdI)IN^U;22$ou}=L( z;*k_4%M9A;?hCxM^g~!-<^)_gH$q030{<7|e<2eQx=&EFSSo$vV(?kDKL>?hBy8si$C+Ro*x1_Us1L|&<; zb`8ApyN3+ZtI;*j7?f?P2$vFnA&0ByQPjY5^1yJUK>-0y_IGX zdbAkk^|WyAlw}kDj^@vx39EoGq5q_SrAr=qtt~(=7DS-zS z6u8JS77Rlk`b8Q#7GaHQwY1m8rP#YIrqqpnW_XFwe-7IJWTNm)bYH#-X$WFa+HGaf zo-7K#&&Hv@Y+fN-<{n2F&A)2eLWY^;KTPKL7Gt-E1$4CMdn|0L1UCMj;@{EynHyoN z{?BN1M&CtiwI8EVM$zc`N@YmgA_<9cv1pg^8{`vxmt_ufDX@}ZKB8abqVL66!3P2T zGJ7m`SI3<9;AC$l>^#saQe~*;&xm)$c+@S4c zn9PyG`^}%T=O0Gc*$AWg zYL-7?4j@vqxJ0unlrx_+1dG{j`vKThL3;`x*JjUn{HHP&Yjj$ zxhim(Van|#srHB>OrbzPPsmrickawzwHIKyOzx zx>(SSEZlaYw`cW0r9>WHc~K@l{@Afu0Ue$h2Mj@5~(S1f;j1N#nuhqde$--hg)g>Ot4;ai_K098=CPl2X!Cha(^R+|BgR7ZuFYkBC!=u7UrH zaY_95pb6)uVAo}&J--J@4xd0OEA`=H<_b`|^8qQQTfnM~670JiXu=iVkd5gx-10p3zmVYlNRilVhfA5214zp z&0uJ808I4kSY|B8d}o+9Wnxs;$`&k|xgahXc*(bz7l!?4HpF*d2xebSDhqH2)gnLk zRja~d%x$jM3AiNX0$Kgm5c(a!Gt?A5XZZu!ItO;dX+vP4IY>P=V40-RY&2pEnYSO# zN>Q8tdWs!k4u!VMaok{d8*f&`9p3JcaER4B4cbg2HC;Uz)K5A?z)xQouiy>I@AgCU zOI?uIKLg^Xih!%cTv&!jfwr;_H2gjd$x|Fy<~hg6GmOMv-^uodx7ZnG&@TEY<6B2u zp_ab0$1RkiVElYv(AEe5E0=I^3UGxa>mXPh;}89P$HBbQ8j_^VVczChFwp1@y~H}W zq`DdgJ9dHCS1Xn&;uuYaS#iIPjPY#2o-*$Xgtipnmy9#;Rr6)=LxXW}C^85({tkhF zG11`GaSSpKg~7>XA#n1$7g%1O0o|?`+_8~_Pdk@D6n+V&D8@ind<@uo2eZt^G3=n} zF-+OxY;xXU7goUB3q*I6@*X(9fSP#lQTB#b!zjp{6#*5C z17KyuNx0&@0Tf;@fnBqL;FaWlSpIS^vMBbB|(8s zJY-Vm;I+~fP+b}dhUFJPO8h*`*NKFeKNl!-b8wyN56`7nLqZjT{1``g*k;T! zc^rcn#{Fpp89BZW>pmr*)$>15mQUy4BA0dW#^=|etM&r4x+TDnV=`D&MZiYSL@*3a z03XRX2zMj^H(3ggr;mWOL91Z%lOSj}@r13Ve&ATLj%B(zW(mWbHs_P=t%I1LUPYTQh^P;GQz+oV=9=( zdVr_3Ba8~OgSZkm7`KY7Lrb6G9G_X2w4vwzA0dl=5;3IySd9b1nArW)ITSN+|2llWg&JPshcfp(bP$>`Z zxNsxL9mz5$8K%BFofPD~#RzfcYAEF-kJmRHAD+9E*XmRRRtGac^=vM5$>&1|oeEZ| zc@Q%D4m7^WgzG_jpzwVh*w=nTHCwO1++c55;3sSjLcJ&M{0xdN^6q9fN&qsi9+EsqsZV+2>!7T7b{5e*~E=_dr#OhJYnBEUw4^ zL0U0boydioHU$v&)Co?QMLRCcoBJDT@+Uhs|25Od}#eq4C_z{prCBHV0s@k_uqrQMSR#ZdI{tv zhJb^t5mbII1vKRx6zyl;Eo^Oppm)Nrsxdc@>MWDSFkM=E$#dnOE!yjuXvXwfjJS4= zFNMeQ#NJiIA%kKl`A`OZLuDYRkPiX;hfop0WMD!O@R$xKZFelxs;&T#egzhjFGEqo zA-E*k3t!Zyu*?EAmdRz9NhJ}aoa-Kolt(r6j7cWARAW28ZKn=T^+X+5{8a`Hst=)j z{6i3XOv1|fPvCYZ4XylA;AvaHqOrm7<)SeZn^eKW$8k_Ob~9wuw8N%;U6wIYWtk#| znNk`-R!$GR_pGFbCaOm8)8~}%9|+QU7owkmoGA0-MIS@_$j4B@r@>038XV+Gp`g7S zX1OxeIO;eMreh&IvIKVJc!9;PnNYX15{@7I#P(^kRamBiVa6UiO9sV+7F3tl(DIu{ z@^3_o7uuk7o=o*!)S$HCna9Xk}X9wbYRykzV8@czSp@NY<$xzsAzc# zyR)j{)1(?Gcw7#GB@Iw8>Jdyl_XJ?`TnGw144vx?;CW>Y>?=J1P1bYa>w#LhyH1p4 z3OMGqaM0W?kTyqFlMT5wbmo~{T(C2h|L{f;)>qvO6(a;-xTqEiM%Tfi?njV>UO-aY zW5^v}1r8g=!Wf;sAh$#s%q#d{>UIczH87>r=?Ro2?qeB6j_F{Sk+p&3v}b|j0_J__ z&YTF`%IhA#?zkM!XVY77*jx_cid|jcB%n~SGDkAza4n$M?v4uc|g5+3vD$QU|*~c6esmV zE@IxFW(MMmw8m%|r*0an&K5Yc4u`i+4^eiMU$N+ck5ZLJ}LTvB7 z3p=DP!GzmYF2YGTIDN7~nhX~$f)e8Y8cbGdB#bQzFEMyE$MfeFMw~rHF{-r&z|DW2Q4qfb40qOy@Jn53Hdd z+LqyqD*7nR5jcL~!Z#RCbwhN0CtOJC206Dj(Ek1z1asSAjCVV@o(Kdj#Y?b|w-?Oe z1Nh%fhdtXb!q4#{#MOnVER!wHMl+XTR>^H4->7^d*Pg7QEht(1UPS@5#B3M7=Hn0; zruD!flaFv{Ll3+*WFlMpg_*AoK#M!UjdvSTT1k*wn+W<7Wr&0U0i^QEVDvO~;vId7 zW#)>p%zTE4Nt;Pp%MFo-cQ7ybzgUWUs`>KV#|Pr`PYi?VgMRQC+Y3IY`k__38(Oo! z!tFQR%rU8(dAaWz1m)j_CDws((|HIKi4vG{FdJO&$`WH7idn`@lx3DPjKy6=GA3z| z9BEZUd$z{m7B-Xldj;q41RYVrOlJ@rWCkEQ;X8=!?}5ICAt;~G3z{E$Kq2B0cpj{R z9;U&H4p1Rn>fbUCVHzM{+ZbY0>ur{C8V(bF>wBG$k(DB=$B9ts#x-o%qxq9%wlhoyPn67C@r^WAVV0*~ERV9~Q?23+_%B;Y!rnoYNNW8B&f=nk z!_`3$r9_D_hlapma1cJ8DFs)@N6?&b6DF-wBGewXz{pL{z)4hxura^RG9L$7W;er( zj{9Elvh6#G4^-3N)^FrFygtY)yw-@P+>$0XREramzM{k^cX7g}e;C52Nf0Z8f5Xw2 z!_YuvfUDmfa4U}izcf+e&fF@%hKnIpOPLTTMYD|gcb0Kun8n4f3L+Ntle?;`>CdO) zc+rWaq^M6jUTH2z1V>5{=M^M~^s!RJh6YjME-6Jk+AT&nYlsnFHpfH7^C(A}kxcS;p}j%Xl)3c_+WX^VV-j*ls zS<4br&PfsXPstGBcO-}!6ItTpcL^eaFG2M7`@+a(FL;r~gDZ+na6LZ-_NT_cyu)8X z)NTXID1K#`AckqGjVV|{i&4Jql0j2*{ZVi?(O--2EpWy+1HrnkoyV+WS& z^OKW`@uid03G;0#M2)&4kuYAFu*c;I)4!C76$j;sMU^9nCk-+n!S6xt5(P*<^fHi% zOW^D-3>L(ffnp=~`slKLHkwq1F>E_s;5lv-r8%~mzHl^@dUf5K|N2Y@Uc5q+SWT)C z_43NZU1wF|#Cb&`C0CWG%upnj-d7-OMs%R?g=wfZ?mS9qh=sQu)4_n!1cBmhi0|XB zy9YQXgJHH9oh^9cY(TaBsG^6HCR5ALIP=do?Z^2>BZ&A;#lXYydMqQ&t(&I|)7$d2z*)wOGAga2pKrc^PkV1pRXR{CuV9BzVaG` zsryJ`@Qymseou?Aysb_gc2XruzlS4_uMPOs1&{Ff&W(_Q{Y0MxGO%n?4Ak#&WtsgP z^PFLVk8dvc)o4bwJ*%P((nImK{wQq7d=!869bH0gSerP1K!ez_a1=3an+DPQL5uih zsX=(es}lPL!;$u7In@019d5gJBW!v!gs$x#3kr3S@V4?S%Ut1>XDh?>Z25i9EX9OM z`dCG)Eid5ZNv-1PN`><~AL|kmmg=yKWEwM1wZMBe++m~1vE&$q`=f}; zHyZ4qjee~`obXU3REmD1Z#-e#^aNVZ~Kwk;Nh+=~0Ks%E2*|%F=3jxw;y^$1w<3 zj(@`+9HT@0InQV563_S6J z)IVKK>s`KQF*jTlC5OO>Qe;OF+dNeX%jS{9mw0vJ#5*-Y)Lw&F%2y&LeLo4u zNlAFY9|KpndBJmiIWW=>hgFZgz}uO-yno7N+8BmO%a0=)&paVTqpN9Mk3rsgJuPIG zbcLUCM~ir4Fp@CMRUxK2GKJ^88j+ZwN~~>GCxUww34v57D79*Vio_HknAd=3O;v$K zt`}f;rWa%>X|WYrm8$}i8AhZ&mYnQ%mPFT>XlCe9Ci+uR`x`%g#F>rb?1$s{Vz-UcXtIMsyxmB=py45=V|J z6YISdh~F-1#9J|WV&h)|xGTFJ_SAVo#DZX$yh$I{Ei4B9&zDlwm!;4c!Mf&zg2-y_@qHxU7|$%>KQ?N9IZx7+cknXKmQ@Tx<4DPiEe|uw?`oI znJh%9zYz=FSr1nYAzswDa&D1N3UZ5ueqqMC>6{34R90 z_&-)8p3NIUbV{fZ6XuK{&YZ7?^KW>7t#*X~dl$%6mxg|HAD*Wzf@afJwhDaYqB+hm z_M<CSC z5kzHW7Hp_xz9YR0pzZWDSYdx1^)mO>64ymw&6q)!QR5gNhFSb-kldy|lV|s&nl^lM zmcMf20Nz;_jkkv@5~hn)2+?7A;#ZOeVVTcxs&Yil6;(pEK#mw&TnGay;&3`;DRllI zAb-L z1QRxzeOxs03_~wxUR0iG&zlxkO}nkmC7my3;xEG^@!n>6Vs)DmaldN>QPZeSJkpaV zuDQq%3X}?QKU|h@Zj6E9xbf)8bP;GhUWvYXUBk{K1;LM~L#V`Eyij<{k-$ZBg<<-{ z#VJ+g!#ve9)%5XiA9y>eb&%Oc4?KtIEU%J^M3n3ZB1M(i+REh!d!95=U(6Jr2pMAA zM^Er3HTjRJeQ3jCeUzYgfIpbJ8+NQR;!RX2$AnB9$J}I?{RxBQuPy$({fDaQ823r| z-umbG(3|~u%^Er4{vico%L`ee=7%aV%}JIxQ7lPB#VHYYt)z+hUzvM>ug;iK{ymg0 zz8}$)JKwR_543+Pp@zj68%-29XxR*dceIf)Yr}aFZcMA55sn`*l0&j#YjBSy8KVCF z2*P=(3=zs~2KBYlM6fz@*3niZ?&nGpH+DII@eVhB$`KhvN4_lBr(;}rJZuYOn8xul zRJz#TWO4Tkn*xOlV&;=nww;BzJmwpf6T48x zqyxxz-imic{7U#1S?PpO5JPs(o? z*C0lyKKl(y#mtq0*)LdguODQON)n2OgV5CK19p=o@ne(EA*EA?aq|@y@si5z?}&rL8#K{R^S9{g)g7p!JREiG%Z8zvduXd`6knLoxkDBho?h??BrP#fL)Vg70EmLo+`g3zq(fsKV7FhB4&xDJ1WQGT0Y z($#eSMjJV_O1g$WuJt~?B`g}oOKTzTfBpWnf9;+_3?sV5jy!j=nm288H9dGB5nG@X zhj)}{^M%)TNrFD;(*Fz_WJHPG{hc5<(h4O924QGa2drrchHt+r@zXONAunxBwDWcV zQh9p|o{8T<>-CPagO?@2U#meIa<`!q*PbJ7=JAo-+7@*2@K=`U z<`_kWxh6V=O!j%j>pNOauQPGyJ>2SzpN-Y!k3Zi67I)jAZ)YpSzv+jH^G(d%O+9n{ z{Q+){Zi2YYH{rpLw@6%U9F%AcBgNI@;IGmLKvYj>E-blijpUe-4D&2v0;wI+%sb}A z>^IBj^ZU~x@a^OF@k7Qm!J3`SlZJ%Xj~yWyvs2mDHNgDEwE5Zv4YdTEi+ zILDW3Ik<#2Vwlve3&`g=ExZFv*SYwcA@wL#l23N7;a||Ng05rCC4Es9L@#ItpPKtH zSJvl?Jn4z$!`7qNT~Z54bSDT!9{Ek&V9cF_f83a&zy)z9ao`eGmL4K z9eMTcD_$a9P20^6;5TF^^DqBc%im~T0lV!VLD%jIu$akQ3X?RHgz(|AV>K);F9FTM zSKw)r3g?=cC%tcTptCs#M)7|_{L~8Od!R>HW^E5!Ithkxd2pEg|HyjtsG6ex|G!e2 zNl_}25Hg3*J?A`+%#k5;rV1f4WX>EZks(5Q!-^%_`U8q zpZELyUF&BpYvB)%UVHDehu40-p1aqtGNu*n1uA`72qxQpDax1YDBMTggq7KK#BHT0 zLduZ2BnLO|UWUh|0;CMhMQoJ~1s?2CV%t%*IUnsaK8hGu z!ps@(FFbpEo0;=crL;QzM;748=PIK<$<-HZoxS!vH6 z-r6en%#NpWy8~C@vP2GpvRnkNz619unaF&59;S3#_-g+}>q>KE}*CJ*%VUBbdB$zYF%u~t^{{5-Vcud=n`{{_0LVb%HT5*}O zwsPctx&;H(SiM9CcWgQn1o|ezxC*9GyzL~W#HAOzaoa0F#d#jkSi06t_CuPDWz(2 zwT)te+u_`%>$T*W(Ml8qXCqW`Nxb)TN;)HAN?k4?-69jY(cif5#p9sip$Wf}Y4Fc5 z!HnL?T7tfodwxmTnZ6djnW;p#4n8>oc8(|Hv5Uck+E3f#;}5iwEIvhd(zI!fo= zW8c0SfRgUhIsZAwVY}M`RRi9!7TaSG{-YWdOH)&%d#+Ke+~kJlVNY0h3cE<;L~sheS}K+_^e)V%q?PL?;M5B zRu+?QnQ_A#Q!)F(BoX5(VWJ45+cZ*$|9erEq+6maZEh>XwOg0#W1?jIm*-N_J_GgJ zGLUocBAmJ=K`S&9)kf*aIhF#|3syei!$36cYsWSBp}liQE2Lx;%R}-~5J$zh>S(S> zLm+`L{g)jS(&vwrwKpzN_Ost7d%k*l?)s`tJcy$tg{>9b*}*-#8J5u>>-VbTes$3+Rb%EQj5zp9iM zvs)@`jVI@B{;bJXzZ6iLo{oUoXW%h0laeH-u;$-c)b1iNOyDUbzK|>YlspuE{kW5# zFG4$^8Gdi+kUO~Y6t*eca@EnymoS$Iqf?nJ)NLM`Q~p?`Z0K-TvG+sA+%ChMSobzL zaNTwW70XD8GViRY<@mlJ9ria*p;~9nK4inE(2o++1CRb>DttaK5i~>9vb6xS1mAY-*RDL0tMt1kkxZ z@L?SOCLG7el1_@BO-JL&{a##MX)fkFc1C?wwxaY^2GTS=MNE=}xl5Sx&u@iC#Y=?> z!gT4}U$NnNgyQ5i7uL%00(_4q!M8CEu9?X&$U2VtH_7-g<^;wDM8hJtD{H|nKtjee z?sNA`IF50+UVnn^kVNyHLwgYu|3>_79uUUK`=bzDzgq~8Q7O;tE0J$%9E9*kweaqA(sg^P=clC=TBKQE+DuVcN?3T*dXB zU_D-NzJHY1@Jmz;sg*5%#T9DVwctqG)MQ$_z+%W=jvJ z!o@TJIUkN9Z&5s&4m|?X=dq|>a#Yl(b?TqPeR(wkd$1fvVl!q{b$vl+3BGb!*=oO>{a4IP*QgVyl~?0W=A(ks19S!sA!I<=Y5~d8Sf|>gy5%X2T=#3JKB~@00}L z{dkpf+sX?vz1w5C`ccse(|bv9-A;|>cvx&S2Z~~8{V`ZAh(z_Yy;$5;7ymZ9V)8j9 z=T0{sH>d7J)559H>Us%Lm2bpGn<0Ikri3}vJy>Ytw@R2r7b|mCSLS+HhYJaVZ?k!; zPQx)h9;Mz9u=<^VK;KAA*?SC8e@THynAG*!7)bem^z0Uxx+507Nq%KP*Wmsas?ok^ zz8FodglR(=a+ zypMs^#C=#Eb_TburlBbJ2%L@=;=9XqvZvk%=1UxGURa43YYAgdnB(Ow&Zw7rIGb74K8UXkXRRu+mN}>>Gs9soP*=c?nOAV=?<#jM!*a(q3RFVHO)i3OjzamW_5( zDfb*L9khxJB*pS_#pf0=LC728>#9@ zpBC6Y0WNKFq4j`fXA)f2zd4WGrLpLG_!O@1UI2|7fpkH<6n$p+Asly5w`f1Ijn0dh z;A#;wjW8$9PZK`Bi$HU@!CH9^S#a;VESop=kO=BYpLTd2QF9A;+!$eGb3FA$eb-E{nOIPz{F*{Yt zkq^5meyse#t_e0~0{UjdeeV_29!P`1xZC($aZwap{vJV6I6_~{xP^9pn=pL!F}&}v z8~(#*AUX9u?jPSpo8J8*=Jazhnk9reJiJ&~?DJg~6G3NB+pW3VujzAEAujUJ$vN@Xx~EibXvT}JwQ;@S_H}B&?b35v{o^=6jp+gYXK;alSF+7 zB+MGZjCCj%X8+M=rkeDrq$S9QTsZ|RzXyrY$fQQwN|?H>5r+!HY4hd@A0V zjzh}Ur?_gp9>La9H09Dr3nfh0;GIJ1JZI)qs!F+bi3QhEnaUm=c0pG9>=qon%b*pW z2miDx*loUxBDn&gX%FFjT7l&2iQuo1LF1oMIF;EI6%^+Jt@q!%cbFoy`U z%cQGN)Xt4r9j#Kf-1CjqT&>MjFL#v}^tcNTt8(~WxP{CkHE`7~LFPl!5*~R1NAEmb z+Hw&AHwM6S?mToDKL!8pPsb*+S{SU{1>0_cVx#3sm{`KdlWKDO2h3tp(^bm)UK3fZ z;@9k$`{!j2lT~o(UrB06(hHiuh0BEdh^@atQn=?Ru($=*l?=wCyW?2x7?7MBPIN*m zd+`8@+(meOOgiEomM}?#nH6p<_&!?7$aARCHs&afEKFj5rmtoyPzLv@&k<-*g4}`c z@!@ni(pwhbd(lhm)xHaB_j@=xVlLWx?Lqm3ZJ4!=>~(72A<-xl`S&H&(0yqLWD;iG zhf%_)b(@$4*XbgkO;9vj^^P55m@mux{t*6cULtPseH3_n#_Whnykd)B+MyP9Q&iX! za1(QT&BDRpMd-YL0p7M4j#*|^m_>>Fi{~W`)MIHt%Ly}J;Rb<;+sO>OO(X4Hw4&=2 zfA;2*&rHhs$D#%*M_G=PA>ZJ7?m6=8OJO(c1MKdX(Jto!N-{Sh+A9>k<{?Pmv zU!$7-oc~HXus?Ywex5f8vv%hZA;~a|*;J@fR)xkXLf^-;6Hhj00~c4pDzuJdij~Oh z`wPyL*vqN8kH0<6_UwyZnruMV7cemYgv>_jpV~%fU44V>xN>OOd2!lF5Zl-h;b#(sxrQVJZmIu}z@xlsUpYxT#WJ8*zetU>3|? z_hnh{3$IWb^#yr0uP{ia!Pk$eL+JEMF`s6m^_+@lFGF{XJIpqYhs=FG=C7HK10-eK zcQ^p8hDVA6`rA`6ni|4vZk!_c^U=&Ng-SWPCYH^+-HKg!Xgce>q?Y>P2lATNqK~E) zUz+$4OS7IKy|EE?^);|vR*5W{zg)Kl!Fk9r++VZ@2HHRHvO_Ye^`y`9vJ}k+!kCP3 z5U!q%W)56bDI@b!*u~w7n38r&ScjkQk&^ivQ8(VBLwXZF{8v4k2G(FyHx0ho<~QiD z?k-mESd7HhYw(fO51|R$VSVa7aFvc!sVBr}oF&Xp!ZiJ*FDzaY%Uq*bprc+#*1NK^ z+|_9_TfdP6V~hSGeEVl?o2tWa4*HIs-(MrSOp~wBs)N^`mA<}@3kQz;E6rHF#v=RQyiDAlUA$a@TLcTrHgmLJ%hpi^TSlg!>ysz^& ztZ%E!yEDIG6Zj4%qnhwf>px;lC(=B3Wd|Cvy^55yGpTd zj0khO`#_=McQo^Ow@O)D>@2@}bE2Y1c7XLb{1dGbw0Q5IKT&u{k9U|y;<14r@n?t* zpPBpxnS;vFaqS*d58jJ|eb2(7%|YA=`Hr6_FJY*M`V|VYuXrqC%n5VgvYX&^_!yHI zqEhxd-B`nP_{}?uIbR$}A*XBKTG@}1<13oBGga6*;3%=>=@+k{`Aa?<&znylV z?YRwzicLU72~C-;o}y@D8oHNAjh0X$Vr&Uh)Z1H_|0IgZpp@$P{Ws)$2O29LcqFl* z5C8G&Nu3qZRzpnQuW;7l>tB7x^t*a|`qTz&-|!HfsFMI1uLV2_K)&GyB8b1}!yEB~+%)+`7Zqr? zWfi);C;MZ^L|m{7!o;vr^lX-mn)&m@Xd=tSM&k(M)P1TDYZ=DKC#aM)9a%;>*i*4{ z^a=KAhz|e!havxsu7s8iYQdM+>GE!Nn*1qExhi0<81tt# z>57+L_wVTQqcxlGF}IrY5%;zE)pYIPw`UHrP2JICbrKxst%oBm4rNO+@NMyA5pz~* zGGaUEvs0qL}eAj18(Y;76sj;J4)(h*#h7izu>PO~pIum)-RE!lg%O&U1vJ&at5VKdAFYUU{GeE}$%n1nXv7zK znDHfTjClP*3qHcUIUnhyCu*S7_nw+g`*A103f;QdVdL`M74EXOSwqtyf5mer$xL>vdrW45jA$%8Z%p!3t?f29};E{w0AdLO}C}D9QXU5uC zr5wn)F>>cGir6QPqC|1q26O&f3h4#ItoZxw=~Dl@0l%2B5Ji12cdRDs@VDICjX$^; zx@t|?ppEiwA@HJ7$JjL`BE~_QY<3W)ee^z|>m7T>)J&!9wxbtwCg!=~Tk{sI+al5n zR$B1wS2pKYpRnfBCYXtOfmV}R^E#16{FpjV{JUJr9oX}jTf{Ab=bo?JnEXK0sn%g^ zO{s{9lQ4S;cKC|(TQV{iluefHHbL=C zi)r<b{AA47fMvyRZgh{;+zYMMF>dA6EW#e#L4CiVchyg2u89(Sse9E{?k{A%+fWARUHP&Ka-;FhU&a|vspfu6nu|DD88<&L5Y00^vE1j1i1{XAvI&#T z#|WJVDr8zT(z5+h1)Fcf6jo6|@>vH-OhNiIH72sB4gYPggo(T%Vcu<9j-?IdTusqu zZne)m-1+>GduX@~!`m+g8=Ws=rc0~m6~f#sjTYi7GG(Ro-MGmu7;n#P`RDbgL`=Kh z*8GG?q=6b?!!JrO=Re07^Ea+r@dvvZ^Icc2#O~b>xK86V&?CkZQ4@b~jrMzSt)m}; z9lwc~*HSbEgqhH4zcBE1sw|8!4Rs8g{Uum_Z@yAKtd}XD*3+8r|FF4;X*g}pv)U3y zpM)2ue1nkZsp1MNnqgkuEX>T&K#=7Tbie3>AzsGfoFs8X)n z^PYKU0xJ}5+Z zW1T0gqaM&^G<%=7O+v%|CK&#( zH#`TvhiD(4^Z{Yw zT|=fT?FBw$r?Gh(AF`@RR&vEtTErOPn-RU=`n2(#$a7NPkKN9H!ARO_`jGRi*sT$e-#nR@kn$+i}?>J#3! z;Y&1HigKRyK9-`KM`!UZR3}(rU6~vDx{iZ(ZD$O-Q4PhTS+Jq{X*I@E!gN$ev&dgK z7c+|4Od^YKLxLFQhdDRq?@&gq8Y(Qe;4d6E$rcuT9~knZOWW`V%1n8;U)ul0ylS8W{KgiTMh~I{4|PGxnI1^J z_XRu1<2&${6wNfLZ^jU&K5)CRul6uAxQ|NNn6p#(xU&`aXl4&KO-{R*7bLW#iU@Vz z1jU*1{Ufx+MpH-QwfzkmueZY1owK3Wb1=d>b;QIgzp?cFFs%2H%1S>-(M%zX>e5!> z)1x@%W@nXBx9djcLWCJN(B6@aS)tD#xG7=OBW=qrQ~vTWZGO`hsnL$Py~g)(miRKn z3-u>^;)aeTvYu=3o9DB5q9eWL(?Y^{5+>-t8lkCXIulPAf8X7*H$f&`=A3@w=5}|Q zgi(K=ivt3<|eT=2)RH9`{T}(Hj~_t4;+f_t-? zX?lF{A#-sEsHaYKxq{!3Cj9YMR^mw0nEw%p4jR}KvJk`KEm1ev9FKH#`0AqT4sv9l@fHNOczcnB?P zL-lyS#4o^VZH&1;AAtdO7#Z6NtX~uU(i3}p66T1QzEY!w5N4v^CLuQLKGV)br98f7 zoKUl;l+p}`mMr+#qf-poaZG6Q6Vm>}w%Hecl04z2y9L*Wkz6HShYzX_1Inafm`D3g`N4@7^`KBsgrbg{IWp* zbzWlMxJa0DgmFuoC-m4{&&0eeR(4B1%$OS-WlugjAY#v~9F{mUL++_RZx#T71xcYyN_ZKCjJx!;On?xvs%;asCZGnl@e! zuP^KHBWE^4uh-HnpesdloiLT3<_d3W|1jp2RI!rqFekfo8(TMDA$xAF$G1Ib&cCIz zOr^*FFbDFidF3j7{$cyCRA=*=a~SD~0X>_bdAuHe9?;=U_nP6(7%3VbDVid}$me+p ze%_jF4K-T9$;ZxhadX%!AAdRjCz@|}jQHm(|A&cqY%OYTO}>1=Vci$pyWO5R_xC3^ z;g&Ay19kX*bIh>SOv0R(Fpmhcs@zNH8QX+C^Q>4I7;(rs>Emejr~hu@KbSu?M!fN% z|6%;TS&Ic_vo?I8`|4-hluR!is{hLQPt=8KhYr7~yBS&^~T=KU9=V?k$`PzJ8q>ajHc$~G>!EUe%$@OYhru5WJd^3d zY&)&4zgl2}llqNX5)3{NKhHYCbQw5Bu;`^r?g+(7PlXqgH`kh7KKX~B?i=+;`wvDv z3;YLj|B*h=UHlA%)`@siMfXSKYi0;l+Vs+J8im z5T4o~+j#Hof1^no`Txg^`k>FdE`5U*SF*W_rX!K_?*pgZ*y6fkCG&WXyj?{CV>{-O*f;9*!+)YtrytbOtZvqZS2x<-8Wk=c z3gkTGHhBFqhC5exmJ2if2-iXRoO?|-vC%Rmj16JlgiIFRS{kxbeiSP&Ri(>E&PfnV zLN5uUe(UnfdP^9yw03;SrxyI6?Em#mN&G!*N?glLEN+L+_bzblU6VM&lux+wu!<}C zVJ2e6N{!ZqFcY$;3je|l*~8z9mA60W$*0}B&s^E8Be40pVojlX2&iX)3%gtJ{bRKF zuw-jqJ<^_OtH>y0IVbDa0?VAjxqn)RIr*Mf@OgBFE9fOzOqfa-N5TY{&Jw;^7_k?0 zRLY!&rt&u>ON4woLs{f{U9m7m{drD&Zo?-JZb1nzYBZXm)sxMOiFa`C$Xd>SdmFTi zxWNr-m&RqO-XO8Dnp;%%MLgnqN*IPP*KW-g5=I!YJ!z5tl-gUiy2TCVrz%{wtEVm> z@wz3yX#t%xX<1WepwuFAbzUIZM4#`enTN6`;LZ*G$ng%lxwB!bxp|3C@TSj6ZuA{( zvC-0{z8OxKO`pAm3`1k~4P`lAq;`>Cd0ste_)I-!5!K-O4Qwf%2!aaQ@?I@X`00~0 z#Vv<=k$&ZQ6Z^Y)aDgrKu*o))vl_jhGn()i+CCS#KX0V+IBO}I@q}5`uvmbnF+1O! zvK-Ur=JXr?h?&&+n{1d?Q~v%+viqev0`+$ASg+>%@sk?7Uq34ROV{Q5_D@B-`d#dY z*>PNxxz?QjGkfl6L0>Ye;L3%iqD6a zc{2C7P$6Q{B+NX*obR7!Sr9W%Jyq%`av+G*$2U_U!qaIoD zJ!Hmw$`7gl?_eR;5wu!-2D{OgTkrprGcVo2O$>D7hBg$#s62+toBc<`gh`mCgxSzx zg|Kjz5v%DySKr2K<>seu%5$5WGwo+I;s1;_;YZ!oJ56y2+>!cb9bu*qSSyTsWXR5-^n>rY zF>?PC#~6>o-ArXqE&g(GGd?V%Dc{MpHE&jBz;9mh3oO;+_V3<=-+ku>UfL?SxksDf zz0Vu2RgXe$?%5|ea<+kcK(6HKg+N=v1QO=SpiP2TmJvIEqVdnqk^5`5XA+hiVE(++ z5NkXt-F5hqQggoZXnpZ2LS0QX{RItd%~IfP9d|Iq0mh~#*xmOhS9<0do~~~RlQc^a zb4Tu~m+A8#PB)-g1vQQ+etb6R`3hUYZ#3nxC79^*5C|db~^US7?S( znRbu{-}7z}6zg;_Ub7D_o3#crQ4ceUUSL{6TiAz4em3`|zBx=7!!^4E&3YsDAf+ER z=6mPl1niI(c09%8J#R!OIv8ezYw<^((YbSVQ$Dki%$H0}_$kBxV&dg;I1M(#VLdlE z4RA!(Gjf87e2>2KWx&<}Vl)FJ%n8EG92_Q`Ut`4j6XrmRNph3oQ^KZ&Cm4^}zmYM3 z%6a-xB|ep7Uu{Xdmg0{X7Tt`$DKy}R>oep{=z)W^6EW=ONZkC{lX3*#VRdIb+NDU# zT2ZOE5Tp>M!Tx|S%h!kvrmG0c+KKXhvh%`k{XsOa!_j&XmaUr&{rn+_X!rtEh9?G1?I}hRFJaCTCd(m0_)%!cz8p+K z<)}x(x}jn6^r@p5yZ+zN_E1wkbn_qV%5BaE#nKUJ>pR3y?OJ$~ALx{S5B?>#D6}6! zYCHz+Cp)6Ui|2@vk3px|yoiY{5u?c^%$?2$g}?a*Y%h1pK=oeDIQaEeH2V%FlmCig z^K|&y@eR1QkuvMNCa-oGQQt;cRenW7!+pF-mZ9ZRvS-tsf}Mk$5$jijW_{+Mm0Nca zGg89j6UJ~|xRBLdpT!)i^y=4#(YRYHuf3$lxQwZX=0I&eyw5Mpr!{9$R}J3o`fKRB z>GOfl>v7&GA5A)RLxtHO@Q24@74;UfB!0cE8d9nCjCXsI0^HFFwbut5*FC#u!+HRCq12$S8f}wnC6xy^X>Q% z-;C+rldf5-9vbi!I*p{esSz(Eqi%k{j9GVKzHtOpmQ#_yuSCC!)8RwB5Ha~Lv`k%;YQH{4%+I*ZIS+NYbiYvD#AlP;S zTnx6NN&YxQ`IX^v$DMd`Wu(|>u090}lnu}MJQ(<$*6E>?4VEB&tm}F9fT0R18S4;V{OevaXgqiu~u;AOQ znpsMvBxWsB*fuV@xyxs^lxz9Fg~5z8--${wIch@t(MGG6L_P`6A?W zK3>#B!?;drw3bq%*%9Wi#u1@0<1V8h0nDKuo8)1wHF9-&Et40leS?7YRPDvrLgBB? z2Sn5(Z{kz<<gj z75sN!W#S*JlrDj(%>0<a9isf zV*aegpqlBh-j{%$sdPcSEe~5`6R}5_CJupiQr|ccW)OQ=DAUPivIwL6Gs^i<2g_WK z;`Z`zqc`x~`3tTTRnR&bU4@@Tj3X8Ng;Tv$-#q$_r8ClYr3^R-@Kkz)bfu zSlDf_h}kOj4Nn-w!$ZQZ1Idj0E4q-((U2u)w9fVY>n>dO5rOg2VII@N3zGcR40u zOqGA(TJRj(U!BCbtqUMKI2M|l60n6?fR9_V@nCZ@rfiVTH+fPtu7t7t94dHCjb{33 zlqeNL3>e${cDXx-bp9{KVDxKDKd1FyOnsNXaOn3O)z!x_J$VsYSx(1`mdUu$YyoT& zGtv9_S$w%5oo`kYh$C$hVFEmN34MF-WyTT4sUlTY-DsN2N0;ZQ`$ip&>4#UCc;tVW zitB&SH1-*W+k_%yr5h|p^n+jV5m*Nf$F3`}IPZ4^`6bf%hLJF{33D_uSO^=ijTzRm zMEUf#6B`%SBe#pGnV=qNYD@urBZJ3C7`5YAPEV4K40?taZFa)RVH|F4?g1~;V+hR| zgV`e@VbM1lzs#iDs5TO2Az_Bi4H15KS;Ta0MlOok)0m`1jfxXh7D7d`gvrc#iT+mq z!z30oB5y?%zEf@52t{9<)^Co>siBB}JqQMG_MwN-VVF0O)ZK-5#76Tc%;p|Dh3Ug4 zF?MZBlrCE3@`Zy8b5)S$sYHX`ovQ=BAU?}J|*5&pRa;_ioG zjfM;xe8cdnWi|5~gnC2I2K= z2gbO4iE_ODXra)*Nv`3#gCfRz5>-QzaNHcxN#l+h3tt{sXQLtI$hdgLgOn1jpNt z5xV9lhR-NR7+R6~`y#jT*IBObgmEy;&gAqX2ID;G3E%A7BUVLl5+;E#$?HOdmv(Pt z+kaD?bf~5L5*MOyb2`CPysJU@?C*$5s)SbHU#vOx0eNNRup>LLOw|JVQtKyTh`3FEJXGgh?k%wbpha*}O=W@?ND(3QrNd{2wWz^KUX9 z2diNa@fG!#D-b%P5vDKd;Joo6Sx?fx8I{53r8eF?4dfcTALj}$_d{jIc5cbo0Z8@d z;n=ach{=)Wv`d7!pSNAGYdk00(?F$*OB{s*p^gfV!`_VD6SB=?>S0CRkWU+aAvClW z-jm8ud;2q-a#ZLr!~ojQW^*=+cW@2eEMd^+02d$|ihg4m#J`LeF~g*VAdfK7J{yF6 z+VQe8wJN0^>ntBUu!F*Eb{tck{sgsKKEmC&3@-RVB_yvg_NoeFDPiK=co!{99dX<# ziL;2T;OrI;LR*(BT;T#=+|rwX=9Xn5W}1Y#OBjEHZNi6k(X#6=RLb|+R}{@+G}+-Z zrZTmk9*KfWk8vt8I{gas#2TazDTIef9bCBE(EK+QD@`?VVW1)EE{{a3(m!03aS%rI z^}@r|O~i#jkT4GjbM|bo;2RPrOQ6!lgp)fI)?Mt_**FcSJbmg8`LQxOv>VV)7@R%p0T zo?H$qj z<6tVDS%ALPJ>eI13cnX^BC((3M6QxBwS?*T?zqq=2-E(RXV`WSYboVIs9iCSsT2IC~U8Ya=33BqYDT^M79?d)A zH!~d0&XZv1W{Eo&6VRmZ6kNC=MKeG;t?9YZ_39A0FgVMYF)yV7ox{rG?DRO*bq|@< zoU5?<@KCJxv@x!R_uXQYZn=Q(C(Ffp&!8pyaHhKnhLN?=x-K2jEA=;*@H&nRntEa8 zJZo_XJd&a@C5&m8%fc_Sc8oXe)5Z^6r0|VA%Qk)vmbq6bsE&i&Vdq?g$0$jwUU4-8 z9xthYc{o{4TEt?qyA>wb4#$T2;rKPTgsWH+izj<+@H<&g#GI2bZ3r`L(^Wwyx;qm? zmBqd6S}I(p8*&Q^-pB&l=fK^$1nxRijG6lcPWAby?VpaQ_GEb4BMnJqG1za_0X=#G z?c3VIu2c^T-k(E=lLOkyY(-3vgs~^g=K(i`B_#~Aw@RhF+H0=jY^EO@Rp!G)-Ofg- zdlB+RW}v55g;oi4I z41*1)0j+ejJKG5b+KVu8h74W*nZuU0gF99a#c7WrBBs5ResCsC^0*?Q;_4(O>48eg zU2LI9?{b`7zM~oA@RE$Q|Ky{(#~B!Gybs6iSCD=;0S}(ug-?r9m@mu5al`%)uB=2% z_6TggY>4G!FQTd!i}WYMMND%EGn6oMUgiro-KH}~o{_ZI?K3m_?F_bP>f) zZ<6z93KB2h!_E%5^i)e6d}|9(YadUp<7W}DsSCC{EJWpAXO!;l0REL6PWC+FY$ccY z+Y)9hVd}&4h2UMDOk0}MKBVXiQT+z9#n~4bg9B%1cD{kQ)g-2zR0^wJa-=*tf%+Zf zcbk6_@yvOQa_C3)Z2m}3VX$OKDrfL68c$NcbI-m?Db)fAGmS8P_ml`@yDns6zmi8+ zR-t^*7%O(_-!LY}F%|W$*Wf+sG^)R;kQ;$juUF%eR~kW&F#M5m$E= z^{o=&e5)A#{ADz=jfMB`oA?`boN7A`;Zy*i;0qP? zMc)vMmIe&iinBEt^u&%K@+;(=+-YAkOz#O%&4pIs=Fu=@G%~>0}2u6noX7l$56mtM}SKV(vEG#B3*$Sm0}53 zi`U%h55u^Y(c7?cO)i(-=BkJpCS?b=5@y1Ihr*+LKc=EdiE`#uS7v=e4P#e5kx3bs zD4J?J9Ed|y`5nc}aOxe|rqWev%QxurzKqy-xPvX(^|DA)f1(6@>3YE4edT z#UkdY6ip~$_%HW_mZpA;*Jmn^I~6J)BiJfzb~a%hYZKt0N2BZ42{>C6ATu`;H=9t| z;)^R{LD|!*ThM#QU2bh-TLj$Jzz+QboZW!{xVXIJyqZamZC#e4IYgM@;Psga%gQ-~Eu0ig1I)d@H zkAtJ@C1@GOf}4I5)w*ZV%>OW|zsT{s+Yy-5Y(t36ckYyBN5oj!!q_~Bdsnys_IWS4 z$;+e-6fa#!CJ|=o*iS;2-kywo^AcrUwwc^K-%Wn@MG)ig`-E8dA2%`@Mf0x1-z*Jz zW)biy%)w!*noRHNiT8R{oP&c2ycTPd@6ZiSWA+;CA)VSh|0iNJrV=KTF#Fck2>aJg zWg^>^D0}u^z_xadRy;f3i>alGVs+uax)yi#@;uazN~Ky(df6iJ5~`0L#Ff9(@J;6_ zXB}#amXYmoKhTG3_std8E#Grry6+P)9@3q(oG_(3%Y<{iM>8gLD0EB@W-nieQ~16e z!=#*yC997t6xc>0*M-F4RJ&o-DIDC0Y=o~rfI$LjHgflI&AsZlI(pTo=h5q2!P}|u zT4n`{Pv=BTsD!ymnC8y6g!k83rlA!L=%tGVtAG+k(yv7_=cVKmKo$8O-H%}G*jyNR zou-}Ve%!P@kH4GtA$Y4Jo@VB7=6^LYXk|P6+n>j6jhlcPn?5M&BB@mGNm>pSVcM17 z62|ZC&7^lKQI7FDsQB?pQ(@Hho={H(n0Co$#Uj~)Zvr+SIR)>7`(Q;2b=-S;hoGFY zv+sU#m0NW2cW5{Kn)s26J~a)UC-%mrO)4>(rxK<@joEomaB}R-ggBKbKaI9k*f*|K zeDBmk9!Gr=*CHL^rw@t`1=Jp+de8oQsaWYOtUB&N{n}B8FVIJxZEHlY8ij_+f81@2 zIVf2>947Qqrh19EHK;RFuBhk5HP=T&qrqZ>(fCJA=d(yI?YN z1o@}8gUfYuq}qDGZbl3IV?2=PF$tp&NiK?er6KT>FpF2!3D=wIF`L(rTf(t}Y(vs^ zMbf&pau?5|DD_A|K+FB2TY~w^;|PDU8{X$q;JYdW6%3Dk3)@56xdq(b&P1~{ra0VX zHrP@hlo{3izXMupEG^O#D}_f(8fE*#N|dJarn7nR>lMyAqvWQYk0R%LGTg_|(=8*; zqkb%XM=87ENX7qui-VCA=M3{Ht?=@33p{E$2|<5b;(NF!nE)-uvK@~_%n2zPBf@;^ zaZgBcua#+@Em4k5&S&4R*r%vdwiYo3c@if3MHXt?(A>6eH*9v$_j4*3C%^Vb)t6SV z-lT)6rzg=9@Rr!>=z)g==ONefrHGj>^^G}UZVW9IzBa3n^(rb+UYc`Eey7b0#n;2Py1kJW0!}@U;5j+QVHIj(@rxcAX zVT3+aLg1ylvajz-l;;x{DjXI*k)PPMKycW7RIHO$W7eF_5*zKQ_8u`BHO4;I5z~@8 zgPUdm<(HYb*jEdV?mWGXGXt#)E{oAbNEipg1oW#FTDDfoe!nhJYOKi-`e$n>>Q+4w zTs~64f0va1Mq_7j0yzm1M%`$)uh=7dLu)MF&=gN*dtiI422Oq(h!)RgpkG~vh^dwu ztsh~W>}!NSGc#n`FUbC*>udInX1%;-xIN{O+8P zxlp6k)J%~3Ogtp`Tx!BbZHaEDC;NdE5^$E#Hd|H)U$v~ z+66pFBHItbM5R!K$sq`=9FHNpY@oZe6J~swhW*wi2pQmm2+YRK!jED!|0IkLVKy7y z7gi`^WJkW2DEBSk}h1gC={Sp3?#!g&?nBJZ#c! zF?dF6Bx<KTL@>_SYxnMif8!Hmb6&E`OLv;S5GQ%4#&CvD=|~6leksiEp4E75a#HsV!JbN^_7@1$Bd3u_@_JgDj@UoDuy=6)_D;6O85ubJ#H7VIF~;H&ENILG_#{{+vbOI7b%%CSi&47 zOt%dWgs}maWgXknlY8R^D#Dj1$VMk+GZm@ik-}%t2`wDHU&;HaC%wA#V;^dN(lbc) zyW!pt44Z=X;5^3T!=PzcwV?$L>K?$-NmFrfQfsl%21|2V9ARb~RS7F}ugVII=p|W; zQ|#vt6WHrBHCdN6(a4)mt~{l*H`^_TYgiI0e(s0w{!9dP3d6M-!Du9E znaA9)iKl*BxE7;zq^oZ?33G-phNX{$TI*ujv=*hxE71n*nPsIy<5vS#y@7J=bsl-W zBScdM_1i@1eOjsed3=}eh3l2WI3Lmr3!i%8^=eY8_Uw(3!xFKUSx%{Asg7X3gvln% zfNv_{*`Z3=(Uvrzuh_Dg#Xp%YqZ*hTo#V7Gy8xGbdOpmAyf&Vt!e{$IaXUDczNL?^ z!XW!)hn3C~VRCjP+II5Cc-eJaSrLUGn{8sFl}a=86?LQSRSJ8$y^@WxDOH~HwP5U$ z+cUMxZ!re*PQZ$sd8@x270t6UL4$i(gt)oQSrd+_c9{tBoj^}i?7+0xK(tI6j<>oB z4Dbj>rlFsR36i2IAWT+#t}xiIR(6LPjox__nr_Hp*DbxsWYY1eU|0^EX~b3MU&rqo z=is~Y2(*WHS3+>`8~yOhD5Vgn0mtWa4aStC@bcn zJv~xaY{Kq&o51?FNMIZ~r@?o{4LDO&53Z?T=OqXCh>p8oZ;4rs%Vrm_mj3HqW7go< zoYh#`d>SsrU&n&cl+h(`74;rET*5RG=4tE&!S#A4=9FWpa{09#>}RVc?1$eGjKdUi zPAbiZLs1HDjw^%dd-72Gc?zL)f$x!W3TbIY(DvJk#tre%rZcI}TB;}f_Y@o#i)W+5 zL`;l?X*y0r!+cAsaPV(eCY&&Oaktq|+#%NCIG74b*SYMvD<--!A3sEO{58~OCu8=2 zVgxKpM)~PH{8_yQA#H;3z&{XW*O#O3wtHAbR(gYdLPSi6G((#ZX5@eqg26&ZCYxT5 zTf=~zG?7tcOgze{&9kg{mFO}O8cx2D2XCR^cp7rM-oxfOX~_4J!$fmBrj_kPw=TP& zy<`$RTB$H%_W^7zm%f`C31dYV%Zt%MoA|!Wwjrg;CPw+px*xM;pDWUtsFCzc%Uu$= z6l9CJ&JWw~z$QEc{-ekf;!Floeb3_8`0*IrY8eo_4B9~~+{ax(!jDbpFix7&>?BM_ z!YoNj72er0%p{7&@m7o?{+R`9t2sb4ovR3xGPia`l=gO(GPlDu9wV^m0_Jv2M9#xL z$ZI_psqGfP`$T7)^G}6qI&-mVc|MlO! z>-l<~>$;xT6eIU5ghPY1n)5fpR9%N7xchQ{q2m~>X7>|E`R;|O!ip{ZMJrr^ zOWQ{@ar7cWz2Cr{c1Kwa)ktGOO=H%JosDB=r&5%#@0TlwTWi853u`hp$5kDx7oR zvGWD8zU1KD$_zAfo{HK>H=_HKAk36cgW3H8Jk1P)dJESAvpHrAVKlS+#7=qxg^zP- z_v-Z)@(CMS3c{W;85;|lcIP=vyIsY*4YMk3D(}^j7 z&%sv|y2~ej?K8&E^0{SsR7BDLE$oUfV|}eBI5GGD?%t0<-PxJg+9eb^kH5oUj~c7K zhDn&mJf1d(Fr$SaG3BkRP@4|TqzAYR!Q)3Wt znWE`6L*P;T8C{xWAx^nl!o=_#!CJxy7mkX`^3j6hH2OA&uBb+B93*d@WhZTq3p-o^ z2bu&^eC8LDTEC|EW&zCosOiGA5b-kl>Dq@vc5OE@U&Nr{q0K0m{Sun&7}!7NQ?0Cd zHfk$js?Hn{Kkt|zoSd%JEG|osZ|-6s&~!k-38nD(^aXY_31-OV8p^Z<@8FwRB;};z zBX8qmB_;Exg}`QF7*<)+^fBLHlwSCNadS?i=8+weG_JgsBa|>L&IgJ0A59QU>35U! zYPH;C_iCq>6`usVtMoIZQOD-WhqyOON9pnBBb?=TkvsVpW_+amYyOuo>D(%~zTSes zMiDsZON&u!JcIBf0UPxLBusOj#SJIS=D7>Sw~C2EJ}H|fE~Dkq*%9KhoZ52pu{2ml z|Cf}=XA_kN1kxfWN_~%CMk7I}Ucf8xJnj0N3tfwi=+W>1wr*Jt=stl{d@RPS;6{2T z&q+rU=5F3_@#*jh!lOZ2jq6<}d8h9egdnR%a*szZQF{tCh&_Lfu6L;>&4kKFs0K>i zOGoK2gL0rQrxEB&ivrGjqJ>)!_8gv#o8Coe7QPRCuk(>cqj*_D3SkBfl8cq=CJKV1 zR8!Yd%N)9krEut}hYbdjk7zDKTa22s}Bl2HtiNSqHiM+6t-Q()aBLTo0l-5P>z7 zGpG~d2Th7UJ?}L(UO0w=&^9>wvp4o%Sb}9s+oF_`FLQovLT!_75@s96qSlPtwMw0~kC6c~^~w|*%IjnJVi}&i(#7Pli8$Mv_D;`hDIJ<8$Gjm- z`;`jOyU$3WNo9d%b-yvf;pyu|_Z7qB0WYes^MIi;bZjLy9$TDfLIqrO5lQk*H5SILsYfctt9J`AQi5D}uOw@F+o`@I%=5 z^{QEaItX(TN6U-*|H8Q`MoOJiRX9b18P1HUBh9m!{mxkFe&-7me?sx$#x=#s1A2II z&JOnTUn!RCN<`6=fly7aBVopKOpW0+YWOuDE)G0DMkt`rkacTgb?n;L!p|py+|KN` zRNd`$`X|_E7SHlJN_*?i*hw=60t&uDZ`N)^*<4g4x*FlhEL;3`c%|skIsslTK$;!T zt?lO+L&CUwPZ4{Uc?c#K3pCf8A5tk}P2^cqoaHVFzp-*mVs$z6qGbH+0zS6hlvDU|C{!^m|`l!kpt62f_?qH(v~CvrIU)uRxPpIzgtB-%q|& zw}#y6$uBTzSP^+OMrZsd2@}=*8ywFhVy#cK;&fyi8Z_4e^0Hfsvz^bv%eEWlTJtMl za7mIzAWTrn06GzP!u;^lS7zH+NEn~_ zUva=I0TBVm6g5^hgz1+G#Tp@9@#AVX)#B=-WB~7qIK`zIKp3^lQt?K|%|dxXfu@(b zP_^w(mORLLt1xFo6+Su}D=Yk}5Yvq&j_BzteQth0=T-HTPK&?baoI^Uo0zGPm0RM@ zs~WhdJg*49l!tHYs2RhLCnUddX@)atw)u-?Wx+y)injbNt*IX0)KHOjZGd37;|H$n zGEx?MR-*lz2GY-ytvz5PjVcFx#x%EhjCty>khvPb^?atHX4n!%`d1Z3J-DdYD}0pV zX$LP$hvq?;D-D9g4(ksHJJfUqUbIwo-uY3Uc|KOgHewz~Gn9sBt(;5qg-F@>^?QqL z{&l62_=4T(Fn+OLVbq&)1iDuh_MLVrX3V>S^&3hRzq6i5m>C>1jW8X9Lq&rg$A$VC z1)8XLIpTW9R*G5ua>alJUogFZwDGKO7^yN*UeBqm{QbHd({C9o?Wp3rbYCXM4%(oo zYha9}W_uJn2ZShgPP&8^&C(Q3KmJIV7X0VAfH2vUcZt7TQ-ui90&jk0IQ7>tP|Uhu zukva1345~im41<5uh<>qus8rY-Hl z*;q>%AMp&++Z!p(JHLg2NeVn~c2=Bh_EDj^-dZu-#8)x%&}H;U8>VQa@O^{*FbhWUOJG?A6^Ntbg~tn!|X0%K#^+MCr=&b8E0GMA&fnW1v;?Q)pv z(%khX9*TQ8^$>qyj$(c4GKJ5aTgVSSrZCbgk%nr&peEuk~t6@4b`2_7bLhte<%4K&ddbs6cbVbccFilUR83Tb(wH{3Ot>bw9EQP9@kS8=-H#2ki#;+GGgog@V@tj47oF13yT&zjN~^_c zrqkRw<}hK7d=C+OwtOla`&^(o{m@)p75YFvF5Fq|MZ+&5*3?j%C%?dt2?mlo_}k=vh};8-yKFl zm;Kpk8&YX4&l7dzN;R7>b|HJkl21Q{{cW|H*w3!2)%z3W6?HzUe2r-pvS9@RzTK6o zyZy$|WXq~toWAxG3(^a))hZ7+jty6wuFNmhzwiM$N18-Ed8 zCX8j$e(`M`9eK}gT8*i7xaje-rlRQTSCy&9b-tA(r4W8A|48e1qn@6H`|58rfZ-aN z>Agag;X}p7enZf~b-yBTXrZFy`X3yyk5p`{>L=M7TmB-@5+?Cxq}a=&jy$ouRx?di zUp&1hT^@NUQI(f;34ZmTQ;PyMRCJ!LbfBx+wZkcSEz2~OJFROq?NEkz z?<-)-Ps~@+6KW_;OFr=iYpc%T`20FboAE;+p4nk6v`s|ARa-X=#D)TZG(&CGeb>;#*zPv})cP#>@roij` z3wSJ5qahiDpF4a|mKu#N34fvP!@uyV$V@rz*g*6*43{vQ`S0cfVZyFo62m&xmxs;M zYF6k%t(Z7f_2E>mOeZK4zGrVyX##zZey`zEa$Oomub@^RACEKG)VGn+ByJ0>-8qG; zc5C3j$Ojj4nkp@OEyw)0qY|bsm!^_1cXf(Hr&;ynT^7=}F^^MusT|cGY?cV7HE0-p zWC7I-sA)mK3wUK+p@Iu)MX-8^Fo)An4yE}v(fiTGH5~T_4931(Q2lwS{Z^!vqVXnzcq9{!UXlaE4E%+N4|b6 zNz?NwYbnj1;b$$Mao1d^N zE*Of7i8Ssw5-wLa;gRug7;QKRg9H4g6>tZtBVlSs=ZR%$uY@<9wVLQ|pHzD5+GV@< zTO`*Oo`lm_wpu4s3aPRHvDQ5fYggSt{)sd!S^X62{tCi!mnbxy8G(haYq9j>Q`}q} zhSa~~0w+192Vr(Byd&<_EfHqhXf^#;cTo2z8It|s^mMu3blOOA>N?UkoxzM%4^ggr z5x4u2r%4z)MLKG?qm4dW)#ywMb>nH9#Tl5cy8(xmqBOWU?^iDDy^<+nc$dmUPeZdi15frZ zhKWNUI-QAz&NmlSZ9R#*f5LFcmWNd9a*PXM^wz!+TU|LL+^wtCysP@6I^KOmcI#v# zd3h5RJm&G=&FOn(aBg!2rm8gDHlotr&l#w-;5cTcE`+TAO5|G~#+uRnvCsSnEa~0j zw9Z13#+F}!QG}WQ_NnNa5i2|}(rSJiOqZ+9x6QtGKURpJqe10?LYV4l@U`}1JRWfs z&!3#aMEzofemH{;Zkw>-i!%&2^}z30fr#nT1AC)NyuN(Bh~uF%5ERrI zwr^VFTJ%OF$92cP#v2iIG#IpRTe6-d95ahBfp=rY?ulE3(eDa0TQ7#oqZAXf&F(}B zR>LkLE$xmpR6DrlQ^eoShm(Vd8GG+bap*0{$_`ZJ{hAi2R zJ%+^+<{UpXAHrNe7a&?1FBD4O6lfm#`OAkknw;%(6auq1Y^b(7#bH==cfA8QrA>GVl)R)2>grtw_F47;uH9$lfBUr0q31N0?~F*gKZgqazhDtg|!EK8>9 z2ZvX2s#BIjvn}Ll(!g_uVTTqqoi>$K6hceOoU*1<<^8g3`pw)@Z1<>*<@UjfHn;tu zZ17UCI9V5Qt=Hnbx=QN5dCoD%2oqWRw7B%)4%vv>TFvWKwFIl{j@d(eulx&RM{BCw z_dfX-#?9eAN*}4vWL+9PX+JA^2JBau2Cc)4qH;y}y(-0_R+}+SJzA2cB{$MZgvm{d z69=WqWX=t=n(iIa<%c3#WM?(4sb+^(e(XLS(m5)F`0x}H+sK#yY@w=3zYY4lJZPK&_(Q!!+sI7M+A*fK2#*e!k*9dc}Pna0@SK1k~ zHd;+n9l5&M`t|DL7r(0l`d&hL`W-kA6R9SeE^*`y`bPBkrXmz8)A3+ndqm&wNx@)4 ztl6*wFMiu0clHp>y0Rbsp|2%OH;%bYn5w3UV#>?WS>3I)8cV$ZRXw|{YE_F_DyD1# z+R%UgH4|$m-^bc|w4iR*8MvI+Vr^+EHeQxv`KUf<(7!3ndWPZIUIF2oywG~`VfaSy zHlMHj(8>s-ymCssxiU0svXfTx+;EyIW1fk6a`G&vw5vH%^M&cY(@-40CoQS#;hcdA zhXPb?O2(anA!t2oIQ%xY$5q_}Xf&}qd_5P!d(%O5zS=<2&L1?EFr`P@WW<5V~=yA4CT%e1~Nh1Tv} zM{r>r4mmDDt=j!@=VlM&)9>cVBmvGDfykxS?B%&u(xG|sE1>UAqoPd?i`M71^)SU24K+# zUNv-?V_Gn2%nyla8y+|{>!Q`1j-8`kWqCw?Pcu?lPZiZHA6et5#k$^n2WHgbn0AEOX%{W_J7Xc6OBs(E ziks@TCz9knT8@y1(nT)*a2)|5i4w+3c9AN*;}P8F8vIg^qsQ$XXqjyXogFUd-NXk? zEu5%viIxbKZN_aiZzY+{F^W36o1VC%E^kuxPkkW2^J%o)ZrUly9rWqQ zF&+jNrLqKeXg=$Xqg(D_d>bHxaj)t4n7#lXE4t%c_f%w?Y{a7(3h4@1bBq&V#&1aw z*HmqmnHg#|I^#A74mDHdM_MeF>*Q1QBYB;3DifqDz%b0Y%}>0BIYW=*X5=CCp@G`N zA9`Tqg^7sq?u@-IC*jv?3I6Qm()e*qKf*LJi5I6E9+Pb&Oph~51^e7+d1B*9^2a^X zq0Od4tCK1sG`%ZE_nwF|eFx*tTzecHa0-9MPsWUlA(Awm z`Geh!Fw1ttit+8w%WSFIZr1Qe?<8w?mUJ#%S046j~pb zW9Sh+WuzxRG%v#ZNTw;uraHohw*{J#1#?x$DvRYc3XJ8f1&jSWqdq6X>gGK}&&-7( z)u@%`-$Zd*H1dpMF`=6t)Tcb5s&55#(I3UWm+2VR*&gR^@kthcw`0#E%#;U7qO;ai za4Id(w7xY__H3S3zI)R-sng4_9&-UtAfVQLNeftPh^2r^fz;{MV^l0YN7lrz$)iym zZ;JPp9~BP|oWXqCcCc*TNjkKpT-humjPgdBI7x0TG<#g2`MxtlXykKNt~cqJgkd^O z$Cj$^FYp2wc4%Y1&|;bfv5L;XIV6$`cQ@XXOg&n&INHtHmP`j|j@fNOyQj#*C_ zwQsuk@VKMUjeO|O_hqtPhfd0iQVb-F!?ByR5S2RbHc{on#Y@r^@KYCJ%)MBIR~^I0 z{1Qc|u`||XS12BgC{*+xpN?LO>fx%APv<$zzfAyPhF{7M4-`=?$Ik+d`+H(Asqz z!w$_fs|bEa;_xQ?7{;F!6&)yjx4QlVMS?a~@%u~?qIy17{L1DXk`p;5k}%rnv*M*1 zGlgtQug=>&N?p78Dfxu$CsgrrF3p^B+8>q5F>_kQBKK7h=3I-TInXgQ95_qSuBtCS z7d=+A{kl()Jd7TNh2@IlJNan+7d(+4OPIHL7sXXOmkO~|YL$QZvTFKBwfvIBM^z|U zO?Cyeum8cgi!l<0nKey%48l{cDs&SEK(qJ0BKXWv#o&V!Lr8j}DCuP>-L&-_lSUY` z4wuDoQ#J_J6i++5!`3Nal%IUmeKpz~{-v0h$!87ebBu~GU1BbaJ?3u_vU+JX7fMTH z7EXThXG2O=a~h=4Yt@CYLbd+FTN!xdaJ)`fD`@N?M7|+Xl%;S3Fa>pGbwI(?}YpW)BcrD;Ij6 zv>c7xL3U_kTvO4wZw(ATI}F*kjL_cqzM{dbYy`DyfN*_Yob>njkDG)U+xwz;TYrZz z(^IQ4UV2HKW>Q05{w`eQvMQAu0>ZH0O*?Pek4rHd*1gIwnbS^Sl&LPVjE13Xf*Cq$ z9xE!NMXYx;!!A8O1W3*Mq>BlYqskFi9|#e~&ev*mFV#{-b}<+18~RI_IjyeKYzJz% ze1Bgu1gxmfH?UB`*gZ%=w`Xf#6D*}m*Xwh0`Ca3rPT$oeA^D;`3j0a9nc8#n`l+N{C3D#po@iu z7-q)LVpP`Q7`AMS9a>1g7&NdkL1vp#*fYi!5j$QfPLS#h?Qf5^y1W;6Fvol+Oxf)m zaewJ{q0dsPwmW=IxVWpS+WGi2fnl7#T$M2H`-}1J)_F-9rlFY@Xj|tPe8w1H&R}=U z&$NThfv<}9p_yI1d&1a{LZ z&TtIdz|7)l?56#m#xWaDhU2ECAuh}thF;6RF5B^BWJ&x@-0{4+ad+=*Y6=8=cV5bdl4{cW_~?@>1Uc? z^HXQMfg`fV8lmiI0@~KKG^~BSHm_%lTAMppmy6TmsiYAhmPk}dZecyZO&b3 zNu3?_6|!d(!`#(wMuVg#cxm83Pppxcc+3LhChx_J=3cn+llQQPa*Tp7?N7#ugX_-} zZc~+NyysJ4?Umi?T52abi>fne*!zaP)}of@NGo1hb2;1cJ89Pjq%3R=_t#xdxU`ugH_V>1eE7f$0R&9{&9)OWaE6_fY*K$O2%nZVeYjj9_qi_@& zQyjWiMOoIvO(E(kn?fO~>a=vB9}i2#+DEq~j0e46n5)h(J?qUy>lv+3_pi42S#Ji+ zNUB8LZRkeJoYs2rxg1kD#+xv;FGYxJU?Y67)@sW3caXj7xJUi=R)mm6!x-4_hDpO- z1WX#XOqe}!8AhX-hRBO;X$`M6q94t`iXR;?@x>G22-2EQD-6iPTN9U zzZq*<`Qw@=uS~hYG5ZN)ntVV!Gyk)!HC=&O-Ft|K8@s5TyVO%v{FMo-PaI=Wc1zL% z(FU|RmL7!+qa86BO@`Xx&)KGM$6|z?vBk%O{_wuN8LQvbmVTaphaaK{v$}S;7+dd= zY^YMJSyGsrRkUxgdepf262{Qtnxq97#>3z|7$*8SO@!GUj}sp}VEwc`4mNC!_Nx~l zFUAsaqx{e&e?5%;@OAGCxHO4`d3rTcoN8Ghd)`m0$sIaeO#RYAy)3Dzie(BJhUv7Z zgj>j|%P~xvsGji{*X1v`*|mekx2EVZbS@oQYb=|!36Wn{qtjr1)7Em#X~GOXcUYV- z^P=p!vsSZrWVF+Vq2E=yzV<4e;7rOsaSRKlFtb*DXlyP=#?0}^im{>b;1>9KeHNBx z*x<;50Q7w7M}wRB@T}JybCxizwj367m#So8eJI0jzEf0L%~plq6(nhx%fajo!!RRV zjbSc_@uz9HytN}9{Itf3+4J#ndwaJzj2t-T zGshGW=Ah=7IOKM+%!?vWMq#T}hC39hal0mn?552LxhDAn48uGdcA?p~Va*qd&E{fp zNIQgIZwuYs^C7rdLOnSU>3-{Qpbb|xb@|V;lrX>g#frxcCCGk{q8GuBVAZ#_&cX-# zFemoAVLcwqPh%M7r?HqW{1I*@mSM7Em*dA1OBB*u#^B>5JaKN0W8pg~wKpB%t$A*3 zBFFqB%&qn(M7!fjGTADv#>cydD(clnA^O@8A#Y~}n5*tGDp}HLELqIrX-q@2m-NCl zt1!{B8M1O6(dzYBn2a_-Tep4KI(QDYZRBRHF~{hQq6pOPMA7*}n(PIY#2Zg*uClYf zCoDg8O)>;NBRGa>XuF#iFylc2g;+TzB6kyvKD0vp13l2rXC!Rz8o{Q)PGoc)g()|9 z8QfToF(FKguSsH4jVKG7L&dPC!(?8KG6a8<=aN}t81`TvQ_Le!%&al%$(9K>`o0N< z`Hk^(ST}?u4aEJ#+IUGN}1S!zPFef(A*gTmD zz7+I9t!w?T`?Os`@aeWxJ3zyN zYx115(+55Th+$Z)b3kD}%ooJs@S2@?lWc;q0|d;BQlNZnU6?L7jCZ!~$iClB`rXvw zKhIu-$-a~#4zzwJt1*M@P0B8($sO9ur`D+wn4iXikPO3Guvplx@j7ZYCwGv=p<`%R zLwZzQbb73S`k)Mx+tfzP_h@YYN|O^vJFrr#^Bm($n0x*yV(RxlvLMm|^}IK!7IpEF zk9hV%Fn8dXu#XfP(z`2RbehM5b$S`Dh{YtIJvgVX3$x{YFuR`R2lfNZJjM-@*yqloaG)U|#Mmx@sC-2ZoB_m847J*{UEt96Yp^Qmm*5M$E z>ljg&*C6P*b;sbzHIR%rl)aXtK-N*h{9T+hhA{Ikr-<&34TbI0u5jVGb(XiCn_T}! zx=o^gq2vBwd^&G@(3$1zI?V>BgMod2}5 z(44M-@z42ZZnWzu(m$yc( z{O5}1^W%^b+zmPt{(cm4BfXX|W=E36vvD+*Z2;Mu&(`9(yVi2sCGIj7?q*tm9U2P| zGo6hyPB=|au2O_h)%c@*RxtSVU2*tlGD2QB;k(#FI<&w02(}VNyqY5J z`{68fl4&&`OwGi8&NlKI(+YaB)-uB6t+o=-zz6mE~MGrubee3NMgo($&wd7pH3 z{|#Y|^*JFHc#INUJhYlt;hlxMqvr^N`Ye$!tOkl10wxXf1*$R3tW{16hv}Z$xD!1b zvx3{9%(W&eN2TEMGZ}8I;h4$%rlk<3Zs$1Br|VzBe8TvAIp^fud5`d+g}#JgE(bHx z48uH|Y78^dW4eUn*2+5AZaa_$ZQG)~zYa#WOQCKR0S41K<_*VW5vK3T7%|q|Q&_%$ zZrZdP;_1;71rwUASlzwKT#o<7Fwf@XxCl7asEHXPTySr?4d$2pP%N34f}#;JY(2|w znm&K6T_B9t@ECDK(qy5SG_=y-qRgs6MOdvBuDC6OX0cobhu5|9SqM!pkR&%=MV)e{ZVraEexQ+32|7zu#J@G00ZN zludba@}aGH_<=dM?04g~`-T*=akSWjq2_gQyG}oho8AdBotiNJ5rybgG#O@#wREA4 zxHNYO^DyI(*nG!yp%s}mpZ8i}|I+JD7wTP+SshL1^=ahXG7ZgKb*9sp>SQsS4Q+yP z;Y@AxeCLD@uC~w#tW&Q?0)VKHdE`7xG z8LwsLI;W&~8jIO5d&3?c)rNp!27jaGe|>#aE_Xx)&A7i8+5nnv(Rl3o7woKfD&p@b z#~Z?g4vr9O22K}*K>B&^8Yw>d;Vp+#M;wQOh6f*0{a%(I!WVt8^Zq!EN9wbM66D7{nZHO-A6zG~qv!JGNY5umJ zHAYjQ>rRxoV!|ZBD3M-kVL7VO#-CI#rvym8fYzFahL{7z9_%b;Qyol+XcT}Ay-YD~ zZg)IO9*on!EubE82zs?VG4&EpeV^dp#*i@6LZZaLlO96(VXdZh|1YXl8=Y10-EIiX zv&s2LWg`@UV&R9q{b@WKc{a=)WHFoV_X9C;XA?ZL?S-a6!{8HbhAJw7TTj!I_MGPx z#CJHR5n(EAkBUt##t5od3Z`WIQhmG`qgoK2BSbl!MwW(Sm~$J@Fh}y!mfh!Zf&7!3 z5w@{4X1(u)KBL_*{e2UR(hJ9lv}qVHolDb+=LjqaW3&61DBCwe__1HB$s5x%D{=J` z)rj}0QfP=_SX>~d568HzOpsi4?Vosz#TIm#&>XqN4%o1N6y6v&#(?MhFo_n_eQ(ZP z^>B`{B}{MEqvEAV7vbI>($K>lg|g*M)ysZ7lSWTgV_5jXrE!krs8j!oCo#X57`fLXf>ut>2(j zNb8g#9U7CynYta=p|OVt!xVQ-K>D;bNN?F3M*{4SXfOe%C$@k=)gDyb_QA^-{#wi6 z7=bW5cN`SuQ+o^QOU^Q9`4F}JSL(l^2o#g1Vgn^m=uyZpEHuQPQ4BMmroCuP zo8wEXj`-;9iJc_DonN6?d4E1;h4PSU7RL-AjFJ06vDBiAFf5ots%xLC=H(cw_eCZM zm3bVK=lc)l>pdQ`VI?CT16LuXmj%4Oc0p9)U-Jw%2zQ?>K%E)(}yVpTr}Y$!uD z=IEm3xLm6v?ikx)@rr4%Y|sW_KLg-;*9SX(aLi!dC%u9&UJIhd#}!m%mr9SqA3KDn zqu;CCqxuQvJO7b}Vc4PlJ4VrWG41lOL5sJx(7d05A$c~~mAD0KCNCj0#|-6N-+qL7 zcJheW{Mt8}N3K>Qcmz7_ue_l$K3FA{#Q*o9X$$_5#+|C}$L(#0!PYh?+wDd3Q*98x zCIAU9mtxv5UIXZ+^ z9opk!qzzggn~I`!)=2vkfFU0jBQuXn^OzsnUcxN-9xZ+iDv{lIs@1rS>7tsn!9=B8 ze@()~zvnmY|H8Z*xDu6JZLxGwd#s3 z&xP1|$VjrD8jgu4%!q|)Vo1jYW{DN%3ovPzpH_{@Hb_9dIA7e)Xai4^?s#x^0vAyNoOum>UOI8+Yb_!)qW`7n7 z>l@RMCeqL>vBEG+Lo?@=sZJK_WSF!yo3WyP6ZG!d19GDk-Y}BsEu1|}Fr_o$uttX7v@I!0BuRtYX4wW4dtrlF7t?OH;$=Zm z!mw0C-s==No%$!-&5SgYro3nio=!Bu{dZjuU_KO^{TdV(I!)9m#vk>P8eyi|0V6gJ z#@&;qSYQy2xjo0B><16qZRMDHggI6fAzI8Vp#`pmn#*36s#d4dgtVWoQslN8!yKq; zOm)(0)6>oH(KW^D365~d?hm6Wh7|FLz`K6qk+*^ey1H{rQ^Is#6(PR7{z5i!V4=pW zeqB}Kst6(fZYv>g7tcm9X_!06UTZAeU7f-U8&31>_L!iSQ+L!ecgDaO#!%5C{_KFU z@S=6RES^@I4>PeM%&GekqQl+KGIya+bK6s`65D75!DfOKAZBF=48xLM)fg7JW#49Y zhi%AQZ;Fls6qx!$hL~T*D0&+Xx5vY=YbbxM-RIJDB+P0}q}X(Yj&Q-bP;>M7GqE!* zaESCAB4Mfzjrq_F!~C>rOq^{1%zf&kHPt{_ww5EOlL1aIIgI`XM6C# zqHDZ9?JLJ933K)GUeP1fRCv_8P-Ak$UkK`$FSHB(PYio_FlkuuzB-HhF)t9!x9g+h zH5t}WbkOxK6~nwcil2LiVx2#KMrk<4g)q5$cZr7=G#8%O7HYQ6j*+EDv#;>`fhkUhL?<}IA#=K^0tJC zwT8A4Hgqb~$Y)McCHWKzUB0_Yu6p&M{kJqxx$$`D90GR}T{Q4hz;TNMVk~N-bKB!+ zXX%Rmi#X;1$4n$lvss~{Yh)*(h`x940DnKq!(GYOKoA zRpXjH6^aFGq1chi-$`|9Tk^Lj)6mrzW~3*N38o-Qeaz46i__|^nAx{B>a043B29mM z&*56&6vwP4%(-r1Vkg}}!ZJEEZ^sDL`TJo)%5h5x^Y0mUX4a}PQH}{vG!8|uZ*6?Y zRp9Pq2O9rT8-F5>p=xSB3@qZ6Dd#z6Ghx(D2gJY9-2_+bLQP8lnnJTAJ0bsEcj?fo zs~^}EV0AVOQ&EeT#CNX06Z_8UVpV!y^m=NK+P-zr;oNcBPBH+Ct+_P)xUvZ$jGg~( z@&1{S!i6S`B0`pTY1uXoPmoN|=>X zK&7`4R;rI-zUyGjd&0xr7da-3Fb?{T$3lGgqA% z0%mUvD-#g4E*NW$HNfvj0t%A*VwkZpdYVKcYwcJn_~T}67ndfJF#3HW#mQGZg;@;? zHG{XWRheX1iT)-^NkfOV=a}lZCrcJH>*>@j5utN~P_VEmme%fxbw~T6XI=x`KD!@p zR?vRD=R6_#ieqvJ)4DTh=sZs$re&d~LD~}4g&KOY#BpsT>lym(3Y<;TB+thA={d>e zV7`F!^h9jz8Hm!S&2TAEhAYnfFfX+p-VCImakDXSn8*#mS&q3zm@8Yu#c|gr2+v8H z=pHv!x|8>aPE$uozCir7D>O4LP4d%xlFvyF6wBhe?@L7QUYp^k+Z^R~z2J49rdvL1 z0I}|V_+(GUh&?>F_LXC96UI>)jz47m^>UXM}O}I0eZTJOY)^F=d45(mhUG;x$Gn ztXHTpOuwdj6~9Nd?8!Lki92V?73eHYgLVVQWc}pL7c;67@y2Z{ve(a73<}+bt zHH{PXKModbjSDr-w_eCb9IvHbVLe?i{g4T-&R5`&l!mm|g%T#8G8$1&uS%HxTd6vT z2ANDJ%q^=)cwDz7PR0bo@$h^!G~*aUj`>ZPy@O-LiL?6%kLjlMoo*pBUh_hwKfqgH zO|on&36qAc3o&hR4(*O4VQ(78+{#`{htnRWOFJNR#&kGUv_Kaj2)o8DgtiWU-?ZTv z{joIXHaS-O^t6}otV^M$rsZOBcis1@MzduCYm5ogh}JDs7DM ziC%$Og*ND1-WjhR%|_Jw7O;;Gpy5Ev5Yvdyvx(&xQ^Ks-nIN{+bP?X7Q1g9JiK?RL ztg851YYF3W^|Ewm6I=W*W=8L2Si8S79GBU{f!>=}K3U>i@HPw{w-WBr9P{@+=@x`3 zvOXcE*0vSWM-*z#jyG0yY#*0d8csJhy@zqL1*W*vzN!&=cBh1PkC&X93ECl;GOb+r5%mgkJ|?CrmOI9v4P~=cIB8Zgt>S& zRX%omx0S|3eEr#d(3o|D+4P(atFQ($nA|%)8 z0_#v~+TpbXyG~FfO1Tw!s?|6;kW15yzdgqh=7Vjtm~Q({HaE6VORy5QNdG`JP`g({>{v&-0%bf1=|z~qGmeWdQXk10 z9xv29Ue{gba$|@p#I~;B^YNdX_TLz1>dCnQFI-C=(j=6 z%xy5QMXPvE@SFB`*e-x!<{T8??#hsz%_!7-aQ>>A@U5%N_|Si1oHqX_#_32RvbQco zw~L){CdV2>&(A`~@HVu=FbK*$YmnHD*QZ%>EwGy~y-yzybq}V=9wZlPoDxJ;Q=Kf? zh0enyX_#3nH%SB20?bG=X_yvZzQAYE8%g%eQQ+h`L|A;j+jE zmzq<{qL~LS1-8QVgkYR#;X`97xxLBa-zJtYQ6W3U{j_np3rXYNXPR($+MBFE#R*9o zzl&EScaW)0zenf(rJ_P?)pp#>S&sc1cq(ES$D|Ra zh35{jQ&5uZaAu+A<+UY3OUo|8*c)oe5HLSY=Xoj(oiCKa-7Y ztYw@j^E_RsF`fHFHDUQ4q1lKe$$I+Qa95rA0?dbYC`^*ZP%|HT-i;0TZqpq0DIJkw zHwt?_n_)rcy{K_x0eU%c=XM;&+$7BHuEFA(D2>d4em7gK^wjUN?+KIhLM6{8YCMla zGtZ_P!(0xA+11n^&4x6?q$&qI|1ttzlUl%T(=P1%JPC2h9Am^^1jU5W?h6qMDz3LplG3ZpvtbSt!>Bczf$Qc_#dbyFPB%0!YK%97_Tt@H zPrO^kF)umhDPeZC4-q#$ydyIsOn&XlvWmUC1*QE#!7w`$?BT&)YixEm3wM8=nI!e% zGEC3ATM!f91o!K9L;c3C*myxl4ITx=IDqZ@$J56vhbaSnuUAX zIxYB~C){_Blp?q68O1Qnxn&r(a*s91GR)ogoAKV;1dTU4V#wM7*!Ri|zxRj1Y{*}@ z(~-9;{Jm`JJ7Ie44H7%)f0iYO(4$Z<#OctUcS6ptHIfhge_>dfh+%4}w_@ty2Joh^ z-J**F;oqwfIy{TSh9ue{@t9*S@GGD*j)s{OZx_2|)fArZEz~5q4^~}XctM@26n%U2mHP6>$zI|&u-Gf^$g^Jo8HSlKm`rm8Xk*FKnF$2ljw zcb7x`-2|nx4?_3QP)t6~!*(_t)0i-G_4bKPPc{(rHc-Z+(JGa7;t8Q-|8E&fNd7m5 zPnYTw?mD5Z(wWd(> zGqADBq%u=DoK*B5n0jxyGz`NYg-n{V((UMY_5aaz=5aN(-``J)6h-EcWGr(xQfKe| zIYP)BLP#=a&YU@wN}A9-NdqB-sC`Z+A!JG?B6H?SDug7@+I!!A-|z2vJ&%9NBbth_K$S;{MX!Z z2w~!P#_{a3KFp!Lv}jN7%CwhXU}jY;kqHXo|6VjFcd4-QH<~^d4q()?=7{3t=-7S) zjE*-$(32RFW=}?Oos<{YDn-K)#w076Z>Bkr(cPj}Ri=AdH}ni;3KHi1Kcf-uo_{d| z>JOlmo*v9U%aPJs4i)JLN9o03>NE$me<1xlV>32*4ERr`^;t_{WwwL#=Xz+^C))I`L<{m(?aa+Ma%S323)6UHGYmf!kF z#<;Ffs}voSe2}v(6ErYc#0alW;Y0BE+1NihB{p9Od4WB#0hn3P8cYs{(LN)f%{0NU z#^htzauTL%OFQj^gqcg2f#2i!A37tL`%Y@r`*;(@PJ=L_vSwnIL-Hw|5 zBk(3@1RRyk;FlJI^L3N3<&pHesgN-4gc)uZ&o}8Zj>(>>R;6X+DT04Llie*a5HZ4$ zLpVSQ?=+$G{WlunIJlKu6z+F6guV-d(*@(O+)$5Fsxi2`YZ8WbmfmTHC5$IwLfR(q zGi%2)1F3#Mf@8e)z zIU3KeHz%*@NZg-Fg7VGMMCCk5&J#cw7qbLDJA48o8>LnqdR5A22Nv;%(t7_-GDSGt z3ZFIMoF;s4gxZ>b8Mws98kF%5@*mHp@p{H+l@Ws0Q@w+6aC^%239rADy8)wY1uA6RXgg@I)qLpll+fXgs=0(FkW~AvGlA1;)8= zgtwy^mS_)zS=ae+=-LCzdhEy0J8NKBDjn6=NSGqR3{i&iUZ)2z##G3k+bon{Yo}5~ zFMBK#GEjdp|D8-}(o2fwp<*Kq(k3;^vjG^eW+AxSrZ|^JgJv3Upr&*wpB5lto)hMM z`C)!?N-rkdOsy&_`<)ru_<|xxaYZJih6IeTXu>t>|4t2!G2V<(`+DK>j(#xhz68U9 zO|d=v01m9(0<@HFYcbOA<^y3|t{mhyjWuQ_Qcb$iCN0^$AEy*s%+16bfq9s;Xu_rN zZ$E&PkkVCvW% zJ6bJA1tq+GE!>Z9zqjL1f^=cOFa125%qExLgTeeF2OY+E9=&XS+VYjvV-&Yb&&q^E zmrMMA@&bPsO~^nA(cIKqi&Or6;q$sPmNcxTX6CMtzwv@?jT?UN)fAH{j1)~v!q^uC z@zW9-F{|dNRYUsQD$Je*D0B|Y`(M%YGX2l9`HKnLw*=91O%X7X>IByoqnDL2GF`mT z`}%qq>o*cHr=)0%2(xWw2;X7IH`xY9wQ5V@^{(K#HcN znl9;$O!0*RxNt0Rs_tI zDNMc>{C}gdot`g#2>RZijSUWDDNd!L;w$seq;Go^t=);PTI+D)fHYBgq=Xqj7>8>? z{DgUrWl>wzs;P5&D`rheRy22t_#ce$^)#xw|34dAzzAQ@@*lHtfNs)z?OVe<*%=c% zwj;lyZTPrs1ukZN6QlW8K02H*MN1CS4C&jlLHpIJq@1OSBNdYrRUsGu2P2#X^t1mr zMmRw2n=%Fc^?OirY)5?3T?EJ2_Rw+KhJH=lV0o`z#Qc$>u_4U#_`|$jZLaLAH+`h< z6f5#Z`6xVlv=eXA7E5o4s-eFaAwk@(Q@(gqHy^eD-eq0z0mfMWd>+Qzv_Oi*9t@ed z0+=dofpF<%Gl4Mo288kHzFD#wI;z*k{8Tu%osg9fH(LAQb7vV!U&%=0V7m#?|)hbx0_v2tW62TzdsB4Z`_Y^Qflk5(v3+TRTg-Lf!aeB>299dP# zjb-PEr!l=2MT;WxGM(!vnV%*a zp$QIULQT5N{-)SgI_}YGxHfHqcq=31yl2t=b0b`A=7m0eN1%SI^lV;9m=MBTMLa*h z$xYc4PqivsyHNH@>z2$mk^I(3d0&{AhkON92ZIYx=c9t4?zZbrep1vJlU%Y9zegG1 zevclAIyeF^E1z<2bvDBbhy>A>ke#{sVS47cMkR~u8E_-Lc++rUZoT}y#$jwVR)7siN$^0KXTeT zXj40OL*GGfxcIx?$X5-(_*!1<)b`V&%&u}hn~^mpczB^E6{bN=1VJ@6aAYPM;%WJ z&4W{?B(&;29;HK*xbFQPbDuRHb4w40anE14!pct*?^jD+-;9*Gy-S$0XOj47hqM_- z2em5NG)sAXtvBNz^-)$v{n4q$xhSEQo-)fj$S=skySyZr-n~YWokSd2HyxET&vNe{ zYohGoZ!V*AG@Ji;9B#I}z`bnIO^jxQgn2}m%KIny<6+GhW`SC@A-P()UB{cv=`z~d z-75`_IXQ5Al!9bEnrA1^gx|14y&_ZL#1)iaE=dy=uE$yzh$*>uhk9V6$ z7H6FRZUYU`c8$l_$0Nac9^@j;{&0sIesQvcDmHKZV8r%5&kcJ8F&Yyo164toW#=;Z zxf5G3PZp_F7t$9gY!^;ocR%TD9YW8=O~jEopf_@fj}Bz7e_=eB(yNZRTFQ zUVtwRm0a41crlv(lI5O;qlQL;7D;pDRDf{Q1fa5vBtuS^ZWTk{VN%an*LKaPx7hiC%!1=Pw8qB%2@+IgOH&$duYc0&_bKfS@Z zn=HqPE^SahAzzH z@yP#{3=7{78U~P#CFJ}Y(A))g??2$#W!DViwBsr;*+{0JrT} zJlT4OTYlmj7gef-2?K6${*x9$)=VGPTQbCG7D^Zk!f@#dK6tne<4@1#NSUd^`Io!0 zUy~TwU$1Z7=fQAjm4T4$l5Mq-%_$fk-VZm+vG}f?%Z1a;jP>Y>GyO9-BWnB`YS{+e z<&p{ab?MnKgh>up@!bs?GkxiMqvPbM%xO{0#MhsFpP&BkOP=-$$!dw42L{njtQ07beO^35^xf+eiG+&g=JO<4X`%rOtI_$4%;LEP& zXmWEfGFyJ+)-G^DwEH0Bu6`gc+B9j=rVvK+(^Wo6r$&}=K&`SJSF5nm+pEy%{K%?= zAy3t`qwu@F9~p~Ipw!h5=254xX?O&j zdhA2xEi$sT_r%C;Q*f`2`qmn#zDAAz3Nvl!P>JZ_mvQKsRw!Z~N|;528QD<4|Dkh2 zXAiY%rt|i!{n;B8h5-{4HY0+OI^zgRBYaV|`XsEma9GUsMrzzqSorP5*Ud9f+^YkO zecD4_$KhnJCYVw0f=kAuaLz~?b$m>+-(5|Zc9U-NUdNuw{HUuRL++9b) zD8E>YW|!nyyoE5E5^wO8>|NRMc(tmD^L5t5%|Y2=e{z6kADdt=45R&#^J4esh5NjVTz=CP%~sNEi>o%(-`&*JQ8AuBTJ-e%ckb zbAYjOcL$CCFUDqN0`$LnU_Q;S8@5RcCA+lI|GX6@7q*9X&lRXMnvZP#cOvGEWcTh* zn7tO+e9yKQWlmK39(^4$#W_RerL#9>cI$)TRu&H-8b7xaG+Q`~JfywJ9$CW7X|RT` zcYBOk*BosoPe!L@O%a?u9Uk5;@SGyO(`qG5C}DyuFY~tFPs?`YsZ}Ri-OaqIxT45$ zkIzco5JGpGBPgNbyzp%7s66N9vkw+Ds#Vwm6Yma$6=?^XHE5vw(24kBYler<+{yM} zI}+bX^K7oFJQgp9=YTU9Jq|Wn)!@@KStB)ebQqrd%N`ldQZv;{ye_sjEvzu@x*o(BsgYjt&?ZAfZxOPHX zG`FWBCYvw@^A-G={V}pgDt#C3YQb)ZFksC+FEYZbGk170>i7eASa%vB{xL{*qyO7^ zDX?hf1E*&Tkm5ZUH!qu^ZTv#q;TIs$It)`6grSy_#)82Ay0mCF2=i;?8NOLogse(M zC!4p!**(YhDKD2cWzF}8!)3`a@eOUQq`ty)aWGvPfYJ`fk*nngGuKVnx7r5uaB)w* z7sV49d`;btMxQA|xZ+>IrGzOYjEiF$|Mg6u>}|eUb;_zcTQKsvtns*3Y~-#;l=!Ej zW@|9j2hJnIFaf!Tf)KKWM9O{raqad}G;w1wz^X4YDpo^x{ydDjdKel*0ugidA2FKW z(xN>j%=Cvz(f-HZP(PVocW6@dx2DG6S}xb++b1V5^&k z8dU(IXYYpTZ%{wzC@lQ68@*}QS$5fn#4=Az50k{ON@)wcBTVj})BG1@pllKCw3jLs z)92)8CiYbYlW$3jbo?|-Eke=ohel5=ND&RvA0DE<>9)ZzAF&cn3Ja{<)B}9#aum(; zqd{7i5c>N9mW8{E(RfOjD#HAuI?n&l4wRK-sa1#XZnq8{)D47b@*{<2W0Exah_WQ@2$t+lynr0n>&h_dTG(> z2=l=th0nWiKsJcBfG(%U?$K$>cHL&e8hO)ZuD*cMlTldxCL6I-SF`vLN%QP7Q1des zW@iIndddl}e=IiUXd`HoJ8Grq_QifKEmP0z?Hkg zjys3OH;?1Ry163eqx4SGC(KNZD8A`Ue_1DbLz_;nXFD?f?1}Y5*mMmtYSg6j^85t! z`gRR2#ureglOWo?C+o(dW_2_Ss#e0iwKGO)?#He{3Aotm5rThF4;2-}gx`&hgy}$- zO^agqsXt<5aj~R_)`?{Go6%X|f&rUAgMK|6sQj=e8TJ)7#rutLjS?;%`9TR7Vs;AK z^*wQ_HVB=@B*FjiJ}h#(3>-R#lfJ7(jH`q(C5%yEBp=fzNtPC%R;k^>+0$)*GqZC# zupU(D5U#jJ(bA>RagI{FNju)iL*edZxNt|IEL)F`3*At0>@Z@YTya42BDF0X#kQ4F zG|!~ZT0g=pAmi)*?nGoows~qseXI)269p z7q_TY%~thg42|bA9kS*zf^)gxuHg8V7fpjQC^ztYP?l(cWbJ$jr>z6Ae)=FBu(N=? zei@dNd2M*B!La9OpU$Qn5d8(I$&F@Ge?GQwQ#x}P84hNfEis#RIP zZ}3J12bpDe#wbdIZ^LNbOVo79qksM*9Frcy#qug9y)1=a|6Foc48e@feeof6EdH_F z1dl9ZbU1YcrknR-MUvkflVZX=E$QCijYv>D$W`hIZs!e&Q`O8{MLNPNis&?!KRl90q(4 zZQUL(4#neY8mC`PKJ@c8;j3+Le7c|E!`3J*?=vitAppQWkFpQ~VQ^a`aD^I_LQCa$_f-ZdE3GLvQHrizl#8ueFr9R%j~BpB2HzhSJ$nRSY_qPS2-Miq!p0V)`<=84=w1mbU z-VejU@BOhPjK%PAbJ5+uGj`GYFOjN-@_`oOq79Z7Es-#X%DwsN1GSmnO0`NO`4ZnF zdK}xKQ!Vf3Tnr<>3e;>bMCF=VtRD7`{=N(M2cO|qdk4|xM^HAYH%x0sCsgYQ$S#~9tAYE--qbEtSUt5MZYk?;5jjv1d|eVoeP z556Pa;-y@faazDk-g6gycp)sgwHyxVtns%ee-IJqj=- zFa_`B7MRt4B6%3Pz@F)WPnrsRT)r9u2g$`ngOq{FB~10#MSSR~E==twwaWj(Q?{xq zkUbM0DznacjQrHkl#6~K`V_8S{1Hxz3NXq43-u2cfWLhV?_2gqNGXfEJLaH|Zchv_ z&Bm72%kg308WH0y<w$D(N%)Unn498ZXH0&Wv z`}{&#pE7vV6(IG%SJB+@dCOdUe=#4UGB!j0*b@fP)4^#z#juY7h`P5{!~{#2hlFu_ z>&OSi4P&lp7O5iZTV*Z(exJ?hFpqJ|DuGSQYFeaX>@=%KsGOQOsMyJS^$1NOy=} zJN)!!JSs|PBUe+`$|Hny{*7GEa;(n0PwJCe6mC*u!K_zUU+IaerQwvK2t|v!-PpV0 z3%Xy5z}}ewBIX|nQ%0D_t(NkOcTHj5*OJbrp_yW%-UBw#GMLHreS*mN8l=v7jLI$z zsF_efO%{c4O8XAobw&8qrxfRYdZ6JVjhoCqh%P-hqpbONyvRQY&+Dlo=HJ4~SHdjN zTg`8ebYcd7B-PN2)6A;}4(y_U3Z~GGUX{1MP=k31thfJx#nw+4;HXBf{!cjEdjR>i z25ineg!(3@FpW+*(bq$;qKlr~;nM{q2PR1vsp8QF^Zey*1>Uk}BahrwHbWb$Ga>7(br=g742@$XX?%`@~p`yck52 zd78;hzMa6V7HJ};v4qi?OZl|3^Z1L?HZzG2)vAB0)-f&e_pso5ur3dtBQ>`c2_?_4 zV`(FK4O4}*QZlFsuZJxyWZ6Oux$eRc6zoqS1#vRGe8Z3trz^id>I|;TP8Ko$jsi0z zOx4Em{FB%{OyF(G+|F;zrrM;lkqJH7(v>e^==B4RvX_{+Q&aBvry8ay#pLDDfb2a_ zaNt)hG;i%ksd*%h|Bk@5#r|lssF{4NIt3dC9~Cj}rP6n2!hBI$@hhA9GM_G~RY!m8 zF)kI}?5>d`So;O^l{`_0!jMt~r;@Gf=P%^-`IwX^w1BOjW2os5jQi+~MXDH#Nsd7F zAAfXup)J3qPQ>K-be*C<{|?gZMVK32Hhe4dK<3+7wW==q2>-SBEq21F#cbA$H!w=6 zr_;?_%)hK9cl!Jd7B`>Z2;WFz~XVh3eDl?S1NT0RvWvdkNYmc$kn=M(F3-6Hdrvc`#-s4o)Ci2oTKakPw zIm$H}%L@;_h9OgdfP^)ObtPfNEgyuMxM6audN{NWM1Q%Li1{R$)L9c|q3JAMej$n( z=C4)_O?6ikzDQzQJ+x&@pL{^ulN$1}#4`Na(NyjlUk8^xFL7<0mfYRr9qK*aW8^m{ z79efom*M|*I{VULJ8E@4IyrWM(}Pid6E%%^tVZ}G9XiTrLsIr)FzN2}@qSa8}22SVoJMbt!u$=+j%B-p>8ghN-_b@AODt8}LiSJwU zF!Gowe3ndvY~^HpFBpo3{m=2fd@)IT$BUQ%3FAVToT0<{sKqB4{po6zah3~n#rino zeZZ2n_)v}eleFcI55JP7PIGxHT0lSVk67HGBd>L+f__pCx*uza)=NfUdJmdF8aW8; z^%AP;&P3@E>11<9!mK3B4Uc}j&(PCM7kg?Yv5jQXW&>)IVg21q?n7cb?Czt7keXZElI2SDp;EYQyXj)u?vvzG zc!)5Y7EI-rK0n83Pa+Ler%1)=;mepyBhN5p%YVSvM@O#v{ulNp8OS4EX~~@SCKq<4wnKDKrhG0mmXld*(Z;OM|t`(9w4 zQHSJ|Z%RIA#VdZz^^zPr|&DQ5Nt>1X~dw#WlX_#eI2m zhArQH7;Epwa81{zGs3GgNs8teVXRG;^5ajPXR2t?qSTiZ4tx7B6|490xh_B8wMIv- zd4WD(g!vndfY}*W3)7nMXt8jcGB)@*>l0a)Wi!lES#e-Dp7h(#s@s-|=8k(LOgdp= zy_fLc8)Y!*Q`D-Ou@TBIUwbLyul>V24*U+m?!B;Y9o9LLf%5<@d0O*I#8m0YEk=C9 z(Y%dVX%?l_ow}0?UU`Kbe(a)hg-IYRjc0LLZcD^yc1l}7L6|YkmhofK&oQ!TbcP;Y z%v*WHG5XEz6n{6g^`IXZ9ilI8Xqyfd9fNQ$0&3IKI6BsmOPSPI$g^326;;GZ2{15!- zBpRmgkFeXz*}3U~oNk9_%&r1oc9;GU44)Cr@{dErXc{Dp<~$7zXG<@BcHdjf$HQt> zMNnJC+VKO}!DY>r!fnlcTQv-)Ji)5Y^sVtLBd^ap?L%wiREUG|0-g#u8CWqIbo*X-^VM*-(zg)in})dvh~J|=h!xltdy=L z)J+^%j@(8Mkvroz+9kh%<2O>J%=m`VvU`|%UJ2jGS6u%1erR$1CO3E}S-iF>!l4## zx!5m~|IJhh(~d9>ySMPCT0CUB(s3}i)F5-wu!F4H-cYI8ho-@AeM_gA00%2Ml`$V4VsYctC!9X9JkqqY`qBlabAPHUi}edMCUZd0=7pM ziI@%&W(Z++TOZ+<(oUIGs#fKvyDPozDiuqzjw)PFD`AsYg!F$d(}3XjqN{wyzI1q$ zy+8sL_G22o$3{12ApIa1r@6S8Fb1}tzv4^HBHVnuO~h=Jo()HsAeW2$q=Lsx^i74$eyDd{hKUPO{q9JcA^xGgc(bitqwQ%)@O^Dc3){m*N>je_iL`opwIVs!I(xE0+c!} z6T0rt#VPT^%=^6Y#VCzGhtxksX zC(Iki+kE$NcbM6~)T+zX!CBh5ZL;IXo5%z&JV6g#XOTfRRb==~T@k`iZNYNSnr7cN za=L||CaZAejt`cXc;ntp1DFoJfIQDpG`wCqr^%#f<`QO%;T2wX=nAt`t4L*k_BqqA zTBY=p2Qh-(yT=0>r%yP+%_liCTQqdab1i_Yc^Yobq-?tmH7muB$7knR7}C8z&P80r z>V=Nj%}QC0pAu#XVK%Kg%b(bIiTT#JNOddjHq(f)%zjvYjxjoS2Id)8#KstL8r)ok zXoU86X37=cXk2^+7?e3;g!4M&weNu0*<@cCJD04-r6i=UwA0oS#@y=!zk9(6#-vWI z@|+RK8$H#|F0H-6l+wWFgo?|eC50e~PhXjZyDmv$ldLecch7i#q`e-BJ_fdE>^~Pz zcJ@d9=U6CZZn$$y8k=J(y`kL+6S5$MS0~3XD?h7MF8AG(ZXJeYH~Q6-O_)f{$|SWC zyjKP7po>0vu?|XtP4x}YD`HW;C-$xxjwqESHqy^=XnteFp4^FElV(#jO448V zntCz)?ptTSJo=pxqH$kBH5*c-w%bEmPOl3hrinX^0r5&i#M?gPPizRo)E}H%(;d*# z(ZF&a^270S!-7eHBF0z3oFvT1pj5u5swb0FMCylY#{84pKb2Wriii>PX<0PfJiCgt zw^`>!Oxi~k>Si59YDL+O46_Ox)a3Sa4S_#FTbD= zl#tfjX>`sv(sQ)Wfl<^MXs$}25r-u78y}6^YEAscFeLfE<|0yQC~#meH0|6Dc0NHU zlu29QnH0?j!f3ua$scX6E89nT=yxlXOsntvlxEFuC`xXSw&wgr_$`dblJsoUt)RvW z`4QM{B}=i3k??QV2m`MS#^xsvxK(Z*uqpfpI}H0^M8+W;`5Y}Snwb<$4Pgd(B=HAM z-m}i7Xcp#%%aZy9D&G#;rx2>RWgj!dVzH?=$$F1c&zfyKS%s1C(mnzk=4hjP?GVHc ze91+ssqs&*H$pp^VfcVxth;|i#FR;xdcr(An7}`)^R(_%O+U|t2Ne_gd{&%N99OtE zNkvxo40x2ppjN3sDkT=}C&baD`13IT8U~-`27o1tkGfUdyk5RovbYaI&-K9P)`zfc z-X#%pPQo;Cq7D5fmEZinr}Zp)Ls#YMEBjq&snpVoR2XR=N8|ze)>|7M3y2q&eZ~=}dqL6)shx_PL$n%Ind;QL!(+tl0?X9O>1m__zOt zFbV#r__raWGv~D_QoZf}h?%fAjo;n-lU3x&WD%n~F%s#)62>JbO2pW+hhXj87T+}t zp=J7tyZv+lE?em!p2`wdJJ;a&)@z(_VW04C{|#Z5OdzwZ-||dbgCdpnF=OUNb!Wwt zxjHh}H%TH!kdOYw2Jibi*kgeff!!KR_qviPF| z>-Gqy_WQ<#lVg#W=xm{x*b`eG#Mi*Y?1MF!iZXyq-zW@J!tzl}+qRMf2_PjALXH zV?8I4vgj9(Fe@B|y-Bc4TcBiVgeV!w9ub0zQ)H+vGr)G0yXox;Z?;1SiSzt&DLCl{WoV|s=lPWe<|%W2g1BLc9xGw8)aRf zU8Ksf{;Ayi(v^Mp`8j zSB5f!FPz;>H+=RVjh~FvPEF^V{7$sKP(yPEr*B}^j#$TD4bfv=z8(?Z z0xnKrqJmg>3%ITigYnr5h&&OD$Fmm0j`_n~EHXhN4c88iddfX?@Pw9(!>AQfKCO!s zjVodFBaZRcZ)nJ-yilw5f3jj{^j^(wp4pbQaXNzheHo}*7$)j$0*0r-=0qs`Skm8; zE^2(ArMUj>1-C1{D^6bSg!?AXxm-VA+&fFD)xJ_8-%Y}7AdGWJ1Yb9Lpe*1XC5ZFJ zvQM`hVefA5#@gMBM=2#59s7kL@}vs6>*zDrA{4F$^wu5|jOU}*qV<{E+1s+a2C`;%W&W?BQ!fIL&rd+~g z+vJFE=={-#N#7}9_V{hbz$TBleyh46I!_D!>36xf!@*FW?gsX(G&bjew9|YDv%g;? z&%N=L`P`?Q^v8PTYU?O=^69p0$?`Z6?xpzan#qmZl3?}yoa zbujW!7B@LPghm~;L+8#CX6V2DH-yRfl+4G_tnR2Bwd&EF!Ah+kv8+6?8Jn&qWl$Hg zcB>0Tsx{qh=zEi};}B{dNf;*sKm2-sog4gM5FA$i;)-9L=dM{DMCh(&&>EpDUZdJe zm}tTr8h(l&az!b-OQOC2EhVq>HlCGV)MG=~|6sTh3A6M4LHMDm0-x0Xzp<5{Qp(Jdaz4rGvgG-DQXwAmiEaC{My zdOSvqrtoGc?3$AxiK20udQd!a2pFe52M~4k9QUvfhoU{NxFu{6cf=$S^S*V0+dN4L z*;k6@3}MW>pX9mMpJZ97loyB}!?bo@!&d4hGOk<<40~P_CGifNgt7e;LVX2NG$XtY zlVa!=XS8@S_8Ms+Huo;4-kpT$QC)HW!a#A+j!Kv;!Yn*`oIiD{5p(;rS{0i$me+BO zWw*>(%$Vy+(b(LeO`ITM1W}*0c9ytkZA-$T%D&CLY&-$)7dLSAC%U2MEOKLNF%=ch zT}6!Mzx_9aIdSL&f7xD_X`7%{75Sb~I!zeO_F*e!e=))qh!m!f)1nC&L7yhP1)9Cf zKto(lObDRsZG;ur(`4u{?lQcej>XVA=_b8eismk1F5WrA*N3%cn#NHQ@>z$h#H}gp z?w57e0!COg;hh%hO5?%*#TYlEo`UruSfG6gLj!tXYxsI3-!#V~W+HYMJVyO#H;g{9 zON=H``rSMtjLEEX{7LuDOyf`*-`*rmu~fr~saT=OxTVCv=p9WOA?+Y(&&3`OVW*|{ zRlul_bnMl+Fxxd0!_Nld*Rh#6-mWjsJEavOZ<e;(HdUVtTcnJz9r~i;E6`xq@2xJ=>Szr znC8vW`MC1~m{~_i&g1-=&7Tp(h6fB0KWoA@%8vA%x|45$^Er}|5B5yuj|`r| ze3+Xqb8nZ7GDlK#4WZ-tV;T}nS6rdZN9c_bx`_tGm*LYt0jPX_2GyA-P)bp(T~~y998(*rad^TI!!!_e$n2=(a19%G}nA5?D{GK%|^MHPy8CO%;9zGYCtMfe> zK?y00W(iS|bPvOp4y0$e`b#Kcve=-?BGBYO^`c+U=;;?+>OMB!nQ^t%}^ zMbn2cvsWGFEu%Q5cNonYD%r#K@*k_5e!)|k+PmW}tjY7+usu20{nUVM+U9Sgbvde4_|l+HMW!8#*bCBTk5Fw{X zC#YSDTie^AKbK}f# zWsbVeTJ!h~I7U2!>vZzKOaDNwa3sDQlY#JkuW3e_wb7F9?TkgLtFBOOy98+mCLBFpj7iVO8sBL!tOfk zN0o~b#bIkGTPS~n+}>BvM#~=Y%xCVblQvWiRtQ^L&h@&x5i>I9VZFPQ9gLJPiwJW$ zVkdlS0|Qr@Bh0ubCihr}xKGB=JA4?2hm&+cVLlFX;pad5 zEjt#eRwdf#D@yf0D4wdn@|q8eV0!xlj7Z<ZqjVK7SgNJpD-=Ytl=k@*T`-jBxTBj^Rjh;eoE&b zW-=R1`ppb3gI$*baFf5FaO-PIT`(V9Y9QyAGz{RP3A#8zV5+;=}R^yiOyBZbB#$HgX26s5XRDWEr$eB=) zCDhhT6%{D!P)IekZ=&GRunC!NKBM((FgDv;QROI!oDF=-+z>bJu%t z#Anz$-@$3hbj%9@`fVJG3r+k{5;huNty8hi|1ecUBx!GV36o8jR}PbSo5@#Y6Y131 z?9vq`zJ*KHN}E|sS=A%BevmMAM`}e~r+^XUqXK4-Mkwkhj>WohQ}KA47Z%-;BVx;0 z9DZ^T`|I7sMLQwwv>Sw(-g!J<+~%5W3@uuZVF`RlX&f)_JVwO0PpE|E=|ZuDm!J1u zj3&gY3hxfxfo$h_+_YVTMOJ$-H!}{8udYI7+D({|VQQAo1`#t_il&e-^DfQcV}D$i zt*2;K#0=xxNB?HdTOAWI`5!A`@u84}9xjug#P!ZZ}l;r|R(%a+gq>iyRFiaMQKWPG0$b?^s>>I)q-DY8Nn9T#4v&wwp720c9xpTct2qu^bvL%1)>->wdyXC zi|*iejz1b%1!3sd6nyNyAC8%CQQ!Ftc)Fkn(e#jBHdTbV`h5jI-K16)MkgCZwK21` zcpQ6cW>Z!(_c2`CSBsk4vi^1Om_>5y1Ckh4sN%ZqDnix=8VYC@ipISuDfYq_+qsX} z+vWnC-W(7yL!`4n9bv|`UC9rt)@IV^Wus}B$ef#y#uiL&U|fAl;I3PPED~3G`2Hfp z;BtgI(cp~gudp+|k81_@aHq>N+<*24Zh1A>=<*z~^S2Malc~QOxfCYgk=_j%=jI6H(V`6jChKqzzwJpv13GRH>%DEW|!*1G&}0 zeDn@{gzrY5p95!NIno?VW;ybM0J;CC} zjpXgrRmgAmP`I4K#}VlD4lKAfqZp;isQd6BQ! zSins0XwJATD@9?mde{}eK-0mEEnYj5Mo#uP za8|A*_q$k&CXJq8>sJlA-S}s?7f;hI#!Z81R}TbIF~#TP0vIK}N0Chkx{sCg(3Vm( za>7K9=*ma-nZgXUq>r@GC}sa%eyknk1!^Y0Mb^SUFjBq7Hcne!x%CGbZ9c`hCYo}( zT3|}V8_a9B6=tT?uw-}`Ef=q(CYc&^G(AM^zk9`K+DOsZ5ys@LGr#oNOr~s@TD9Yt zJ>TbhBAdSUDkI281zl%?kEBeoXX-@x=*LEl<>o_P!IDm&AL>?O;yvn}uH1|6noF=d zrviE5`!L{yhlq*F6?fWn!rZ^Rn@_U?e+R@b)&yGYiCO>g}H%eRs6b;o;D zk8dh}XIYP7nJ=JhuO-i4@ETgbU!c{AIXFMV7wrrVU`)aabP1`(u&@*r@6M= z+TkriOP?c6V>)Jr?t#t{51j5b56c!+!z*SV>|aawn-7=8XqFKsF=Rb|)8B*9qh}-E zlCE%^mdUo+9LKmVDF-{PvD`GSoCahyli&6FgOZd|+#JzFp1%D(i7lQX`0aFz2-=1& zBit|`ej3&$Rikj`PQ1!nB`(?)3FAf>a`@#VhxjoUWh7Ki>&N(P@n*-~Th5f;sz9(Q zNv*DZ!oZoj^7g43@?pc@pb^tl&e?uMH60hn@3(+af-AObIb!uI4vx=0;}^9n1hkOE zu#F|mcEaSm9mVf72w^tcP?n=upE+wE%cdnN8SA-~Fng~h*Uh5;bh@5=v|A&2YRp?C zS?I{qtjjTda50{lnIOP*FIP5f&3|M&l- zNJ2s-TOyJ@3Z0p`j_lb($d(W)N%pLzQfV(r+9XM`rIO|>NtEoBC=wxLPqu8|$C-Kk zKJVMFKcM^VG4njnc`ny=J^Triw{sLfc||OIvieW(-byOfPG7Lhpq(`4jk;9(BWZ4* zw~_ideZYF#QrgpK;r3+~mZ@fVH$fjK=08U3!{hL5+C%}=2)M8JTv$hV@?D5 z;fy0PwTxwKbBki8apz}2rD~hngkI0vNjD_4lsbQUjd`cE1+|^|yiyFw(}rZ_L=^A? z@HJKgn=&53|I;Y^svjd@Bue3-r4r^#nhl@jl+IZ8rL=?xQVbSg!29brYY`XDk~}`Ou!7zhG@+YiS*cE0=fZAobg&Aq}0>fWU`s zr88cAMvGxL;l(#|Gp0_2-`&o*tp1xDVD<#2t9nqTw0H=aBVzIhQ?qh2KU$f~xS3EO zU{yyx+wdIgt6Rf(O(X?zThet}ktlYfD26QyY`{3^NWIQB!gAPMEZ6_T&2t}v*ez{f zKdYG=Z1)_W{kp@ydWi7Q9*dYl!eqv6;twrXGDo`7-m`P1Y*~I88{So2;n8@Z}2(UDyp}w?!9Tv_g0{ zH&qygD?e~RF*8<&M15Mv_;Ziy*oU?5Ota?~LE5X*bw+&>G3~<|utcUKjhpZV%4c_w zJgJ_mxx^rCn+7iN-#Ne5FY)f3KCae^7OZR$Q%RVZpG*0pj(3=fE_B?z)Y00%{VjId z=XQ*$ngI;WWh9C{+g4Yorhb0|R^8W;rfvNK-{yM=PkF>e7cua;qfYJI>Nx*9uc1D( zGbVb97)HcAB~0VD#eDXWN~XIuEudQWu-30AW<9>jB&s2x5-PiplK5~N5tG^!*9<*xwpv=YMeT57u*oyEl+JzYUZLBIdGOcxVlT$?3O}&tCk5Y1N5Vof|ju zw@&7O(_TUZN>zU&;1RCe;;otAhXQj_gtyMoym9$s&Zd4eRx_hF-YvJ8Q z(h#VyR$yN5sT}Lm$XPv_!BzE|z;%wMMehwa?uAl}0$V0Nw7-Oza@Cu^zvcroklxLE zX1v^3JDt@l-N$74e8S;Jt)v#~zYDVK>HAs=0)Lh4y49ve44$XN)?zR2omyKYwF~63 zj6J!ON7U+Un>QCYzq@dlGEc;4Ehn7~6UE=0|BczBM<=(BBINnr|5z`-B{KD<4_Mc! zm9$jy4cj|*kcM1T7c{p~3ULyqO+{CZyn_do;fqqb7Gkyg0t(ps8kOKX9Ue;D?v0~S+8=dvPWWQX>Lb0O*2d$I6bEiP`&M2t0IQlDG%O+8w( zF9%cFb^3YcjB`isq4p!*#i~xQ`KW}-uR6AoR(AP;Ayu?QCu5AKF?m1#X-Vxz*kbjw z14vrTB5eI6XxDX?zWBBTjN*wx^=<-1%y`1Q*(K#of45;T4yAS4k|eoRY8tyhD zx@dbz6e{164uVyTIcMFkGs2#}pVHI+$$L42Ajwe4BqB6HP5xS7%r5 z_|TJ_n|;09dQTSK7=tT5XCYu7i5Mrs_)m@H|FzO%C$Qzp-Y3Sf*JmwY8&VBrk|eu)`Zicu>4iA1+bY?T#28JfwNPHp5~-m2%WyFO+|G+jlqB-c7< zc9wuqh&uu|!X(Rg@E!NGXY**JJqSO-6(@987BenfKiUDat*^Ngi43eX+>OF14YbU!W6Ds$VdEc#TrbeAkDsS6pGa@axKlpvIaVT zR$1je-N?&Mu5Z;j^wPr=Y8Lq#PV=r}(V;3B?COaKzrEOM?F=r>6!{yPp;x{g`}>MJ zg1sUph%oVa_WX}MYOKj@THK!0m#1$VCEvU2&6uosC22Y6u#4o^WtnfFmv9d@6DUt@ z%X3)JNxOE;H%NvogtPTN47CVApX-JwwtI*9ODE%qmYq<|4)NVY6UMg1e*Wm}X67uJ zmhAd%k-u8dQgLm2Yqt6V5AB=f9;9}!w0+W_BE$F&uVAWahsCMe zNIJS7?Awu0&i@E&^06gNcMveI#gUdsm^u4$`566AOwB~P#ofI~k+EmE;z#;KMtf); znor(=-F*cj$32C4L5a|E&uBDxbR+X{r0f-XY~MgZ^arqUay$xKcEh_HbQ|LCf)0x* zfQJ6|iI{Z4e3|}$U#fV{m`$Onv!$lI#TH$Kf6N;pNYiO4g`4-_p*Q<6oFrF;giGt0 zm2euJgZL>AaBrLw9>jXXW?Ccyy@8`S525~RKg#203z#Hv7RVxu`{7#Nc+Y+2;Mj7d zXNjidTHId6mWC)cgS{a1!t-31hs5HCLbSf(LpnuHlp%jg7EZ*Mqf@^P7#6i36Y|qx zv#cddL8{|%F8GkyTfiI?F*3qj|8z3;GX9`sR+|2&a(=}7$vt&5?j zMN&9wjjT!^wWD3C%i23=-*6UNUnc?Ihhgp$8~icfPZsR%IC7NE)du>);FNex^gx_C zuMuY9tkb;d6r%O5s7Cc>lOlrRhUikQ2E+1fLaclnUY?Cni?oeo#n zuQh`eXPl+1`O9gq zdTGLKC=&Apb+;-ORCQCh%Wy7M-22YW9M{0nn3e^p3^O?){3 zkvGb?JC0|#vZbpKIOGO*$aM???<~c*Sqp?}j*FNNgvqDqg8uJUGrPZ)DKnj?%d00W zQ~W+mE<93qt1FerUvL^G7bxC1{i1NaTBvpfeqLyY z6D7lb&gU0z@ZyZDoQ1|AOBO(nBWK~c}dn;3q!r@3hY)2rDJ z{^jE2eW4p02%nLQglhVUGqgToGTUbJHBZYWZ5zsza|4Gku+~7PPLE7gVaMM68A%x1mBoD9vi_2rok?fYlp}MSe^_4n?550)6hL*qvIH?~P}_?_ zs+CG`sY*-O6i)+bqp z@i9uYJcnu$C1;$!Kv6{$;VOwm^C=3ZJsyd4GeguC4Z{@aZ7#|s0o$YcW7Gve`*S>g z-A@y$c_U)%2(x|oCEkC5iS_(Jw7+qkz*PR8Eic;hROZ=_68Roc3S2*m{~|fODsjxd zLkv@yT$W2O; zVKI#`35Vb?hlawHG*oUqNWYy^FsJm2(?^WaYDE_uw7kTvP=?`8n?GE-r3Cg?e%SDD ztAHsMF&>23ZJov=reebtyj)F{As{VKji zV?SA)>rREHNWJ!v0W<0Df^6jhk~ztIRK{gdjUIq!=S-c4D* zP{@w-LQej3j-PsntDyA6p)+W<-aHWlDSA>*bDw}YEl!=GgejkVj<28A-um@&>L)$9 zgt4eP!$?;oSo^dUF>!06vHOjPQOV%A)29$h`Ko%?2ViPU8CRE+&5c!G3Ll+n&cNRR zUpFnqiM^)GRayz%Vkb(Hf4RaO&JSDjMMeeh(_e}3*tz- z96uH3^Panf9wp+x`T6BPE9vd$_G$&GW=ROxPrPspIussv@VZliBvqNsx4KC$rIoH{C z29g5{IUCtdJRUa{xt|M#YQBrrWD;ib`%`>Omll!^D`*W}R4%t28o}zkYZ6j>Rqw`D zI|`+fNWMeA8~3YWXs>%(h&R-pw;Dy=OS$^*pSa6S6QT9!3^y&o7dLBJL}_0ZFuJ0l zESE4HO)l_xAtNM@oXVA*k`nn~?I5<}0RvW*qNu`{Z=!_QQzFLZ52f>MIt}yU1F)xz zhZna>IIhJnZrngipld4klX7rPUyX)aw0Ja>B4P>%6J>Ue-@rObzRV;q?)o@pa;sfz zM_sTEa}Eobj7gDDx5*Kz(QX+^JqpBd;Cgc}^q-Z@eXZ5P6FptRT#ccIWsG_md>^q@+^K zj$|Ic-OI)fv1Rr8ix^eZvCHOMp_=^EU}`XY271&>WlXm~n5P`)OjsREtTlrFlSpm~ zdl>gTjF9RpwhK8UVxADDSKt|*V{;|8!)WT9HbqSgy@&RQ16)|U8MNx28BsbXA5JO&R;kl(R=Vx(@E+^Yyy{UM;nkHg?6UO#o zK3`?^O=8rcT*)6$yngZB`>s8sP6xz;ir?_BM?10IP2w4sViA*48-cP>dBP0sPMB+-&%xs70sPfE zjtz?x9L0WPKtM0>mg!t_b|zA9QbT)*c*^lg)N&XRW{>|hzRcW^Ijc`scpqEv9|Gxa zt*68PVN|m~_1gbo)R$0r8O>=0Y#Q_r7jS=vTcD-o09Zcn0!PQYNV_=?&GmDHYBWVm zU&17hFX4lv#>}do)De@*kS+DFWcGGe`#+3oPE&=Ps=hZ~+YZ3!@_D%UgkYd`0bEME zp+%rGj3&8aU2GRbOfE*dvokRLkW|175-~#v<5*C_kFf5~=+nwZmK@I9{pZhW=}+cW zIk(pB&LPr@BHLGziJ4Y5s-LGzcotM&&x_M9LVdjfY-cXTciqK^EpLtY6tZb`bvoYW zO%O1v#dkBBFzY+r=FLI}Fz4t(^7Mdq@@B?EE**O%Uo{Ij-KTXL-I&`h&460oEfSMmVLrN=SUoWyEu2=h($gx4R@j~PC_ zT$$HrGGE-`98E9gzOxEn4N=(+Jc0$vwWN-vDOX;&P>F_oM9lYA>0iw2E)+5D)dp z3qt0-`X?D0rcki9X(TMVZzhbMW{EYJ=6 zJ#x`Y-4DaIZ~~@I#JCVfS1*BoS=*Nh@F-UM6y^P?;}O zTJ^>ohlREW+B1%z{BIl<&N9Q3>JeC`=LwgZ$!Kg@4Cm%h#OjLrwAUhL6JeHhI>Db^ zZptXPl7iU4RNm!C7x`#42gYY|n&4iw?SBj@@#H3cmj%V;cr=*Gp$edFu{<3WuNg27 zv+&V}=0ErT82t1scJ%j$)sx{uHAlrcZ8u@=pSZ+tpU{^n-AKQi7RzPt?j7RO+JrIY zqfWx%E`>0>rPyie72z^VY)P@Zw-PS5Da9fx9#6)zc{c?)f^Z$Ex0XL1pEi18_m*QF=k}%3{IlR^4uFRkHq<(l= z$|j#5A+!1ZLOA7!%%@h>hiC`z@;dcd$){yIdDtzl2syVA(+*-^qzxjNfmokHI-4F# z;5$DTKlI|U2~&h>zKAQEc*4ZBjN_;L?97a&A@KUeZ}!gS>|Z_t;bV@V@WVv7tRQju!FW`~isxxnA|{P6^QY|M zcl2t@Oxa$pbl!iCU9rMS-l>lU>yVH`nZw0G7c7-kzOJtl?j14_T39S}!RleL7w1Vb zTJ)ncI#R?tchD9Q_9x)>?+EU%GZm`I7BS}tb3SY-|DD%h=6F+gY#U!zYyCy}D_(=yxaG25FbdB~Q42lxn zM6MzxpD;&zIr6@%ze%=u(h$(r`xI#QK8B7K$5Em?K&Zw_#1s)`)Ql~>z2c?BdtJHm zrz<0$_G`3!Tgn~AK}P|fDYp?M&l4IwtHOcPE@orPqgz6f#j~Ty`n)TgD=B+zH6zO@xPbQ{3Ow5oQw;z|WMQlswv0uKc&& zhF!;&%4UV0XPWbh;Nw~W?Ft1<$R%WP?k4?)c(^Pqhri+y4u|<+^Otdmx<{$KCGp67 zKNoM09Yv-=I+{|&bLc(d{^lKFer?^tr?E#QpQxH3r=9GQ^?CB5f{Tn-?KQ;NlO~$3 z9aM?RiK(}Rir5ES z3tRXNJElqUR+ABPowt0_s1Uiw&%S)~*PAd&dMw1|R?V_nGR>>o{#9T(;h7IVO(G9h!y4d|G44;2>!|}WT zd@>40QCCsdX(4_H%m}k-S1g~i&R7ymYXPTHZ&~G=&$3yEb$PFl+sIf$7KL5KLTpam zZu;#Ezly?`$3i~z`iC9}FX@VH$vx20E)uKXb-=YVL3pts1lF5c3e}txtFa)=rN%>i zNn;nuqP28Wm>VMdygQotz?#bn&F`RkSS_swsDm7ZYO8m7h%*PTqJD4<9uA%cG%#L1WlthW>G3SUJGLl}K7h`+eBy<`Wi1zcL}V~3UU%oDZk zvXpsupch{YCp~hmlst#YsfT2Ixr*k98fqn8h#ZP*?G{HzcbB@te@z&wdUS)U?;)Hm z3&lhm5i?VKXcGzZhTY6Bo7_e+lBB)U`y{bGZs!=afx2U|_EQk>&ssRxmcVn+3s}^M zm=7OBj4}LZU1p5snTBLI3&NK-lZ5*O>9TlA@v{~l+A0wgJO!mKv-=2^x}av_o$(<~3PKJ@Vn!#o%xU{n#|DvWl)3)F2EF`Pog zT=kBl-fLsAP=6v!ZXKcC9b@pW!x{7=hu*i8WkNNh#CNljFvtG{^1W_x67%?S<-!IF z`DcnYZ1MtoC6TM%jnmv(L%yuDq%iU2qDjlY&GohWq zqvr2XC}z$TFp=Uc;7*vwwTF4vzKbLlWWkzfKUv<7ImQ-T*~0_{-hsvCr*vyuB6y=b z+mNY@Fsitz+Y7H?Y(h51^mIT<*=p1-Ou?JEQ}A-D0uR3)#`4Og0;a22%{Ia;`If|= z80RfXOe|L}J^q+KVYiQcay&zLXr6?I$L{0ilA%E6y@gxP`h zh%!&Zl!S>Ga-#&3cEr;K;yeLUEmq@07=L8~-((phF$gVJnl-d%X06U*cl*5+FfRNv zWTjA+&D>W=yeDGHCO?B!ND&^})3VTLK7wvLli1=Aedea%rs-{%U5iHd)YSs!p?KCA zOc=R+48QM6j-)B5Tv^2pWKDc`u~zrnv#OC6xvvflE;Limc#Xo<6q+^g8eO*3!F~T# zT&TQ?1JtEV=b8rsypyn_H??yaUj?;m@fdi0rGN<&F^33K_9U1$K2#ye4xxn0#bxZt zWyNfAZAZ40>^-WKc=MPWLKwZ5#bdOOxhCAOTl-SmJ>$!GnmPw3seknK57E$xo`VZ| z5AntF2=>~G0)K^wNhVC-Egyc~p6`+*`guxQw2{nDy3962w_zJE+(l!j7l`|PlT;54 z;Ql=(D;8y{RldOAj?^r5`%}8^*aeTRVYu?^G{#o$#m)_%adPP?^riG`)o!gqyeXvJ zmRhFiUOs>(sWzMyx;P(2C6W6qgD0P+2=Zv zU)EyO@NHPNVL$bkPJ)Z!cKm7o5q*76;1kKPRhS_0PCA<~pB%k;MM)3F(yLtQ9vUgj z?48FlRc%kVu;`wyBwiLP2;;~E^2?J4GuJnlEBC)Jp?yv@>*dzWRHK4+U*u6EH<8_y zkI>6~3Zuz4(CYIW!5DL-paFip_n~}uAY7}DlZb2wm}6fN?~#nYEk!+acM(%UnDxg) z`JhaWS>sZ!y!2!>Gj5PGYxw3VV}18N9Im~A%Z3Vk`1BcDwvkwgoL)W#?@*a{2hkyq z5wOw~Q+EfTe|i$43|FD)n<1M|V1dg1MoG17~t*&k;%G8Um#f;TE|02yS+8>Py;SLLdw zC43Sh!sjQJq5ZJgm|xux2YYj30HAq$M^vltng{+QNf zES9aU#c0~%D&P1C7^SGT`$U*Wt2}tGstt@6Z3;DXEZLpj>)34pUnNE-Yv8a+)Ij}> zXoe?QMEn~nkgIHhHC6bv@-ez5%tg%?Z}{3D#G6S=;N0#TE)F{a`GhuRG zFW^IE+nFx3hSnJ|ll^*e4Qtjxi^)o*0lel5Y^|TdEAKbzjHqA4lS)|Blk00HYBW}RmiPGQ%{-+cP_nNd^JTFv z`}9Pew`oEka&-8l@#a$6)ZyK$&iiq5e$I8(A0?dOZfcF8h93~NZ3 zwcqFP0kaP<{r3_ky@+?~FpzazRB3I_zl6yfa(H!pCFH7S-T4fcE3`)Y`Wyb1b?_K* z1sZftmQVsaP}V59<0U8eVe&X-6oDed!iAUm;^`A27xN zdHIoKy71agdEJj*W9&3_Y1)!6_)F^mJ>_3Ce1DEGiUbR4r3;syV{qiJ6ApjW!`$M# zxIAnHzRnl-p7TY_Ai_+TI-hrnieQ{$DD&P&#%$}M$*L`l&TnY<2Bi;v(Tv=HwZGJ* zjXYVedOXF<@oLf;`7a?omV<|*G;zGr4EduM;r?zNNQ-aaw9_h#A2vvMH+w{k6=9yg zo52@uiDud-k@9}Cqa^e~Bh$TYKbf^#1FYFUBp!Q*0mUt)F1^1YZpSlhs8*9E8ook~ z?2e>jugBnTQ;(g9EoqklcF#;y1JtFs8ilZlr{fRE*^n-Z9LtW7J^7%0x2A zuQi)()?HSb_7*Ohe-Rn=Uaub!&IsyNo54aij?eJzGi}F2c z2-Gg541!rubJP(qYx4z+En$L}N%(DjcQ(c&x1JQw3{In~?^~Pm3zAPUhC$P0jigRB`STZbpFap;^rg?gLoekyPQPyHumSAntGai|vboZHLYWPyCl zl5;ZEyHPp4RPRRasUc15_8kpXbx25QA!HEm{<0Q^HtMX@z?Yk)m(L9yyjKzQ$R72l z>sS-5+j7-fz)>8~I|=hJ$CW>*Ok%3@%9U&9OXO-H6=U)>t7IxYbm8$|7OAMpK;A{0Zay zXcgaJlg#Y7PWHGjk^KG5CuG50!g*DKzs;VXsPk;V%Q(@6rqB5A&4W)mfE>|-uffVj#@fZZ+%miH|?O@=eMQI>1rK)oWDRXgjyVA z{}uXps62&1TYiA+S_3VMsW=rgSP^YKnj7&ajGKAxjr=z06xSR(%(<*zEc|Xdi=VYr z!f28O%cpk?(^O5T9FbbGei84PyN;7&Lg$OlAL+2G7OJmj!(w`f3UcX(HNhzAA=-WR zhRL}yHoo`}H>jkDTYIf7_x*4(tb(3%eKeH<=BZfC8N%cxE#h6R4m19Q+1bKHwrp27 zS&2NBcd%FO02=6ouo~5Ezu{Yl7efCVl~209x*TUJV-T^?o4ZM|UtSXpvG-yGH|N3y z{Ba^d`QQJtA4E(ZVM3x-@Y=<3%=IU9!|wQ7&gGt9-R8Dt%oFbmot7Hu$gb4kv(RZt z)dI=32aUkFBrDyYjeyecT;CKE7;2Bi+9&ETk1U~X87!_jn+tQAp7_uT3FB|Oi(k_= znQ8Z?T$yD4QU2~~0Gl`Ip+vP*SMAo~c94SD;~ko-s)XYQ^%nI)3#9DG>sXy?iJ3pA zBcpLCqDDXDUhPz3<)FT(o~Ws# zputS-Txdt2+D2*5uRvT@0Sfh>A(A>{*-K<7Xzq>mN5^Aq^#VkG=#IzbH_?fmj$ubc zNB&pwp;Z#*Xn7*P`tNb(-y=F5^jI&Cz0;L7dzr}ujiV0bODd7IwL~~fDRsL;8+RF6 zt$B>yzb<3u_S;CLowWBPCzNgQr^~PRT(5Q)VYO;73VVwuP(8(m_LMMQEzj`<#c50c zVGd+=VqX7vDH*&;hs_}6uuI}SA(x~6c?}|cO5voPM?G;K!0Ch>SzfuwemVs4)e?BE zSdFO$1{g&9)QMV4@Qf3yNf)bWAk4&*+5D=H$C;>`ZGf%|3Cf$e%7}A z=f5G$$9kSO=Tn%#8?;VqIb1d*^|9P8egig(g?MU0j+Ejfl~^VKV&nTr|JRX)*5X7^y1Jh+c08yS-;w0l=y zl}jqRTS5qsbImCs1gNa%IV{Rb#^r?;P=6;y){S7?pELpu$4*1X$sYyXjD-R1Ej~0o z!b~)g@tR|U8C&{#cK^~#ey-x4eD?4jZ1a(9;hM-L{Q_p}5c{yJcgw&bjUq%|A zRDAwD3%)MXarScpYSwo|^`>C-XtfTbmNW~KjiHF?P8gkQ#r)>;K1_LXxiUllv~2p@ z9C>=5S|+9K1=!t|k#X-l(t;_Tz+*X@p9$RDlPe4g@K~`tyhdHhFTRs>y$_0vF0Kn zfY#|f$*$!J#A#;W9J3#a7ZXt2ekd+V;}Ezpf!kDNjXw{^Ax1+-s3uOt3?odF$3uSn z@+Hj1Q*=#K^iP(n_fI}-W(s3rKsV`>4BPzmG?sc4LeKoXAiEy&n}>PFbV?i_jASbf znD)QS8TInS^MVSlmxC1^6jSWsV2Oaq5i!<;c{{0^FYGyX5^5%rg z)MuWfAhV0~$}>?nr9g;mRmrYZF>R_Ik~{hh!R8osoVZZTZ7KIhkXHm(mDv`D&rZe( zosGh0&0WNdC(MKV`@F^wGo~*sZq>Xs*@#Xp6x}j?Wm$X93T;GHttwT0*dtF;3tmc8 zZmgw|M=q~6?!P!=-zx6eyEWXd$!>U`Q_l^uGsG7%F}+CdCsgxY#LOVfxl|b+|Dq$4 zc!(CarBv|{)`h31;G>Z$L{F+Rh* zoAWCGYzKcXfBao;!!HVI3bPlg*(y#p3kWmDC6}-G@07 zDLB(QOUNKrX*pCE`4(v@P>C$GZzW;ZmWSMxk~+?^n;lml;zyS3dtC8@ChiCY0Zq7Z zOTZ+FQ>PPQmX|5{B1gF-PeGBbX2<2*fAm-61=R>~x+?X9Ctaml?8u=o%@YW1O+sbT zK>2J+pvK%EITHg7g#Y&EVkbo7?1qh8dHZl~(dSu|BELbp|@`+YaLDhkYJ$7$4A9EFbqWv7jxt5u^UK|84Gz51X{E|=@~mrER` z$GJQB;nvB^+*`u}&TE7xn)<2<)v)4W$`-;TeXilB#JWrVm6j{LQtIVZH!9_)$Lq?= zC>Of%QwEGwx`BbzAbm@UaP_U~!){aZ_}~Cy2Bp|%-C^&dDgZ@mO1`| z%wjlox7cUPWhJBSN2w<|tCvl^%t06tDHP^awAH_|zLhHMqxN48R z2)5$|%v%wYNSJ3=^ZEPX>DHrLR45zjp30xsd&|{2cb2QO}#^&1-=%x{J9xk3;ZRn#El%P2*e&mZ4_NF}Z4_NkmLKVX_KJ`RI?k ztY5aK$ky_1vh!|ZWS{QU%JkAmaA`&(Yf1!VKU1#iONuL66iz?cIHb4-!vAF&7a`Zc zsqBAjQPnOKx!mK*4PJ6D+09rdu@$PhBVw`$6SDR$ADpnk+Jur}GY2Ke*Nz@6x7T%& z1yLw)+=v8NzYay|DeA`D5CxS)@wQehjP&>8&*Zz@?OETr!IwR_TcZPTmwq#|xNOcZ zem<(cu9T^&8Tg<7hAyUENLM79ZlPZ&MGqjYCRX_n6Rk#LLMgH5bD)|~#y)vq1PxvX4_BlUO|#}^qwBftg*<2wnM8zSZf zVII%A&%3pGVSPluLOEHI!W1Z^?C3Xsl6-pgP6wiqZ|93Y-CAksSRMV2LD-fzO{w?-(tc#6BG7t1~Ior%X| zdT;?nw07R9i3x`jcap^ykb%4Y=XC?XhRMJtrGwjQ1V7(*b`gp_;E^ zHR`J=0mh|-zqxs&WL29ArBB9BnN!Umrr_^9#%WC;vRoq2_wXKgt~-RDzx}cJ)HZN; zL$Immdbmck!lHR5+|kE7xMSZ*Gw`E?m3AZx!{pCg>E}K|HTT6E4;{ip^{n7ughFDf zQ=!xuy+OYATLhaIwuLb{y&o=II5utDiHXM!qWX>>$#yrBkBu-NT~TtT1L|xUuG@YG zPMiJ3$zvtl*m*;6X2DA?q^;;CvJ%w~`h=Nss+|9>w??wMU4=5z?3H}-zK*QNgo}*B zHa|2!42AEM?G*GE4IlWT=&lFK9v#5S#cSYR-xs@vb>UvyALd>z)4|zCf7z-tmiRic zjM~PqEC1t(l-*hQ|MUx;2Jo+3Pcm@gwTn$ zn7ZGUGwiP5>c+RnuXzJGO;bDU2ztrw*uGAv=7)$GNtn+j&-l4x6D5qV%f5Wu#1Z5X2!fv{7dT$$=C*Jhq!2%e8H|VW>7&m)7Nz;>b?e|XtFzc zz75C9x?T9)ZUv0^05t7i3d0I}iqK=YPctjH72&P%_3>Z!yq7&*#9rsBE^QF1c_U&b z6J~4iAAb1m97&6(l$kRAy(}zZB&(KlTT-;ei%c%B?V8xgVS2 zT&YW07>d4a6)=f?M9kB&VMzYciL)Pglxub37x%+&AKPY~4ZO$S;pPoB5irw4j4xq2 zy8h$)9j}&5p=wGVPiE|njb_eWZYk+(zZKfI{n6RX6>-;S(kZ2W-iw!FcZfgYs}@0W zd@y`-Id0^+WbVb{mYDlyC`W1@?EG27eI8{cU;@R57D||Aoo4=N%>&6qIv05R-YdUV zmV->TTbEH`8b52<{oI=4QZWb^$&3*{jya>h{EYR3Afos$81h@PL>1tN0aWV1{ zaLT^RwQKiMn4vd_K7v@n*qr>%&nmtzu_Vm%10j;aq3JTM0hfeo%F6u&jDL9uI#+HI zFcy@jzNzCP^t3cXoXc3wx#a=Qjy8iO4&AwzABW&==_}5tgQif;KM|8c7!$AGeE7%v zl7a#{wk!B4$@5lI_ zi#24b-;K?~eL^+W8xNp+pof6TsPqx486MRejAJqvxiyFzyk{5;{vPDc_*>xn;BJ_+ zO>7|eUt^k5!n}UkL|TqgiOB_W z12alP&=2lT(TADb_~ky_oUs-#;F`Fy1v4q1q>@bv?qjF9P))9V^k`!r)o6TYp{!_MKfkIgL&2W#;JB6QeUhSFsg^v z*>i<}spzv5O=dmOA5il7d<~3nHhCAerwSoEBS9X(x%2)V$s@_fNGa6}(GqSYkeZ@K=#ds*Ptu!&>>JRSW zJZh1A>@QanIvF2ZZ-UF4bOG~M9MFw~iL`vfYv`Ys6rLlY^4T<5-h(vesqar~)mlJ3 z-XDG4Hlk;8FjhKmL4~OczK!%n>ZKK!GI z8$6GXL;37&NDT~z_JIZgQ}v(!hA{Q*OZc5}36hyv^pQTr%WUtAmX8`v0UGWBNSPdh z@qhLp?KOGVXr1P}aXaO61Yr<7@qNT7IPF)b&T=(ekI+!8pV1Q4Q|<7W+YRr>*#ag? ztj35iy_EO)P8)+HW^|<5t8SmXy|sgkW8;LSdQi)7SOogOVdp^ao0d3}(si5yIM zf}QPrTpzl@Vp)ly$L}mr0bz? z?f1iRP%e@w8NPVW0nGgT7_N5$5O=T;1+u#^xFjl5{`(Nv5a#52IX|GAzvQxexw6Z( zHf+xqM_BJ65?1BEF;^rB_PFL1slxGt{qivAQ@p;)f_3nD0tS`_VvzoHxGc-S&8J!T zJ){Qq1tj{r7${VuD}L6d5hkc4jXxz#lNc>3S4Ivplc!B(<#)!V2<<|=bdC${Lagde z!s_=Cq3uCXn`1)%8%0Apobza~@7#~;ns?FPz#ZyyGB6|M3gX6#K{E;BTELz#y=N); zrjbFCXOsZ*!F&;OJE}ix*KRUvo|j6y<_whSCZMwUEOPZyV7vGTKG>cFw;&dC%OWwN z({}W77!UoM$DnQQix<7mp~RDX?^R=kYSP4N90~I!>LNdcJ0d9@L8t0l!`VGXAu^Mo z7*-Wy;Mw{-RE`zM)}Aifwjk#A-GXCfPWEe{(HX;@XSc zMEAm2pBtIX;IYG5^OZTU>qy2JYKQoZxeV=4>LqzRQ|RMiUwIOh2d1Fyw=Z1lJ7rvo z!&aQ_u7lAl-BDrSgBf(lqBhOc)&AX(OidKMqw!)^%mmY@E!fDM|L z54%w6x>%KkeqXOb4`h*}!(o;GCU@Z(>?$3J;R_yd{XQpf!8cZ+^@V<@zI*_y7DOYd zN=g@${8YO7sY>AUzOnr z^(ETkegzq6S$MW$9%9wCVY#OzwrKhxw5cVQp4fyHMZSpA6EjnuiGx$iMj+|v{(R8+EG+gFAZraZtt+`kIfG=is-BHcJ#_G7 z`8#gZ7cb<`vZ46NXfQ91Qd0-fe32?nHt~cBG>YY?cXg8tq0AJmWd|iE=X=XO6lODe zJxKdZR+2)x6)aqK7jc$F!iA(yk5YI#T*9jo9~fs1$FRi%F>Z4*T1@GW+?oT(ymAPS zHj9_VmEyZeBh2G}$$WXegJeWo>PO%?g=zWTn0Zk#n<*nzcNR5qP~8;THI$)jC|wox zP@?k5O{mlL-X)!#up7d`FUkO2{zk$u%o?B4VzK#DJeE3(x40Wb%sIm7_DtaqUR^F} zNe?Zx!GrlWY@mEr={jEJBQPI*Pe@MskaizV`PZ@K7bg7SF0EQmy5BafBWSNG;#PXLg zps$MWrid_`ox}KE*Oy45sT%#t6YPNS?=r5~K&I+P;1YVDG`3_?`hSF-d0b8F`}YYU zQ!;gukW58Fl)cv8pJdLI5Hio1$vh>QQk3RNgGwqQp=j;hCMlAkU6PQ5kU0*?^jvG* z$2sTw`+cA1`D6dF|9Zc!`@YsaUBl$dgbdmk9DbR6cYETy#3ETg+p zqVh`BeN<`PmXcwsPv3!Y&umQpu>dg^dWh;+5BFa0LCxB)ii6!fD3x>!zSu=uR zN(f_cX{rgEnWkgX?jS$)c`ZTxg+Py zSH-c?9SH5X61htYC5$1Po7aSCSehW5e7BQZpih-vE$XShyzeVNaq+3rb9Etg;-Pwu zMfot*eS}i)LKL^p!`oH&D8C~Y7s^)SU{nj_M>oK}rMpnu=9%KhrQMLVS%vfpcDM~> zp7xnA^ED@hnshHNy*=G;uHTTkT>Qpw`Vy{;c}V@#lS-wughg8)p}M+I5^-p*T`Fls zbcFj~zd8=`bq(#LQI-g;52=hQMQ<(ZNnj6)pP#v>NU)kfxL;hvREeYdZ%B*pHL`g7z zVZ@GO)sJ#X71JGeHn&HI2YN7jy$j0@eN%+!c;N!oex3_`DPcOWxoJ(9;a(Sns(|BM z_d(QvR^CD$gP4q`2^>qD^uL zl`5=<+2CIiW(V^$Bf@n0o-8!|A#hzr6sjjaa_0}cGL@Hiz9VdDS}3VwXVGd9Q^{N) zvhy`m{=5gxs9dBOd!Zd^s~Hb#gGA*nXj?VG^O9hc?pcE*9kvSm)h(e1VcN}!6P}#E z#T6?G)gFe9yk)N`ayR|=7q)Dt<#OM>zdg-UO%6Wos#LVJRF#7k$~|x!)E--HTVTS1 z-8lWUCG0;(q1W>5FjO>5(wD3t;5x!X-J=BqxGVd$zLa+aINoL1!U;*u2i_<>L3~E}W?PE2jNXw3uUuXxeASL`*cy7ew?0NHp{ zcoY|6MkDr|0?VrX@qMWU3SClRX6u2ONvw3SE~{a8BFxy0i9%6?E?-}lZUh^54I1P% zL_YF{g*>dwEqIy~qtu!-iC#XCM1#Zc*Du9(MA4yTNAB`Nv8y5+Sc4}WMkYJhG{oC5{d1A6Yf?h9O;cmQ+T+vID>C` zhY;A0VL};Z6Jf4cWRnE3lG=59H%EzU1pq8u`C4uFY>!UBN#XorY03Xgml> z3D)Q~*_6glOcjrr=Xw*R(6~B(tjhlfCz=kzHHV?{8~FPZJ02-x$%M&$Njo=eERB+rAjK$`?(Y`lF5aX%zlA zh`fv4B!{lY1}%s%%WfPJN=?oAGuJihz)3xnew)+zrRnYd#)#jIi0RgnQmn|+#JLg6 zd=|Y8!xMfWRIZjV%<@6z6zbXe<~S}-rJ&eGmYih5Fwum`iVYC#3i|NFGBoP--to!- zi~RX*QFrOWeoH#ph^xSFYs6wd5hG^X`6h-Ssm2PuG^RKa=Z_N~WN zuO{j#?Typ;tXCvLbMX#krd~(!dxj~UnIl;v9ytuH{ZP}UKjb!@(YC|~8>_AG%px8? z7azjuF|0_|iD5Dc<2%Shc=fgypP!^r51CRXpOAf1Ica@3FP_sxjEiNybbu1A5tq)2 z`^9vtChc#3A5<*tfqC1FQP=1omR{wMt{001(TDIcjokqlS6T(~+T~($+(9hy>;m03UGWD!hi6_K0Q)wv zX!g(_rA{5BxmnII8p13;x>;EL#f1NnrcqZvtX8Twl_={p8^h`77f5TGdkDjbtAJR7 zB`!AN?%Ai=L2x7b;Ax}@LTnCULVy+O-i*Y@M*e7Q!{)||VIC0X*X}LC(dv%;NwVhc zuQX*@-z=rBv7I2Bz%YJ!4CCi=Q`**kV-_y*M*U7aN@sP(c^5C7zFJe z^d_9MRZ~^mp&DtE7B_-_TjTU6!<22!MY^9CKI|BP8^)xHNj-0t{%MYupF=QUuODt5 zW0*$lm7|t0wn1LP!DD*77Y$m&$KHI}(WlC$XD3KU_1_q=>Ra3h=5?on*}tq=zF|L} zw6ugU%ow|@d~v43Kl?M;chD;Ee2RZYWb!Gc z!$nV}tsWiCY0yM##Lx5J7}1*Nbv^L&z(CAM>WtaF1JEef3Q<~-So1y*d*WFwZZn2y zP8b_QPoYMMg5f4z}Vk6Fte1Iob|5RX~rZYu( zNj2u06|8N;Q8(5fuj{hAXK#klC(O{S{en-L4&UgmMt!@?SUI%MRG~?KBb62{^E9qC5kJ@EmIqnR~nQ<*i_oIOcVfzAP!sl2C6 z2>N&rz@q2jxJLc&s(LYN^ckiXVfOk{GXFYlUP;?p^w3>Gnu%Jut!;e?BQ7>#K6Fx# ze+EsbEwkoS;(nZ~GZa^~JHeBh&XgHh;U%bEqss95fM=_k%Pc-mx|Y;@mh^(mF?TGqR^Antio_`@4<^^9X}> zTMjLKgW=;Cj8SJ=NSHAUV?&sx_Q68=(7L>)Sfe&y5ifLIqOY`x{wNbMVY$p2@ro;c zo+3uP;)-))y~z`Y%Le0$Nk=@Gav0i?R?u7t!@!ZDu-(rvF>KK62-9qRh@e^flZ$+) zQP(kEBv9`pq1^Hh&S8T_+SbHD`;8H=xFRNFT`qR=`>=S$P`saN1e=@T*ydve-}xaJ zx;6xJhB8bfvt|-uX4+DV@OodlHX4n(Q&6?c$aI=gSIP7L#?13#)`*y_P0X5ZIv)78 z(-!0GJ0REcFmAS^6OL9G9%O||@dEL-Hjr5}i!h_A0tNrTk6f1=YH~V7&CPu1rA&D; zkryu>vIA_;{*9^J!K|@<ajDZ#6jyhEmQy$y zp0Yyo1!3s;Fc{qrGt5bbaUsmp`+>r2OON|G!%$h-s_1WwI5)qo*{h-o z@V~4X-i$EZ5L6nq!@D4A3PgQXtFl7y@?;1uA7r`e_gJ3IHp0yR79>0}tKv*(>3py~ zN4C1*c;Rz-o`eyP93n>S%OQH&Z;Z4GeDy$TkS&tB8Dig>!&oqU5SHbHVwQafjE*yF zuCTe;OPEhbf&}C4FS%DIH0pjEz66*09OBcEh;g0s560G=4cg@q`*2{$ z5K2}yK&QlT1R2Xvb|wrzsat8|dTbSNWrKEzFwdd_gudrqa0bU|&>A+(=rOZDx1htv z|G@k=Yh1TcO5BJcxZvI%j@e-->L$a|ZsD-n5sU;d%rb@vBaG2ZKjG=+7hGF9*%YI2W=zHbg)`*LZXpQJ;|DGH7Hy+r(+!pdB9kAzC7=}Ex zhEh8mA>D#;VF0s6k6Ck)Fj|g>gqB@iat2`S%s{)N{dPXA}o-pTDFwdG)IOxPnZq;eFWQkFS#-MG}HuW5Lf zI9730&1Ezbm_$G5)@ zP%I5DpD>Td@=^fJT*YR58S z;UIkOMY_11gRyfV+dV%rOfg}4?(`H!ecbT$@JX9V|?qK8>&QX32$rTk}7cPSFJ}?DYh1!@=rPCv?{f zLg$ub4dv$k`baGd?z3}RQ)bOi!fgM%U*HFQK@PEVnUekJg z^u&lh9L}$#KGDYlu++^8MTwE{936;j@0m5zS-C=^Wpu^O@Sw-Q&s;rPY;;2p@O8Ah zajoB7_`hO)4_YUCPjrc}MvLIiXxb|fS3L*9I42TM^8>M|idl1&mHFrq#%nXZZ4}pV zUr%e)uNzP2Ze|B@C1b+=#)vn9-)Dh;FE(0c=@+#;tuXyj7w9+lN6E?oxU@eK4;BUD zA?10Bp0=Bnl^PP}iT6I??xU~V&r=%p(>qgDRiE9I&bNZ8GfX$a^n3nUNL})R zyO*L-w|M23>E=IC_M-5WYH2AcW6!ul5vl8vHA$piE?V>R3AHv#&PCH1QCRnR8-|Wt zjo?5f1|3XQJfGkU(>xg-yor-A4s6gY2($jfKxJ3QTinR=8g;3bzhao*2~}!~5V`mW z*)O07c8jjV_D_0`CUtDTcUMVTlwArZo<0dD!yOn^I}YC`$K#i4W8`i3M$bw6_r|=@lntx+NYs9;!LsA@i7A?mT z9S0H>jK};>O{jmG54Hww!ux^D(<)d2^H9Ppiu)wEd41#h(iPWgOB+SW_AL3zB?qKy zlxU4OXd*_u;)>TO(bKdZbF681P~+oGBiv(G5Xj6DA!NcR{N9 z9!HqXK0!kC)vsLT1&z9i?Qw+eZ9Ndb62$KSdS0y}8o8IG-1f>Y_DaTs~aP??W&7A57BD z9M~#7Ftv#_8f`Vj4VM5ERazqb%25Q~2*%Ur>;>vE!z?FEFYi4o%P|`Dogt~2 z>%PC?H-{O@MT~((k@T4I+ZwG5lA|DN#5bFYHG!~>ok^YiY>>Mz0tWkgqN`&NI+^ds z+aOkmsmBIw17UPRiiOw8M*Pqqdgxl~lR2mDb$(*AZvPcy=RjKDt(m8_u6G3UOIN@q zdLm>8#j&M-6`gQ=%uP_N@3aGOhyD&5?$_ybE$GGQ1`!erlU zq$~<*#P8dpQ7^HGR_v>{R{3S&*#BycxC;EnyeK~e`&naQ%v({%*kIH=FsIN(C~}S+ zMBjz%$g$^~`{uYN_twO0CRZq#Gubz=G z353b}HAx6M(U9*oNuwT~a!%gNtA#QB z=nWGc9*fLl(O5%mcoSGdz&6a9RKhghK2z9jrp-Hp_L~A{RodwsVWnq_zcJ#Gqtx*~ zG2#k+x`7u4ZWs!qSQ1Eo5(wLh-k9(+5Eos2P=0`2Jiak&l!O^^JyZz%RFALITcdt+ zxn(AmoN+19Z~5QW{65);)`&qb(FMd1UW@I%n4CWzC+Sc-q(>N>hnOI;K6S?4vL9D1 zS(3#khRGpJ)#z-Yd0j33Sx=36!J|^u!#*a;ftsYhG2-s|d(e_5GK|=uX{?qX>S`Qt z>b5mr4h}{C<6Thq=OJj*O`-Mm8fha~$}qPH zqS%%=H~+Tg-kiAKZ z_wB4vw;4B0ZZq3e_Fn%7Cq@eY8%A7gL~H0QV521mRC{~k?HgZQYi0r6j&#qN9{`U_ zY`@vXFi#27I4W8=y`wJQtBpoIVQ@2r^NJAJrvZbdxTjrB5s7NtkOoamOAxKu;#DZM z0vnYz1HQLfqr5JOZ@$)u|qcoqthLZ{a1y3QAGfmaqxjqI9f| zNP|)NItkN@VQL6tX|q%IDD^p4MT0h_be*b?c7Z&sNki3d%>2tx6j{t~8!VYHT0P3Esx7rF&M=dN_osJ%3YR0bRG zs*G#xIxxrgyu_|bkgR3F#Qa#U~`9MC=N7+r^_EWbk`d$8KaRm`3SDH^2bbj zwynKlpJ!9TJaLc-{gcYMV-_0qA5V)iD-0IOqf@j64ej_e61230Cv_?GHi03rX znxHF(@P!IuQ#*BmU05*E?+gLP1!Cyboycv;*0h1?(qhw=Ft?i~3wbG3-1zPq^@zsd znQeNVlq+70kkS(Leilk=n$c{A5kJqB!W}rIUcvhn5x6qZ6;Ur_SV?`o*WK@oJ2h0M zWjY5{pV+qMmnLC45yt&qjqtJiJ1)soqkh!5L}mBZLS=C6wuCW0!Z3Qh8Afyg>C}1Q z3O=4cgsxW>qVv=K7#|gZ!p#;qV(5!9y^Ux%ke#7#GK?u<47*ebcjwpPd+=10`yfWq za*dlZy7LiUOtPpAWf+-dDGbIihyIPRuiAmXtG{06*}4MjYjE>n2M1&11+p~Z9B7P6*I zvyHHhw1%s7I}D3Ci1S;f;V50B(nk8?Vc(GwrZ1Zt1z{F{Yb&(-{)-zhRHH8VdQcIP zTp_z@Zzg3wh#1kKMU2Z1h7nf*5pykk5khbGf@984#nFa)G5OPc+-M$$M^xczxPXZX zw_(Xw;i~=_>xQynl>hc#HHR}0kpH-c+bXDa# zQ8Mwn5v|D^a6?K?5;0D8*O2p)l;tT>c(ndf(quQsrz!2=F+K>>Cl0~vwgFh@=ZDbI zkT7}dEHHyGLmL|i{mLu2-P6dL_u83d-FB;rf1KcdV?=AjcDlc<`HeX|cN^M7+oC4C zE#|sK;C=-?4c$G6gn~V2WzF&h3K?b*VN!zJh1SPPIk&l#(X~!HQ`fJ7YUKJ0oQRP! zx@c}H7ch*NHS`-(_s33r!x;40Yl4|pQE0uPDX85Nsw=0#aL*HIziGt=Z8c#cp2Q0$ zhnH}-S8CM0Q~gx;kDpTJTY5>>P(Gm)CQ38A2k%J~m?TU_dJze3U4i|K$;cVq8wC{~ z6px2d#h#Zg`s%Mn^_lrt;mA_08lRUw&n<+BZkHe|oKV6!6Q)j~wtQamCCZw%WfDeH zKyPYv7D)P9A`O~|iJ8de#^l~8*hCniJnOC^wZm>$PWY^Na&iXJxyhK;i~NeZpSi>dQ5VnJTh<(U#II>S#4`tHmResm;>b(Sc3S5BXMnzRwj>rT7s^laQu?SidA+SooIO>q~?F?8oqMbpy* zP&CjIBa^mCm~@5-Ab`Tgb)eEyeQeytDpu|@%n8E4ahK3|#1-zs9D0Pj@lxe6&Q*Ed z+)Ii{d!D1TQ9F8Yyg-Z2fEy0RNV8e!Ji9}x!3xyX&CRiK$ssp{9By{Z#BQ+V4eH&C^Y=7lmLYo`@J zTb51vx74_d@;b#vGyR;}}zdFNfDxM+J?p?6+Eh5lu18Kp$k z`Kzc}B%sV91BtEA2OD_vZ5!O(rQVJn5~IGKi}WsFCscJWLl|L0DWmHP=p)1O(09Qm}iS zF&>=!qG;z9uXqx)4tIQCD%w66f|d@pXeMKVPTSeG_JS~@f)j+qna8+4Xp`32&730^r!BW!# zlc~yRi?bt4oL@-R*s#yDnlQ&(Ulwlop5%HAriZRpS5;F(^7uL<4P;wVGpI=;sa#Nh zdk3`&#+E6tvmzzNCKn`e$7^n@aG`uK&JJycQG6)s8RRRD#hKyC4O5(b!^%pl8Rk1- zTt}7&V~kR`$)hyt?EEgOB|{(Z>mus#8MD)2@c9g6?~~E5mPzi3-Fd{6c$XbVG0k*1 zIyv@--@Gct{Fjt)8LEYe569yI7_U%D2N0#UwlSJyo zE+aSR9hI7yXf%-+y+)2k0o^HYutM>$)jk~lLl506<=~c%!vQNcH#Zo@fH3mauY?98 z(m6f)JWuFH$!Da^Qw|+eDLB1LCNE2bomZSx6_Hea1X?R%VASq7WNi;)$z^J#AKn`) zPiP@O#~*=4&lN+D^+m!OV9ld+<^l|3LYR{s9|+ljsa)|Cjk;^Addkr4iSp>rU6gqX zXde0-*g+C1Htv1K1k_ugpI zP6>zD%tWU+7(agyih8DKt@KB~IsM`4IRJ5=8e-EGKj?WHP#afUP=6%6p7utXn>>aY zLzu|@Zw0%Gb6l+#-3VsaQ+AD?r;HnMUa2=J4t7(cU_gRs-Fh8G>DC~ej0&L|oM>bY z_Cu@jmKe88fe)`l_H0ttG zGx#y}+>~`vMk__dnCi=-&}JyaYNC^80^v=O4L{0&^rW_|A3pcSfvy8l8&Iui_t_hd zpL9n+8ikGKEyI_#EE%>HTRP_u#`Lj9=;ay3RZw7Mna@sMzrjW2wr!z8*6vu8&W@Bc zBy}3bQLyahmzV-o%1-;r(7|TZvodT4$r!1 zN!DmHYg`EvXx&Mf-86*DrMFHmr)>5313TsExy>_0Ma(MSNYuUv#mcZ4l#U64W*5Jo1Dj?8V^NrpM1p!Yj4GuUz??~zz2r$AWYrsbCi}-4|3xv z+wS`4NLA|tA5@pR>Z&|1k=Bi6Bpo@zuq8hR+Czg;6&i}SW1^9_)(>a2oZ%I}h&n61 zQv@xbytGLwMQ%VN%-GcdlV`_E*0f<^B0s_yt{9}O&Dz5~Izp>}`%gvdSINSG_f^VN z2ddtpwmG&V!XeI$h!M4keq#>o=!Q>AHCq)6c{pJuqiC99Se_Ldv$jU&Bc_IWnH8u!02gAC6oau1$Xc-E*3TRF=;$7D&=!6xmSRyl6L%cXFd2j?+UzIT%A7d$Ub+z&KFs{AxS`yv zj+8J}JIULg9fpf12|I>_!qJ;5C0md?-0?@D`xu;>ZjO$buN6J^29knyGsxWrV9pdL ze09o}Tp)q90?Q^$Y+xPbOuHFeZ#RwlVD9D25itW*P4kW9VI63>)Q^>l{XE~YK2W0k zu2@s(QWyY-(X;WqdL#nqf%s)vEDR#vD~3mQAmxiu(3-_If^Q6SlQ7f9=_$j0ICD)G zYt%CjFX1&#jTG;_Wb&{R@zhZyming9lR_G8Z?*LDS9=&~1+fTP5{R5bb};sJD0`3zX6mGr!_~N0v*(e}<_bjO%58Vc({`TpGPYzndAUnCKM7-)q!FUb`{@S=RAbdLs%eM<&5IBpi-T z5qNt&4malq;np~FJdSIQwl9Jd&GdI5xz+;{heuM@WE@6~oGf`-EDPknCd@!tdm%K? zhqI#x;w^QCEA*d)D*flJk&BzOcoq<)!%nUvEnL6DXij~H#Z6l8P%st4&c&MUW>`>J z7cYkUqid&)=yK8@FJ^=y;4v%t9l;rt3ee80K}jiZjBgLN$0t(YTO zGlgO5tfamiI=hAWAHulNy7YK|eqiQB*LlM1VZG#eR>#=^it0V>`kqAFXHinUr_pYj zr*Yxv&4PQ?g|oDte_z)vNPX(!P^K9s8)aU5~AY;O_1W2Y(Bgw2ncr ztqXSc^v5K-L->%+-fR+?3$!N8v?`5IKJf$>(oCa{xYROZn}Zi;`GAth(@#>z{*zSG zaSUOZsgNy;LnY0N>41|`r@jI04xmS{J@UTy!B1*K>0vVtRo(qCwvHEes@aq3X@)T( zOdort@cjN6?$xgX^@mSYiliN}eDsM=QnN<8H7TerOq4`XQ+??>qMneVhGbIh5mY^0 ziJ6I%Wa+Mj2dQ58ws132U&q1dO&osgVkN&uY|wfTX6Dgd!s*u+xabcB>dB2w6%JF5 zDL4F}?Cv9HP}TbkJP)0KC{@|7BjKo#ru!$dY)>58oOeM}WmgQ-Z3*9ee|#!gi8y6A z#_otl*Y*>oxe=H({RngAY#-sAm%wFK7O11`vgEp5Mhi1$#q#b8(-5ORM;8z3rbu## zVi(1|YfnIL$2nBDJqG3O`3PLl9p?30VNsq3^yWH4O=oNElT;-c!X6=~v2-4uFr$|A z5?0gMze5+a3ed3dq&onSVpR>N$h!blLK7R zs|-{mlC(SBb54$@F0pe?(>HXQqV5@x^*@29tC!$aRBz0hql27Z2l4XP7~DIu8?7Ao zpy8)KB+MLUjXh!Vv;Bo0uE)8pgjv|Fj>`OPiqdAMWrney3Zmp*#m#en-#up;P~+3C zDoJmxsHF?qZm~oq<<}N_2OxK5cU%xQV$KT}gp{%B)!xhnoCvdZ<0)a;hvS^vlLED- ziHB1EVTRJ;og?R`twz=LOgR0Sj-aKN;aPc(ikH&hIZ+MUrzv>!7T?O2x5M zz+90@9Y}j!fljmYQrBLwm#Wx+c4N9TI#zeZL-TsrpB{*L8%!xdc>~pWY=-q#wh=sF z)~qDV=m|%Jr{$+P_45LCi?J5+I)Ap8>$l{Up4nMa16sSC0vxG;Y;W8JNeC?~Aq%F8 zvuLt-Cg#R>gtq@f#YQ(DRPh6l@^ueL8yn5XvbkBnFq;UYyy_$TnQ)40|D{0vaK|xu zZ3`{FI4x9JYMhO#EthE}P~mOQtI%i(Fs~y>4QMwUK8Nm$oY5?$H=h3dsJJuH7sIRj zqV)YP+-~BAA>&xw)0Sb}3B#xE5-v7R;PU<~P+L7(B6qKr3NGU$1$P%;B51G&z ze+|ZSm87_Pa$$hew@B5H43cC9O>*L|yaPu3LgoQJygLy@v30B8EKH7$u@4iIK; zgr~5hES^);r;|+wRYqji3RPUQhr+zAIdH#2Ro~R|SZt^3LQfFl(~#|g9EeXt-afk^ z3mcE+yE~$wP7=0XorrTD2Qi5vA)Pk&mK^#G!vqoL(a{hgbXfwI(vU8NF?*G}y^58S zR(c9y>q&&>I8}I4o%G6<*Xijl6K@?dr57lN?DN<^b{7T}Pe9)6PUze|9v-7SG02lz zAy=G7T^m;k)0cT#G+`!gj1`;+6R53GugG*)nLlf&)L&FzY3xdc1il@_eKj zT!i@!HDb#ro>=vGNp2U(<24%~Z_&PE`?BA?RVt z&I09Zh0Y|*q}8dy*jZ8BRtkFQ+K!bsE5EBOYT&?E_~uKc@~IR@6HDdwmS;n8*!+`d`9w|MfUo%b`h}0TeHzv45g9d_6p|yF(x~+Gd;d9)@{9m{*s5 zgkx_HaZ5}z>Q^>xl{ZJk@z$-z^J1Bg_^Pha&O_P>%7S=vmE}OyDUfQ|*KJq_?r9%9 z%xg{WoY8O%=FxHSc8pY$C|Yz!Y0wU{`%NWbmOVTq%(=afi!`7ERO^N+wSFVMQQkBu zYeUMj>&k z_bgK^#g_fnn6a}Ct=JLpecKg1Vz#4e#4bc1XUVYf>{3`u7hl_>E3JixkcZzbnN(MWv;%&P7tBaNmjLxF1e6YeDs>K$dcDqs(wNWCQ$F zZg6?bUOCn=O#M~#s_uD0*wez3^P>aQo)iORC+lUhpo=&8+Sno~EukWmTDZ?Ifvkdx zm&(W@ibjd$aoZLyLBb((q^#G1?aMIq*l&Wz8Cy`0uoLqavS6_fdwyt67`M8|g*y%h zxbvS1)RBu13*!x%^O_BXyq@fi6k*qVrc{yK64Z{Q{50GAzf-Mz`z?m~M00$MX^eZ# zLeaS&kFYhnu;jr$M3}O=wf+pFPnd?gqJ?Pf1Dx@@0`;^`op^c5X}(*J%Y5|;>i0k? ziWNO>LX54=+C-XBTPd8kgUS`CJg(7WH~ehT2kWU(gCi06D ze`QP>qa_zHVg_-Q)BnbZ)^yph1>we)m?JcS>W{-1ba^m|Z+c>Ge=n?B%G63T*q{w0 z%+ebk!f1H_S6V{Ww64ed*pi%h*AJ34V#%+FF^Ie;B`5v1M#Qw+x(VMa2H=BRQ)nGI zjES>{B0tLu!AlOJD~0#Olo3<*-PjQ3;xfu0J|Du3yk4N*Y_Un1=(~isJNAONUHkvG zrn%b=%y}w9?uwRhp(msjlZIf6gBMC14q${4t6uHE2F;Ezd4>mt7)2C!nJ_zkc`Ma_ z+~cF$z2KGo>qkbNZdE=*52mM;*&teHfZ z(ed8GG~=UORAzzN=5@R>v*|lt-{_#^(6*WXIXA;~nG1-6R?))``&W)d`}N&OLL?E^ ziphwjW4h@dfoMI9VeT-@EW&J_?k&tXa-2JtU7-HHf#>etYc5}uoWyGt)7Snl7Z4p< z{5*eqn)EtYe;k^anBYTrJPxOC$CR*SbZr=qJr8C|a}&%k&V;dj<0;sFJImRer;EqY zy?l?}M)Ib*qotJitSF7-0(*1rNo(5Y(PHN&_NX41T4LRQfa?p%6-x?Yp!nSPxvE6SEGRf-NR=5-o--$d@ z96D{U)2|q^;#~CaN}|rg4xra74wd=I*t6jvz8}1VwxNF16MwCQsbDU!jWA!WBLu5+ z9rzii3)HI{&rnUM9jS0xKUc2Ph)S`qQDB(zqQxYO>Y)rHR^hcJ!N+|q&r`?5P%Lv8 zjd66fxfKK#R^0`=op^;Dhi8ObvmBq~LW zm}g^0eFheNXPGIYHDZP2z^2!*b=(Pf8SaI4ugSJ99y7nF$HR#PAI%rU z!SkUj_!Bcx_lpvKrF&tsOo{9vXYj}TO%mp>oZB$M^w2se98p^EClU+P`t8f)x&8La z^{;N=ofZ{Ko+fInh^33-n&zEMMVaeK3~fyw_jeW%O8lTT=EjKTPvPsR}7Bhw;#LDR#O~ zg0Ax!FfaN~5+?65{K#!DIoU<( z$&o_8JCt`zV!~oS8`(@M(XOTB%j_GdTW|zz+?Jz5?@0)#NXNIPo8f4ZhR)szFuSuz z!n|Z*qAbEV*lrOL#J2N$TD&xuo|{b{9IK5GT<{<;)-%}L$w7F9{gA0x+H(FRgX`xrP=1jq`{grCF=0B|g$m}2n(|*f$e}MJ%bzW-r#frDjqlg23^4=C z;7O$l-gTc!n#F#Gl%#B54tLU(T-E6$#$Z0d!Zor%Mz(=mvU;(l|T z<=K=I=FswkLIYV-{)%gXI)E#emmgLs4eFfZD;_=~5#e%5O`sLv@-u9)EkV_ZVpNws zMs?F7?DRYfT=qi7j?FZ8S26YLA^wmO-x!Sz>`U3UD zA2;Mh^=g!3=CtQU0YR5HkKsUrH}Cv&N(G^IISD1$lJEp}5qF^TI1b(BZov<~SvdCV z5*C*oL}k!L^xq($@p&J~n)(d$i7@vj4HDL;)#Y_J7N`%0KbBVyX|3A!wml#7;fbVH zs<)#|5=E`*^MD$gl%itkGgO4!#rT9+__W%FdtIGymM$e-DQopzZ4N$_t8uYvmxOu7 zG9iBw=KGD#LZL@B7qzNDZ60bkXjP@5GCFS^CyH(P4JH}U<>heN@QU;z$|M27akHPJ znpW)RuVT=}-W4BYW3bj-1vmR$cy&s^740)lxbTuixsdvWct9XAOG+t${C~@vA`fnm5qiT@Jl2kMQ=uOB6r5kLTHu=xXhX_(dZy z;lCeh2rY3Q5^-*3MVh(5eg#w}w;U|4M9JKNyaq)3LmAIqYMP!=*eCT*oOA zWT6VxwpwK84=^ry3Z2zY zP`mLBst1*0cup|RB&~uAhTsN$L;90eqMj@ojSLeov-1!Mqt9HR8)1wrJOqa~ce&5w z3)HPW+o&wwe98z}aha3Nc#AD#-ohdA1w0Kt!Y{uPNfFO5Z_PVN+;Q|~U#!WVhuFua zD8o5?wV46u#SxG{i=Zg)1PSBLFcySKw%sGRUB1N~98#d}9@C3A?E6}I(I%8jvVTvt zHt$gtS4A?EpYYlH1)9%!j*Pk=Byq7U?NSqYuHZYUcy7LBWQNe&?y zi&`##L*8MGH;Y66Q$r=pM7G$BBTUW00YZXPG8Z+mKt15&O1VMo0#%*VkPEfT|AeX8 zpQxSujviFLqTl8>u+=A**hkWPlV2cV)mF66vB8|mHaNcV82a<$u^>4NfvPBUr$+VS zcVosdQwg)d+FW>WHIlnNyFk6$;l8ZL_g$(v>aQ}}>z|R7^%)LRNI5pU7OA@L;Jx7u zjL&|CV)#qEs$PeI_Xc9e*Or)O9*5i?qwpo(9|LbiVc#(J{P2=t<`Kr($x1k0>BVI( zqm#{@Im(JLlT>rgp3R8K|AGqT7r1x)fPn|Tp_+e>oYikJ>*NVX8YDgc0GGYrF>uKTR9nA8P(lqn$@`vu-+&`J){yUMfn}}Y@o54FM=y#>Q8BaI z5BAEjfnhcfX7Rci!v1^XIj`*n>YjC)DZK`cSJ`hW;Hpi(N;-vA4%MXZ{T&L^YUtg1 zCrP~4@~@DjT8sM4%&=-n3)nr0#j!GL{JDX;^jr+Y@UHB(mdpmtjWEISO9c19mfRPw z0`;X|$wEK<-YOgSP)^6^E3`V+LbJUZS(AUjJ(nE0|9j-cd_~&wS7=dZJ!bELC!*~*ALclU1bEF}6m(Bu{*6Z>i_sf)Hnp^NOSzjgX zRS{Eq;RnLZKBC{k_b4u6n0_laK(TuuT9oOc)tgwTlI57;bPMKx%Hx#wBi?g*m%frpAG7AaVJ>}Hk8OhoVDZk@*b#dKC)7ic z+}jtg*N4HPTQA84mNQHwVeYv*3a(n(-1W!;bzb#&F7A9sLD$ca7cohx45Rb$2Sg>= z-`4c&`wG>88_;{d6~@nLhRGviF@C@h%P-rq$x087lfWQ59gl)yA^1e|6ahHhXWE^T3*VfEO4qa@6%)zgH% zRn57==mPcVgz-xE1}XgRt(*Aj@EXYlJSTiW-o793`&x}kZCZH9(`G$*i6ObvZgS%Y z+{o^Z;aPFuJ;vielOu?;4#H0j!x%D54q>*xoFl}fcjB5HD^L%AtFOE_yM^4ud@rB$ z^9!7we1%`ud&!|!&aXy>;w|!QzCzSqweIAD8?9~8@TD1!S|#91gQ;lcL&3{-ffzW= zP8zgwwn^V6%mT$+A+eVg_kwN&i_D6-Z(p0rzZZjFI`@n8d5UYA_<1`061An@Af~hi z-6~$-5}n09>W@T}tOv?n<1zT&1nTLXfE3#>Oc*y_!t`O*loIAo+ZjT;PUAUmnj51R zAGiz>L#wlN6E6$>EJ-8lWW4)(vDu*aMp|r|yS~7y#`JyAsm5r@04!TTYI0|$W4mD@ zj5kK&$X)ghtG~GKgWAY9-Hnu8e5I5U`R4=7aV4zt9CLr?hMC|>RFOCWo*#i5@!1T z34+JxjocCc0`!wulP>3HoUms)OMonjO2I6z5fQCBky5)_7z<8YLL3^IZg%z zVK3)M%1ay?)*Qv+^>YzZn1YmF!PqUZxaVJUQ$v`^-jjsVt$VpEvr?*OKQq z;Q5M1e@YvHC|GNo$uJ>LyD4#wum0RcA@ToSRBoXeUFK=M#^bMN$cM#74B1Y834QdpP>ZmF3)7awR$zzza zVJ1wzox{Du;Yg@tf&5yAX-gRM>=vxW4}DsJqK0(H>atNgxgjpPY+C-Cl@K1xRp5hD)T z|HN!mMAO;Y5%VkL7_s>nE}xwR5338fD+|YnR42)rDu%HnOsvT);Tm_18?~oEeSY_3 zfitTwx3}%dZyEl-F_Bd-|DGF*r7^G{FcAr3ftF1Z;OjRNeeKU-tWP-fKeLA}6NXU` zW@GD_LQ4+~cXn5SIy-y3Y`@=Keoojc?*E5*_$vw(7bbwzsL)3@f$9in!dL$sCMXW$ z+Fa()wWlRd8%Y@Bv}r=`$)((%n+w!$yWA24Z4chYsh(tw>>`^RanQ6B@9^6i?c9r$o8l=Pl1U?j-jcy6DI9EgG%zWTZL?H{=zsA=BjLl;AK_L-Eu2XFaHsm@$9W7 zfBTO?e9TxjXriZy=QMF{M2vV&6CGNrDKr}o#XC9TH^x!4V>))cJp=Qq5cFNo9=e8| zl&qOS7@KS-p;Y%NSF?|vhVHCU7EbM@syR2FPip=Nc~ieg7mw8bU#0Knw>64(mFV!= z2aR3jsQ7*b3E67&svdx;HxuFU)gMPg*bCGFhFL@y-R}E@Tjzo~v;76?u{(BV^zB%Z z$?uyieK&fa>4e$rC6z4vl1`l>MqJaJUOz*(z6UYI<wsR@~pd5tqNT#!IbW{G#f7 z%R4L}S&}SSvzjoEl1~a%M!B-5wAg$v{-x;B)j2c8(^4*ep5h9fn)DK;FMmiYwD{eO zYf=N(PfxMSXEz*WMi?xNh0miyuvqOxPf2IdTbYEk#ycg4Uc@k42($BWcOm=Ze%bV` z1?s!MI?83*?NsZ^y#L1J(Rul8ho3OD`XGItqBU(VK1CL_WE2`yXRwW@49VCr=$JnmPLy+N-eEQR^i4zI)KH8v zWez>_xMWQTVXp5t7P_i-aW?e);Cu7AFf%Jh9+xsr8Z>cR(`x)m8nlYge=xQl&#du$i6fj0d;(kylxH7#h!=H@K_u_#@^GKCP|nW!t|bEDV#To<`U-8CapHh)ZX?> zo}YeP@-&_7FOb>3f?ikB`lkDh=mMUtnWwGlaTux)TDv~ZriKln2=keN8m&{vU40mR z)=iS;CMr?FoFI&`<#ZwF%?YmiI44 zJkN8cGS8~>oIVL5AyFzx5~V^iCruitB#mS!ADyu-06f$ zh{kkzn;`Pe`oD+a&==4S{6UG9ucSd^^G198Q&_&EOrquMkaW!yr!K9-u)538ckzDI zp;cgKV}2WTn`6!r#;ksrn7*-&V4z>9PTTV|_iE`eqmVYC(k314@DWbuIL2+!D?AD1 zYQDBE#gv>aSS??Q>wQP!yD9>!(^etK>LB`A2E%-+iKONy$6O`M#){>ld$68xY6u00 zGp4GXLk*35-prA+ZEfK65Agc_0zKFMK-RsNzcB1Lm|D0SMa8SIAYv3BOt*8M;{3EeLfh_z>Zs%fDqYu2s=)?zq(RfD z`8x536ilhCrjglZjLmeXD?A%S>ug0qrU#Wd?#2|#|6Dttr}GTwm>OQRt$hv>9~<-( zg8R}nkz0^X5aNUWKl<-$%H(FBT z!3V7oVVd}@5uJ{76v7M()nokotD?^LQk3_5AXff2|5h`{zZ7eX5>fls0@QtPi{mND zh&5p;t%Vb#*&RW=Dz#BRl||jgqK-HJH-Y_L zN^9D`O<-f=L|i`Qg*El3BbV+AtW0KNM^*~@CQxa1Ih{o58@FA;bS2FBiLs(d?`Fc? zafNF0+K+^+LA#V)+uA8LYEp*2lvZeF(3*c!GLlRnGy&c-JyHMNWb8aZr<|6qFkiY0 z&Th##dVvp`4af8)Olow5XrI5d=EEYP5H5+*fV2#Zx zveTos(!ViT&oLK!@HMTnn))B(=$ZF9nETxvdWW{btnGZ{WbcAjlkM=n&zH^)JETD~ zAxwX}VDbCZT0-K|LiO8SW{z3pb?TO(4H4UdBzpoG`XO1H`T=)rGEf>hxZeBW9%@Roc{vQ8JIfEdTeQ zX_ij5tuai{mJJBJGnd})GDj@s*>nzZhx_gAs5>wP$IQ8!>N_Ph)`XD_3l{4rs|dk9 zh3ei-wkjP`L&g3ribcht|6+3e`I^Qs@gcGBI58jT(PlUqyB)qN4-DM19rk;+!bQf{ zvUjMCzVGR3GQh%*EXu6M%gtXYKJh1=| zLU$l*?oKppIZ9IF$JO`}CUVPiab8}TOpGd2A8zd=4C!O2H2yl+ko}wVK^((QHkC2C z2c9B_x+v#9bHRhyQ8+hu8wzJFg5AoU7&mqo)-B`zrXI(vA&l*!+2WRGPh_>p_sscN zVCd}gTC}L9E%}~olMX9-Ax+Q97#4omV-SVX&(4^eIs!+VC&P2R8>Tt!#H1TLaa@P1 ziQonuO_;rhri<}!9?DKe7OD^RnxbfOu9?ze?+qCnG={O;#4#+~tvL&@@WW5{_2|;p z5ucLBpx7~q@@_q;BkT@L{jn3pefb^13%=NFAx!;n8}UW^`?4p|g=(LU(}bP(i$#k} zA4yF?!vBof*6Jx*)BZomdp7b*Ot797oBWeYVcLEt%;^Dv?nZp~{LC?_gsD?zDQ3L8 zBU?-^?jGM6Le`AV%G=s>h$1yCc<(*`1=vQw)LirB^M+w2-=G8Sh8akmF$O=cZ^2Bz zC8#reClaVur{*I5Z+7!R%OFg^JxlTK<6AP1kV17veM8~gqe03OH+Ks<860Ej@&YuzS@=+~2khZS5AK%MNOA_Gt%d=J9yi8Lmb_m@17%iyfBSkd>3S zW|^KW1RdQYo@$#VsbNtL6T19j$3f~ESk1$+97<-6*Nm%m*2|6xCwNpKqRR# z^W$omN5Ia|%#-eCAAw%49MH&bIFduQV2IIjdbn;6U6SoVogKV?+GUO@CQQ>Idg6tr zS7g_`D3~(gkg(HZq8NFY4;u5N4Xe_P;gKI;p&^EeH|3Z)bnQ?v(*~)EQP@SbZFfE{ z!BfZG2##Q#;`yN6xgYxd9P(Nf7>}4z9`jr~a zsCS`dhPkw+MR61ONSNFd9nquR71^a}R7WtjuV`LVN7!kw=?{!ftDnEZ4^9g>X8%Yk z_`7D0z^@}PPrVUak1oaNhr6jsa4J1)&)uk79HX^}f+;rL#Ld00%Hrs5?edZS%Av-I zvLHimDQ3f*Lgq%9b^M7oDRdK+{Y(lFvqAHqRbbZ+Tg+=V0sEX|F+$rDg97(qo81mv z*5}u&yZE5hAE56j$Pb^sV3a_yv;Gq2=mjuhnVbBEW2t({>==f^2gKh zf=`bgLSox@QsmYo^*1Igp$F}~aP}bUndEFOdxanTJzOe&e&hSC| z%rPAZQ|o6h(WmAu*{k6cymt#xzQb24-;BCbLPoBc6Jmu4oQ+Z zmAsWOZRS0v%9WpBp0w|jXVMiOQ?r^nCk<<5i}PnKvD`HlkG3vELq$45?l+MrvF|o>S3#^4aEyq7FZbyG(*o}u%hbOpd9f#-s(_rCjhLyvq z5#UxYJT6Rwd%f-G>CWfPFn$&g2xHcAm{=|PfowlH?52iYltXWs3XbQtD(o`eO2K=k z#_~Q7bg`@NEF+FlOo)N$2wPasoPzZYVjw$8Z?nJHhxgBEQ?TKSO(e&d5@z5RxoG6@ zSmr&pP(83$Rb`NyOt9JdOtkdn7#8KIj4ANs7%4iqWg5(zOu*65ctqcGL6%cG-d0aW z*cyK0agEO#3&Mjeq%JFxcpJ0#{Eu456uVk2>cAupvN59%y#%v=n)GYEstd==CrtlteH5?G))A`CrLbLVebt-rda8Ig zs7%cNRAZ=LE)AM=AzAteonkh?euN38?Kj03${RFk;e~_y4&!n;Ifhp`<_h1WmlI~) z`>%@2S8546=NGDX6?)`eA9FzPx$GniEPW$cTF*w$p;5#BO-YTf(!bf>A{p1qXQIr? z9+TtZv9<0ToY=Gv2EF1i*@REe2OJYf82ju+qIpFfp%Fy~jmOQ%HJlzIbUN2w$wEVH z6<{eNnt#*1Bgcewe~j@9>7wh-3M92#f`iUUSTS-6@*H+xpCwh~J>e-M$$Zcv2=g^` zk2rIGZNZpgo$DgPlrIAAiq+z}Da*|Mi(zV-7=K02u8*OnyUvSs=40y!XS6rif?C3K zd@7}r&7mkPOyXyOOB@qVn26*(;XC^Q*=Rk+#e4OkqyvYN`6 z#z~v8*M1rn!v=#asJ3IBD`r&eMZxAo)SSR$o#`BtOqh!GYs7cH4TN#zczAW#D>tpz zQLeR6Zon{=2aTCP-;Ym!safK`iJqmh!TYQUs6r2(jIQsA!a+wcG(Q2K+-FG!9mz52 zgvs$V5Nix>AY@YZ!+2*sxqm@JvAq3sS!IlYj2pDhiKpn`#RpBwAiiLUB`Zgx=JW`J zR9TK4cG-BN+=?lg+|sPL2^=9z{M7e~F`*5G$3cbaT$iizp9#$%<&4&e2PPkeJ4rHP>#tZ z%rpvgXW#p zcgZNAfiYb61i`9w9@<8#ac7YyY<9GjFiSY*G-14Ihl;&+&Jq&IlTJ%e%C9^(H5zl3 z9uuZxpj&gABeY2~Oy3%mVDS%zodxc+zlti^WAMH)rNKEzV+marZ(f^=+4Pv;=)|rP zW+cZH5$0C4E#g$CWt7TWsMg({C3npGTmE@wtV}`2Kz74!SE5$T z$yGF+2Wc%#Nrbeb~y-9YdcGrM2@*ln9XkcMf<=I;RLM$x`qkzlFy04 z@(r_v6jEX0M@dQakC+1_^V6YQ}|dOjymwa1gkfcU4Z~Qr#|arV9M$hu6R*Wd<_JPGdkq6uJ)Kr_S44%~!(A ziWn*$F$|<{NqViTTGddwxh&stze;!ccFTJl(*`Xdo`h}R)NxM&hJ6fsHu!u z)9C~{6m^5K=Xkh|j6}<&j@aIvnmQe#_q_u7ns$?`X+W4hhpEL?MzD}U!IX(-kE+%V zc`2(|-dM%v&HtrF*mMS^^{5-{d|Si}jD_!6YC_jlg!$`8d=U5w-JWAw5oYD=4dRSy zLBhLus=pbuU-iUMOL;r9rIKL`$8!^S7R3KeWi?;l(PII22hG~!o8+y9=~ENh z75!ixHyI;NMPpQqHPW8sAg6jbW_IJz!5}_wdJ|^P>#d^B_0>Y1!-eV_5$lD^yONYY zyOsWbF+bNIC-;>nE#`57 z6t2dYFvE|o5>x#tYWO!*7Ed*h8yy;@JX+<}e=ux%R>mx~r$T1;Zm>T?Ik)Qd*e0KW zZEHo03y-Gfka*0dF~^t@=0ishQEd<)JiAt?u0BGPRm>?DZ@(Dx2d1(KXw;;OYFwz@ z6T{`BF)1br52`p~Q3y3Y%iMtaGCpY4IA#iA6k49*6Pdp-=1QUZN_P{bUHW8Y#W}q{ zF#nSYWc0|R+`>Wd-!vBU710=c&JwXVvT-^-3Kfrd*v^b&90)TtZ?za6v`V;loBW%C z&Z_sF1C`0^_lazJY7ClT*wR^f&~Dw$MLx;iFZSn#t({}EUrE5)5>ud~GJhg|{@hp6c+JMPDIOZb9_z)(Eo^&*I zSSlQTLQ#%y$%5a<$;vtP_Xrvc+ix^#G#Ivfu2d=zL`_bsQN7x*?a{Ef>4-ePW6<}G z#>ATZ3NMsnLI@)aT_G;aStJCN7OKBK?kIoqVze?jZvGz_&9R5z|YQb=tvS^4>d`7aC` zw8|K^Ni)oC*Bo>?(+9ScXgNSH23y|EM2*qM@TE%}{z~P+`$yZPRUnZtN3}e}%LxmF zq_-4L(`}@bk8h`(^ZNNOjAoOLmvKweoNRQ$a^SMPAHI~y(BFF#^(vl;sH;a2`XL^T zj0~lvQ-`bBNtgruJVk$Tp78Q2L4*R;n$B<{&AAyMiF0|Z)b{?}RNB0PV4L8B_ zE;oUGTulLC<`m5r2Q`^3G^gp=Zbh!p^+<#=A~yUF%mt(07_(xI8KI&yc#D1*>oE*n z=`ots&0J9D`w=8kkF|hr{3;@nW6l#M#CxV#%g%|Obt_b-n-3R!Ms-&9-hTTRhQ$S# z8a6$dLHFFrF%43V!us|=SRaw2+wcTj+UEkN14pp#)mAiL&!^`AzSvwN%+`SpV*TtH z!uGp#6%iRP6z=y`9*LVP9S4~SXfT>VV;GiaBgF;u2I5+K1IS_%Fmbpm`c^%PMV+@` z#A&{Ce&PmwpD@vTt;CmJ_Cn;tLUoq?O69qZek#-QgA#@v2c2$}{t9$$qf;kyaqC1r zf^7Oh*pJdh%{t)_4yPedXAG8K+YWWfHnd*E9S?nO0%e3b)+AhvF6|@4keZK1H&uSdb4(RI>ijL1SaBpo-)R{{+yN8mo zVlMBQlE>A&C(OFDN#fu`wFTQ7h3dTcFnN+~`yCY2eTJN!J@^#9y3At?; zd3&L1>B&P9hGh^l44a;nF)4NraiOmQkK2vF2472R1Q?I3Ve_DzasUIr$0IG1Z_)~m zskMZfoEAElp?`DF^7p^ds5z2+4AXZB z2&pp}(K)dgGtmuZ^ABK13BB=oiqD%7+@Sjt#-YtTaa&mnVH>S!8!zXpGUQr@+11wl zuO^^Tv)v#InO6;Qq=^mcHA;Z_4rdJ5yBCI(5`X0sUj;I_8biV~O^On&HntT`KPXgR z8+T20fBX(bqb)jrV3-Lk-N6l7@$(DL&V0yLfjsS7hG<)CkD{23h*;%_hmmP8Kbwec zEBQw7a*MP=k0i`or_ExYWgUdbmy{BJbCjxhWQ;ud)?%TAW%GCa%HKK^AyKB_u7Y%)*i-d*QG!3{NlDku1%gVlsgCl?VgQ12daj?(KX6kp(nS~rkf6`Sn%1b9N62Z>y@E?+iJNau+GMaB|2RO!wFxM3du~gqn=uH2{ z{Z(V4ORW`HI-GyOiJS0n%9osm}YjFsN*{f6_iEn z>$)Csq8nD^9L9UP0GlD_n15D*rG!~@I#_(&-%E%rDpVht87$8j@mx`_B3=0ZVa|6r zh~v8kV%e365ZY`&gYIsqJ|P>&XD6Y7f`=dOay9;hskq}VPI^CEFgizBLweb&yG`4w z?yt@N17nrV)tI=E!%mwt8?@aEvQg7yG@_PHM!>oaxbVaki6)uo+%O&|Kl6Fhk0^gfYzh4EAq6Wc|jl0~Eugv^t8_Q-|Yei)r{2 zPuZz+r(txn38Rs9`-`_ zObT>0F;ST*ZYaB~s45SnM9YC~zaWu{$DWD5F)TF1FlQ{(h*>xa@tvHYwRj^Qx15AC zM*CniAsVjl2TSv&8=szg2(z!{e(}RIJ0U%b^3zJ|h+5s+>(}e0CsvYbxQP5!{lEc=adoBvH(1-8{tB5lkt3g20y*=l-WmZWOxUDH!)7AKOyihSgh|*+kJNp#75XS?v1w`{cb#@earwek znb&oyT+OCxFB-IeW8P-dG_8|^OM?v2btt`oQ++)?PMwX57c~uxy?`D? zS2>|t??bR|8Vl3Od?Of`DE*t8gqc?yE*`xwO_)egj%NKoD}C0qmtBplEn!%!lc|~4 z?l*=FTH={UsM;e3p;v~$qj)N84n!eV#|d-yWZ-b;SadDo7n1Kd<`H3>H$;gkIn#tq ze-)||OA?j3W7o+#?F|;0rB%kTYa;e<0*knsZ*$dXcanl8v#7Q4wK#lsor^xHSvb5k z0kd*VC4=6<2kjMMPL16lM$WYt>YX4@+Qw9wx^cLW;h^{fvv5ciV+U}|{LADN7Cgd7 zb2X|?H$~B4N9^eogYtInv`J(k(UNX-pYyPtieo+#rs}f@G5Vst@IX!f=J^@nnz&z9 zZu9Lw80`fdWBHA%k(sElHEjf<2TaEr>u97ca6x#}9Jtn|rz%tVpbh01?WOc@(gH*; zlj(wZrcmAgr@s8kL8Z*~)Kv+?!rkoO)V8c*tigC|S4e7}dn&0sPN0WqsJPsSTDHz# zfRWu5D1WdK53_h)XH$-;N0{?97l_NF9fUep3)Q}lZwvkg0}VWtaT3OB^jB%#ESvBf zqfwK2RgIw8hKTw$1HlH-SRA_$hpF$~7uA`twQI7Js zNdh%pl$notE3$dRFig!Vmnza3S~7vb6=3rw_q82;qa@s1jPlpa4Ok? zX~Xz_Gli?^#4v5AiZh&N3ZbtH)g!$YDdr~I2+FG6lwS)uhHV4^{=YGib1J08X7GF^ zK5QO>rn9Z#`Xd5+zs|?;0tJ2?h(oOf9P@>%=}DO8Yp02OFiY6>ol>p33{={E2^H)* z*HSWrPVxUL?KiErRxxHN@k|ZFuzAzXJQq)I7@{c69+yspW08$B{KJ&!yFCtW*Lb*l z9mfnNOi}S{v6;KG5J#97<&6}H1OAe=)4w4dIhcPFw&NN0Cs#3M3H}U|xRI;Log*T9 zj||_cPQ@U-HP9)Wi?J^hu-zR4@e#+EbBqyTLhjEJy$fdxh4qTm6{}hb_W3fIeVskO zFwuWML+7kNF)4KK*}s#BH|Gqn^TTA!n-h++Ro$`XoC3?w#UtXMl##ZZq{U_oVf1!8 ziFSKk1Qj*U%Gh^9X5pD`sMTPs$l}nBZ2z~5aHnaJy2T<_;r1)LS4>3HzOI5^7i!sRkSRO0 zgc_R_2LDp?Z;VEbjZZdil?|qo=tMm8q!9O`dFVx3om2A!vo6*n1qjo^bV`eJk+%ov1(oddYjIW z25oYJ^lv-~Q($Q<<{P>SlZF(jgOu~+#@1%C8uTsTIw@X!|m`#?&0|e6a zWFA3$(+qOV`(XRe@i=#woc4+pc(+Z<*djC)js9LEVYYLOH(|!^o~C$jGfS`?U8L^c zdV*2wl{MrRvmQ(SP4peAET)PThGAu;MN3M+)HpaiLXOo=wAj}KD~h|~X5IqCim~WS z$9q%fEaX$#70ZX-#xX&Jd8L`lMLSXbbt62_>y8Vr+>xHU8ks+CBP^9VF;ikW!^k-%k}xLzYYp24c?y>FfZ)uo z{Z$qolT>AG;-o?A`SiCMRw~cbu<6M#MfIs{WJGr~zXn`!SdAg69uVv=<5bISSf9wN z@TSB||7Ig$Hk_TKXd3DzEEr#;E_)iDyI^UseELUwIWqya3a~-TDXLO4`_HQ&8riO)vQrA#ZAj4@m*~$YYma(V^H$_lDE<)>t;$kST`ku-$ z`v{|7v`aj)V1=-ET#oW^g|V}y%iZY8 zo9&*O#fGW5xtsqRw%^EfmGs2uP^4Q}<3Uas@~2FP?on#ZlDr9R{ZiuvOr@_6{7)sEdca+aR@zGlDm+L7%R7Q1fm&j(78y z2CXkwbC)m^8@)7a7w;=<=~1LkJ8xmMu78mH$=M zQM#fXiY;a#)IS_LUGBm!HG0E~_PbdCpHb-HBT3&w{F6+ap48M8SX5 zRK_ra?qs(QrDkoR_%RGkpZH>m$0{_RSBQ#cyKr(1&riF>F>eW@Wo=-fU*;?9r~M|N z--cYhcabW6<2TYqz@}$qHO$hO8g}Z8J8>BM=k|q#nI+t&uS4@#IukU>$Llz1@vg@Y zw{`epQ$ZNT0v$2;@^ay0?ILxb+k10EvpNaE-7J3%T8S6`H|#9%w(dh|v0>iY`z!gl z=WT|_MdWZeMWghP9d*Ra!tfsS+WdI#cy#2L8q26(XYWMO;KeebjdqcGk=N{8t)|fi z!bum&#bqZOw%9NeV5Rb`Z4O(Zqir6eBTi#&>J&WLHxG}a;&40099;)wqReb99tHH0 zOkns%$F!iq*k>KToO$vdp95I=7Z{bgwy6R7-e7)FW?Zq!4yi9;~L zi{{C)m8kdpEYhf;Y)Fgg62_LV0{Vn8Uh*-gFk*?IpmSRFLApwP*KlEDs*TWd#WN`f zN`qlxJ7#GIDk{M0J-1V5xb&WjsUMUaDSZM^cFYU@)MO z*x{9&dVP;w2}|1n66STZgfS<~g7v{-@7Xbe5gl%qO; z(RQ4w-Inf3tud4IHSsitIrD_OQI#f8XVp z_8j9#m@V)B5=Z@&AS|PY0(LK)CA>@xR5`X*OPjPt4cnyInpPRpxAQSrb{dJhwvJfs z7YE%|_Gq|Nfh7wQ&~FvLikQGnz>P3(uI&;l(qn`{q^48K0eSL^I)YaBI)-(sQAXF1 z&nP3WjbWI>UK!Kb{xD8{lH}!d(@+kJmX`yDk`eSf7DdQuuHG174&l1{t=icjzVsYP|WS=g$$QdsJdz+wd3a= zffnCydJxQ1ZU+jtUlporx}3`G{_Kph!uFV?hD8S%=HvzL;#O9pOTOob%hW&hl?Ut=$3l@X z7LnC*@PV>aRu}U->EV3o+(MY(0ZF3eV}Bv-X`$Nb&|j(}CRVa`RrU&Og=QC$nxi_~ zZ!{*r)Wn=Ez|^m{@N4LTRqk;Z^}-Cr&LV8-4T+#{LnJk~IVP1bjiwzIohG%=-$T(vGj97X#alE<%pkPP4_piWkclE28|z&ojfi>(-d8 z9SPI>GcajtE@DnaVf_!j-^6o_f?-?}#3ht&-IS6ndbx(ntBcvnu2tts7#6ns-!Lck zWMj`EIdvPGgwjRf7$lp9C&%*fVrd+%nDeG{d-$N8Ak6bY{$gafpKzN7t*W27d{yCU zrM_jGUzo3>xktd-7_d!Rqo$KA3m5MTShr&m^yz&FyKYV}*q;yMTM1ZohX=X}IOZZ@ zo))->tGwx)_Ks2%ceGHtRdE&eSs6;0z_Q9(q1e50!gtTv{3fenfrZw!d0b6WXbWn5T&|tD0 zIHtpV72ZUQLA_6Qh-?x`U6U**Or%1m`1Lpz$nym%IHrU!U#XYse8W{jJyNskX&2ST z!PRApr?-;SRK~C~G#fOHniUsvp|l@|tS9zxJGCC~k4?d<6-ulQi$rE!et>f4m=}b3 zHGGqJ%XXE}oG!hhs+KCXUS(u^PHG?-v}VxQe)Dfk;fh?kv>%I5hiS0>M$c9kTT>)g zMKvC@B3$GC%@dCKNSJT=8^v{Xe1+A|3e_!M84Jc4%X5-f&5$q}HEh56H^w(bq~hg~ z_-1d7{k{>%Y;2Ed7u1-#eFIvL=Qr%H`8iE%xt7+Co?&9}8((29VJ`L^A~$~KWf*m9 z`yZJ9NliyRdgJ5vD4gkTi;Pq2;AchU3X4x-P`iz&znQPlE<7|;hcNZ0&lfKb^%EL= zEL4YdGLXM~byubsQd{|N6R4~vUHKTt1}Sl%l_~t=rlRrV2<$rNiXE1x(7|yd+9mK3 ztbrWUj4(sHScysYYlvr;V3VYdrMZnW;r~7SQ~g{|OWM zO@S?DBk*F570UO8!@k~h?DNjU;`h-Q_=c|n=6tcyC5+C^+2Vy(e!>viJ;UaNDHRj` z7PUU6EB=3&b#FwRXgLZV&8DJiWCUyvPQ%9QG(CehK)IIR6t3g@%|OB&!cy@dxlxzs zs2;5otH}OwM&X#3{L2K`ps~ZPw=OnT{^md3e7v z8nerJ;@D??77z&I_;ZoyGu&TDpu_Fu=AMGh-OYwuZk+!=2aTD)$bLC^>?Oz6WJ`?d z6b6&cGtkVt09_ZwqF);SH)FXPQ^MT)<|rDB@E0uG7O9)JN)jGf^p-Vx%ctl6^>6Cm zI*iGOjBvx<0zGT2g`H|9Tq%QiL6bOm+VSeuG_J;iFl`r@iyKDz3mw}PsY|yM2oYE4 zC0S8hjHd1)4D-KP+7rc5wEHe#>xT(ARC_JHQ-g;4I1YdFIMlZ0k=qtrjU8b+@0W{u zR(`?^@}$QO7KP;px{LQ;$0?Y@{(q^FJOWoa?hUp8KCD69?U@+T_Bg&yB1|?{GoPP2 zoe5KMP$rfX`U;;r)4%zgqa2*rMQ+^xtzj88|6yH5*pXvE6>aHmjd=t&PjC~ks(lA> zpXpJdm!`OWGZ4?lEoM*) z`gPj`SEUQS99xIgNp_$Ld(>F!g3q(+N*Ec(1QMp1?me-?mvlivYJ3xtggs*fRmC-Z zA@L{2utqa%(3l&=4p2-DEBRgZaSv>o`l6)KkP)h-U3_>v!>UVgW)lLE}~?o;pP*CYES8&nm#*@NhXZW1q*S? zfp{T-q8zHO-HqP$>zC^kZy>2*O&QoxU4zNpRzf|Axuv}*OhTXLGqCfN9hTGxM)2IZ zsG0B=7Sn!{=Eh^4kx|m1r4we-P($%2IfaH5g=)73A@XS{?^S~zr%4!QY0?>*OdzZ9 zwG80O--oT29tH&3QMkTa0*Dhx(OvtiqwUSYD{2Dh3#4K9RZju2+|tC8aBnGr(u z@My0je|EBAYFHZFlU-a5!HaVx;8aquxlRYH#Bl${KELg&X-N@NzR{ z-aqDx%|B|22vbl$Sxo5^EG(uQcJtK5!h@h;%DW5wBn)ez$1qF{%eG^d_DjtgimJOW z!E{qrTup zu)t*MX;*bq0EX=(?{pbG2_L-y8)|bC_?xRKCyb8nH1T=6)xwt`>XxvmLjHN*Rq^49 zQSz_-UP>_=h8aCuTMFA%#`L95#n%VV9xxtgzp z+1bKKTy!Tu7)aGb>95k1UZ>Uw_aB@Q7^aObZ`1Z5K--ud)fpyB^&JJikFlj!I#MWI zWI?e5S|4A99zUj`jqgdQzOP4KGFP*PW2&v772)kz(Z@D`8fQ|`(zPtrzWJ?09hXQ6 z!#a*JHRFA?jiU`XrtBlPwE5`=pm;MC{VzDvlgWYjcH0hRAq80ZA{-taxuq@UmQhU1-5=5_5a6>9`8{VK`~Dp0 zwg|%A`cvRuy#SZ2*J5c+ZUQ?wrWIj)JpIIwv;d(e)kZlNpHkMc8YfeH9;al3rol{3 z(3XzsY=zcfZ0GF9xu}`QYwwD$hXSxA-5P)Ym5 z9aJ9YrlS_h4>^f>yNbk=0WT44!PWd5Y0DXB!s!gj1vA8QEs=DfDC(}1^9 zbg;vlA1FEb5LZ6$Mq?_wp51R1PAh!S=jL#Xj>yN

|k757n`a;GaPoN|+_n?ZnF? z<_H_(3)OWuD~$}Ayvpr*`HQlII*qYl3d^xVNuPs zSX6r*W_O}@=I$K9Brz0klK6geldCZ%Ov4ub;>`xu!kNTE^|z=FDpliKN?n8ZBEzs? zO3w#RC5(3*$8^v9iOlaMxSN*_m!>0erC|sPo!7$6W*DZ*RH)$^gg5U4B{i!!#*8qn zJ^e-HK~v$&9(vHJZ=YNn@BZ@0Dq~f3uDp+`}%=k_2;)WR$glCik)qRbieDW+_zWT~o z6;mT6ksst3*6o_D(AMHlM7xyW_K*Yc-fn{>8Ow3T)DIIP&2aGTNxW>o5^uin>(%z$ z(i{j=!(+KP+Sy8|n@{zge(mIo*Qn*gjB5UY3C+|tW*ByV!_+X$bIK5Emq1hUtOty` zc)^V}g3k2D)H$uCnA?nBdRcLdD`C2)2a2`lI0?;flRx`%LZ?yQ*=|z}5jtj)j+uZ~+ zN`~!Uzn5_RQC+##k~qVg)W?Q}R2k;^Vg7FvjXCD++!AO_ruSHTJ7R-uJ|3jHq3rZ@ z7}#A#;KZdE^3y}YERU4-8y~`?7R?qd_AU`VelApRJ&-FTFJ7Hv?0G}R4!2SdVzM-5 z0#f7Ve=uy&GE|3P@?aXq-CP8E2m#sared_^d7MAG3~6&*CCpQf2_cMKp9Ny;9xH{~ zbQMuNbeFPzaU*%NoK?cVF>HEj)G$k{F**}1rqL?kxdOEn%W!Y^csT7oi#EoLe9d8MXZvhNZ+aHI*@`=Sq-;qo_UG5m&0N z#Q1)`IH)j3=LzRg``Z%i{(Gr}`OGnigsG^zMBFm$_p%>jG*u0-R9epuUQJZco3NB&`dw9t2vFq`|HcH7hx$fH0SO%@9}l z1`7@DP@t=2J;CwLBZYm{5x+33l!VP24Tdc?Y$G^Uk1%?Zu{qccSJRilcB2KH-(A2# zA73o(%U6MaOyE3WT1=iMez6D##n7jL|r?B3DtdZzx^!91fFwCyGEFIFJ_5H?}P{`lyF&I zzk#yWyLm#*+4l0c)c=W1Po_qL(X43&k`YoXYgYVpFchny&(7gn9XDiTG(!s1QSH?hQJmEdJ}O;rHEjMKLbLxp;z=7!Ou+;X=7`II_a zRqXv6c2w6S^|4bY^Q75E!0tVRhToxL@?mf=rU#ze?1SypG9#V3>rww_HOlxtA-yVZ z&oQ;UDcf$Ug>rI1uuxD`sNQM4*(hXr>s+Vv6c?b>MAig|nE*?MWf*NQj$sWml6%~x zU%wU|x`*QNbZT!*wVz)O?#JP93+#N#;{xBqBsEP46A*8vtZp7GEI&`BBzJGf!`oa| z?Fn5h*YOSyqeczy$ry&IVJ1+wEx#sWXMrZ_AGkT? z5%SJnLf@H-(D~I|tRE1I@z>m7vHLh$eR4->GhgZ79OG)b6XtR6-J;9PP@z6;(vEdn z8rACeOQO-I@{daW!E2>QgQUk#D6f0yy8i)~ zN5GcOE=_kp?`2oSR*_+Ntw02I3&oYkHxR@!R)&O07&ks>hJ^8-`6*|BS-22K>7&P{ zO;AOqrU*w&k1E;QL=3|`0)|PM$1yBs!!R?-_u*9FFnIi&h$BJk(QnH_WOO@^QQHzR zZKV$%G>#cbm;gu}G0bzT*p>(Vk*r8RV+VP!R6YE+TR z71#lasbL#|lr>bm6c^^LKq9pRO_u|&o*%>^$HlnYp|_-F=~~I4Z3v@Ic_l_43lKhP z6{)v(3CeYPQmo92Yb7#__bEPTEWw|3xMY~X>hvVVxI4JiGatcKov16U1BAJW2xw^x zHMKF=o+{#ehqDqUnq!;@v%w}!+(wCGBj{w)ws*eK`$?gy#i}m9Oo06xhH21*#|2o) zFMH6bx%Xz6l;Q#i2L6 zza{tou8^JZ!OqS;EyUCCqnwZE^D0<$`Go%7i>{T;5gpZ&jlAS``c4GZ&YwX-o|( zC1Du$Z_0+1AZXtlC1O zjSX-!%LX zi}|l~u~uIXszssbyviTOV@@JaYa?zP;f}{)jyXk`;A+u|q+na&Hr?NR`Pfr#*r~1Z zN2gG!2@rGGS*(-Io5~pGt(7g@2=)4Y7~FplmahoMv?y;hT2%n|;qe%XAZgI*a?EAI zj7jdLXkao$c+ zYK-p^@kv>hgkiN&ObshqVwff=|6E0oQ)oIZ1G-Jdp?!S|3~L*WM^rB@d!&N#;V|?Y z%`L4lKMuYkjJ<)bSQb1%I7AqklU(V)N1-@9)Q+5|lS! z@Nf^T)Gol<^AuPynJ=lanSFf4hmYnWMp9kr>>=6DtN3V6QoKt&nFD>%98-@l346*EY5S%KR%B_iyCdbgE)_y?Si~AsY!VHl=n{hR%m zeRB{pMwucccnxM*df`#cv-mo69g6qyc-j$;X+fADS*ePX->rmVS~{~_tOWVJS3;{N zR=+R>4a-nn`}d$ROpS{r=vq4y&-x5TOfz%5IvIjiPV-T%h#ua2xdy8i@<3M&j_E`g zrvs;?Ar8z_62z2E$C?CdH$jn<~&g ziwZ7H?6K!%5Jq2fKwgat_?o>ExdHre+lyP;V8Updv=DXQ%@l(A6sfB=T%&q*YLAd{ zIa263hnoPqzxl(`=+w#L0*%|}!t!WeR8=^jnMV*5->j*%?nR*Ya%}F(R{>LwF(ORQ zenZ9GGFRc_pdxkeo8GEB6>a6Q`zHTVqrtH0DH$|jSgcb!x&Zlp1E5=VF0>8?Aa$G- z-XFb;*3}kbQxE=c^7x>QA(i@*!=c3{2@fafBMps`u)Vs|wDvp^$m<&VNOeZz^`GC|^&4z5T(RA%)7}mSHXAOFg=Jj{U#kF339p~5TVdByi zc(!vowuFs@w+=2- zHHoDg56Ab?t0b($C42UO^%r0m)>nOC)oR9nE%w2*YCGr>KLK0g3yjuO97VSo2}buS zIHoPfY$S|NNHRQM)lya&hx>NniRrJnb2G5I4eU)u%RUKaS1B_ z0cYideJKJ(H|!}z^h_l^>t;ypbiew(K-Q(llHhK{$U6 zHWvSnr!$YI@_GNieGe(Jlq5;kNDJrOb4}W$P3qmEUAxk%jW*gE+`?YqY{|a6Z4peJR8Pc)B?sn)WOG;qUcJK$!Ov* z;!B~}bxc7tDs`C08I%!XBAUXLIRJY6r zm&sO8THX!g+w>rpf11O1OJ2`1iou)Dq-#F<$Zw`qc-Kd+VS}2xm|PbTKOn6YA{Mnk z&9e>&8ct;*1Jo$UTGAG@(f$W~Rr&{me>p?_j4PnM$r)1D>B4rp@6G-13%WjNCx@9J z!PJQ{z9s3qy1((&EK5lA(+%v|zH?07$GuFnA?<5xM4jVkM{nkc4RRZ-Ar*TL5?r3?CU zk1&69A!B)@o}c-m4SIjk7KeK}IU_W4l`sF-A38Xv1-9u7z}QzVU@_qWth%}gb_|h$ z#`bDB2N7s4?MEy=K+Tq5Iw)pQr-}fn_41R4l@O=0)l9ewzABOzq z>~|d>HT+-u_PUN%XdmASe@h&xzV;+Mu$~Gk-Fl#NqY>m(KBDcXk8l`Y$%5{un3f~I z(>Li$Gix+T$hc7oD53flv&*G{FYXWRor zn3-C^wlp93b$Mq2ozQBf1V5zDa+v>ZHkuTZ<$Eig-LK4;_R~0Yb^-Hg=?mubz(&rhGN1Pqf;(tq znMpm6x%2~wjW_osby8EhU!d4n4_SAuphjjN?9?^~A73XhI`$n-X2`=5SIPG#PqL@! zQ%tM>_4L)bYRnZXfLU~n2)_w}7<0=czStVs=RMsj4f{Z$tP4C}z2`iO=U?~*`tLiz zzvwI67{vp-u%qzgk0Tsh$Ahgg-{9;|W%%MQnY8_qNi(4swWO!%ZZR6n6Pm)aI~5|V zEm+C4^xfx7QH|%(UJptA&>Z_4y4KZ#p)|cpt?ht4UR}_5q#b4k&WDxBr(wR!0+{Uq zu!pAm%HAo#9~veSKbvn7j5WpNmt~|+ZXC>fYN46JT@!>g!UYTtsN)4+qrSLb>uEXF z0JYHR1eJmsh|X_^_#!GDdEE`S#{Y!a6-!|9($nzCYZ;_xPlb2-@4=g=4i?mFT8#N4 z!AzkTiyg1iyJrkxrc>p8rtDSTjzvNI<92O4kCA=gaqbhyJfQvVQ>hvE-fB?4_=}dm zw1T?%ACS|l15&yO29nQ0+WwUgw|pj5cGp5j%WydTO%jB>FL`gAD5j%Qlz!y;5GMG; zTar6$H)FKVR8ahf&#Rg77ql!sLQF8dcdnzMZtW`Avw&)%s((UYMlW2*E(gs~PO!ma z2^#ss6y@YJp?oJ(2p91n;+W)nV4R=U(L5uC)J@qQ6Cp)zkANB)kM)t$FhS#8SV+t57@gnXIR*{UST4dAZUN&%z zGn9RnthBWf%o2(jX%U*fr&^sU?s!Yy$*dF_SPWs$J)9u?`$h_Tynatj(*HrDW;3YY zE{52XUC_%?-@>@RFpM4tANtONuoo?)bm=>iV3|ysKCs05*<#R?-orhcE(vBW#e{Eu znqH==$_yW%4Vq?FFz+`H5=I}rEfn68#=RBqAm{{5s4Ss>WvNtW|4*>aYXl#&M2GILWEZClz$YO54Qlj+6daJD4Mv0j4lq!_yZQF?K-JX1~6tG{VIRq2Ft z>@l|*YW}OCEJAp2xDZG0IkDVm{z;aAH^p4wo2Flq?c>*WQunwvf~q~P3NM8}WyBaC+j7WEPK7#+ zFvz@h1tOXgsDo)O#4hcFNz-#dWaI z_X+qJuYU=bhfCv-MI{{Oe+xQ@VuoMb#`6|5^J6YkSwduv&}R58#yRXYGh#h0j8%FC z(7nFiJ#ZNlc7N@ibrErUMT3YQF%!674a zIL!ZE&$|?Jx!#30N2ZNmw2f{yX}j2nzf!2|xDSVkcg=*eU*y4P%1?CJ`2n)uAp?P# zuVB-JZumj(J^PAkU`)~-l;$W0(HZ@y*X9ut9gxO52EE`gqa{n=A;laFYja%mJgEjDqMe!VFvIG-HF)BAl@hXDknEWZUefy5{O#8z?=BxA&^fOi( z>o+EY*gpfvk3Jen}!R6Oa;2pb*Y${|SO;wtDd4;3&uZDPC zMH+`Okzmp&ro?kP??Sy2b6W8&X|yzAUM+pggj;B#_tr8vb7MU8RBFO!M`PI4)`fHx z^dY!18Dx5TXqj&@*t_(@$H2Ro%YIlS;~l}VID3~B-XEF8VSe~?NA+xqN!ovlr~Ooo zi7qQ9JtG&PqM@P8q!?B7H=BxHd}AP`VG5i)zY3~;JHhZVYrykzJh!0h^D;p1gaR(p zosOd>J78~HNBs5SNIYrb6#Ut+l*0&)ahO7i$-MWGSG`T0`F^ID_^$9kLnC&v*kucv zNMvzZ*JFsL9pLkqKZ1a}w_yqYJ~&pzfTu+-yt{S{!beiah3z(w>$;w~*{lg#cWO}R zgE=_UwVK1MkYK7PM)|249}ib%QkN7H+{85kKuY(kR zd@K_hKo>75bHLi{G<@+P58JP3hXY&fag(0pIJoZ+hxtJ<24}9O_cVUw-?b?wiksYt zl93lVnf?;Z_@s!N{UX5sdW(*Fk~|wPZw}K%F~UiH>6cvY@~5g5lb}Z(q&3W)n3Y(emqsdhPjeW! z(?nKtN-oIkr2V(Tv!H}J$dCFag>~)*L8GiSKJeZN?+@|DXDsw^mE1+}@V3W&U6KgY zhFu&+>IjXh^IFow8aMKfeJmnDy3J@)SQ*%*5Y(Cr z`r6?zb+s(MyD1B`E&2(&SJ`2M-tG8H_C%aI=RQon=YlUaV{Qq&-_BuFD8|V|Rd8hR zXWr4t#UyDxW>*G$V;7m-6)wM{iH-Xnf$?J&P)!Dh(NZX)CXeB8%3neJu83qT$|2{R zA$HDLi#;zenAsBo2}>s9gOer2eg#`N%utFMkkU(!R;hK|aiy4KzrF`?SKhKqv>vm5 zPD60bg=nbn%b;#C8BkG9b)28e!M!*F5}lOsn9Co~r-j)-zO}$(Q)is96XOkZ$(R&5 z;L-J^Tq56a6NfRRm|*P}X$t{vH&@KY$qps#x=+GI+|3f$KCD@IrYuZjKy}-x|@JTIG2#sFUI*ZQlkCV@5G6 z2dnb#J<3j>+EYyC<{m(blUvv+jXQ+ZXZ5juR|2(VDdsS-hm*LtK(NIl*mqGKhaq=T z-|?L-e;x@PHgquuT4T>q)Kjv@g&(lUm57gn)7EnsJBsn2d4;!oqP0NB_ANPUuf%p# zNRhzRci5M9!?EYf7f^q*f}6CUid68Q{u4UVqhPjB1JAdX5yh`dAiJef;EJ{j-rJ;s zKR5KD$42|e_?ZJ7W~>K?;Zw}s*^79-UVegiTc|kcy{+)x?>Kg(jvf2p*)SaJ8bdD{ zHK0Y?6U-kc1mpH!(EB$MMi{E%4>!h(rbqS=pS{##@2C^rSfq}vd0pr+eof$_rAR!Q zJ*zp)Op5vWK%2KiHBR9Bm=^o(yv~#qo07+Q|FP94RdA+iFgR9x;6~%}RRj@=w72Tq z>yVS)2Z>*KBBlSNM0a_Y=(FPC9}|`F(mWZ6R;VMrT9Y|U$SMxwN-@Ik%XkA$rGjzt zB}AaKLTD{Dm=u0^#EP>~*S`8fFKuXA_=P~`pe$$}{SQo14uaPGGI(-ktf*{iDM|6C zo6yub*ns~VA~QTuT4X9IFEQaTYgTd?cZ$i6n!wYKkrgVhr%A6A#JUPI*vC;<*pB5X zuy`3C@~OVoX*dh!#o3@-E{)B8^TBQrH3^*aizN5^67B7Dk2~v(3;KKE{nMRjRMR5z z@@hNxY&0dK*+4P!1+N{OtaXKrxh2H@z5&1Ivk@8Cc8d)j;}6#|q(Ll$Yd$Z4;E6eK z(Mk@t4ONBhXfvF$Jxcs1jb%%(U585Kg2!L@4*0Pes#tVfxN^cnR{U%hNk+4SVsy{9 zIVyWu3M)-Z$;wqO%vIF}Hur4+D>^$4qP8U=_hw6#>n%UAF`T>(4ymm!?23rqEO zlH+6Np{NhL!TTJ>SL7SvapxxfUibazy`~$7Ik|$Hw1X5AKYBWEvN{s3-&#t3%nM+= zpCq!T(+0DbAGf0|4H3vQy$w9Xy|=nwLFyYNjMJ-8@!ux2;k!5LtQiXLN+*N!2U~n$ zN-f+Tc*;B;ZUmP;J9E3hMRyM4PcfmE$vofPbA-1-O381_7>ZR!H$j>Nv{U1=UO9hX#JZQf+ z2p^uO4F`LQ&>25hwC%ScI98UTOJ}X{^B>d^c-eZUTQC}yub;$?##l0GHz-E)Ru^yY z^|iti8f9er-9)tec_w?>4zbRK_2_ef3i!|c3$fwJ;6sHI+p;zA!HV&)>|8C{p>m8n z(a4V~M2G*IfGfSf!N-bLf%udoUv>wJm%zkj+@yt3%uWLZer)@0VK%>vyqve3{j@uf zU0f*;R%NNeXFCkHCrM$g_le-|nh!@5wea-ehX5yzf}fM8;ev^GaCeX#XyGZCoUMd@ z9%2{ip2kr>hj5thi#SX)#YD~Pke7am(#M%Ek{!7zUYSZ7dWZ*5o%;$2{)y)>>k z^a7%n=EEu7q1bTS3kdc{@=nI#qe>PS3k;& zL$(;L&x6)0PuWlX3vi|HUv4zIZro^cDdv!zG=Gd*pm5jBG7{`tPd4Nmp=B0#(^c3M zu7#dMg97fl90$QK^16iA7BFxWaL=8mRI=zvK6%+-HCvjYqQArQI7}_Y9GtmY zU=p=OD1EYwOjxm>XsfRW-5KXOjJQ-jHANNgcohro$}i#KF+&{iuL%5~KY+ajGqJE# z8y9^@K+S#=vCp5&(0as{xGflm@5kQcFwL_#Oe4kkI-C^@Dw`)v3o9c{MZeJYUTHA5 zY8FJBWpQm0BrqJc#Xdvkl z!G`@;P|dW-$YoU_)YP`Zqu^n9|Dzp*92=>$NDGyx-YJR8Ym@==iUnr6rF+u zlfB4kZ#nF-q{_$9v}gA@nnAy^9eVp3sq1eRc*f*|=MG2wwBj_J%H)Y;na@P(br$)% z)ktI{Wr?@0dCy^fOE8ltCQSDpU&Z}HT69AR$;eR@D$MW)r+JCUczZeR%<~T1jkDon ziyQp-XAYUGo`WZ!zEAYPYrkU_PM?1YQf2f-n)zYmq{|8t=v7C~MjGQiXWwv`sgg;< z6f^$!S-#!{UB30&64Jf+DqE6v0@j}S$YFd$<=~Wi1LA`8;P|Wt6j^x)?3^;8ga*6@ z`!2yjJN+Q`P$@ZWqeOBJl?gANT|vS#hv5=s$!$#p+@!fs%!E-#_`bqW{-3J1WY``V z_89%w1Bsd3q`4d_29q_^c4|gFTDJQ(3e&X&t*04)=<8VXasy5oau)b?ciDUA)}W(F zvyk;34faK)8h$3q=0>wZGMdE{vuFAizRkT>{`WQ1UBPM+b9{$Cs7gOZ9=9rJ$nG^@ z4I4OXSBAo-o=1WlIZ*J);QFUI{9cETY<4w_|t!98ThQL-oUsO3%7V{I*Im|f; zW;Mmw>iF?PUYRfjzl({r>QvO0e-?OKZlHR$3es>6* z%|@M$TZ-jrQ|J>l^d?GrtemTgZvyM+SQ5D4Cs~WTRU8R=87k77z*>1jgimQ zarCID4{x1TqeTw~;q{+r(wP4KH<~>Z)3&&d@4ERglVVX!Tw^BCX78urYiJjqBiC{8cD?b`F`p{si^klfbBV94u~F3}#UisPDieE&}E6 zJOCL%lkm(76VSvpop7aS28U9}KZb=f^>E-JB`h9|tOJKRO)>9vCo}PVv5foFBC@7$ zHH5aFg>+E}GCubO#1SaD1DhcFbO{~`uF zY|lf$lq`rI6btng;m|xr2<6fW_{mxae3loD$boqvA9t3W-5QDG_8-Fysed6MRE5LD zPUJAb6eC^k%BT)4W}0IPiFB!kFui9i7{|R8inF+xX3^lW`X(2%Nt1d8@q#FbFlON` zQO4T+^RRT?AlMh50*5;m!xZmZxIpBFmHnQ;^PRW3XY<;Y!$eYyzm*14!K-9S?iZ5u zS4CtjTfrtZ7cyeQ+FrXyP*1=6>f5Wq*gg)@Ea+D>nSj?}HB6dDV6!t-{C9^^!J_Lt zXgHt1^$$j3eHj*HXIF3-Q)>8BqT?RPp(ZJFc|KS}28{zSyB$&{&6CUq2!Ezlx|Y=4H6V*dd}XiD@Q?BON1*kognF>{L0W7Qm@`?B z&t!wwQ7s(j3Rqiq9F#jBg6y77r1n+;KQ#A(;hM|P&^sC&rcr{)q?kV&W(Xp8#4^7c zipZ8pQskmiGKuVqWmoNx1KG@ybwt0*mZY{QV~;OS zA$VLhmtjYVB8bg=3m&~W@b{@MwtFv!mtFXY&=Mm&zWO_KyFCIIT8#OhQVjaoC8@yvwgk@zO6vw*K>vq_iR2=%ylL|VVWt%_=tP@{=}Kg#yzEE>AY9Mfv9p;X5B&Z?e%ah z6O;h@(jOtMv6H*7KQyB4bi=Y>-A;X+xT1nQ+W&%_N@)lCk@r9uK0sm1Q*hapPd3RZ zio}@zB$!T$k&gFs%$;k)$Q>*r3!hAe_2*2J57UMeZ~2B zpjk-}ZaD;(tQ;%)cUwx7)m;TabwTjEqyb)`Ot{kVk1U&D&0!2Am;s8}F=#Wd{KHV@ z#F}!l`V&D;=P~Iiw;|_N48b1rZqjfN?U^>^CuIK21$VZI?rZm`Hc$?$%7Ey=Gewbc z^A{K&5CnIW%V5Km5(p{&O9Hn~;xOhCjM6bGxIFiQXFAZuuXn8=uiB*857NfOv1|sR z*(f-9Y7aQ|(5{xFn_yB$E*ScM2YW{!s44#d6V>cR3%oy)UXdaWlS%}a=`X;5+E*^E zdquJi8grPRl3hTHVxA2P;pxmt<}aI6N&duYvTh2a$*bjN#2=NybRP?-ry5Qb&w37% zv#SLzINCzkw;*DO&D#vPeP$n2$zMfLAqucA(gr13nu6DEdwhMB0{${*Cs5~R_(Y9_o`vcmF{VU< zaio}hhv$Ntf)V_1-D+YGZADV55o(Z@X74)4!R0wikg?HM*uSR`@(Z&-+e`{qX~rRE zyEf$VU=;FwY7V<(Eb#Vr8NB`PUNBezP)UvJs)r2WFx?W&bc*?DTP08!wwN!nuO{Ao z9jw8`dbG9jpwM!L3^*5GL&nsj$eo^f^ER*oj$Hy z+zTS9n@|@#8@?U0flEtOILz}2+@#GHk7jzk;Dh>g{!e~288k*)IP=;l@To8nIJ+xC zQ)Djkq4E&VQLjL}L)#vf!@6o3;M&lM6fbl!bEhZcRnxTayztN9d7WNHhHc^Ma#WIL zV)3LcmSC1qjNRdH0{`S<{$ZPH(mB7E&Hg+GBJPJWDZbk9LS6;(d0h}oC(Oez5n>_~ z@ZujB+A0m;*o|}CX=cSqZTxz48#N2a08d1%s!jyp(<|SB7*i^FZ#*dGR#Ug2-$;dt zm8~X+99!7F>(jt@`%9+mxCcyE*$>UGeO%pbJX|9%6wQO3fwK78f7$Siu<-G=I>LD zrHe;%T7ub6F<-oz1fwTnMtW)$i4+90CQ($d-yVa4ZYF`_(l;O!$YGtuLWo}T5C+?; z<30NuKr7}EgzuY+4-L%4msXX*+NEKzPqqd&cGAFDJB`X;u;xZnVaY9l;}r9C;Emvj z-Wn$BQYF!k(nZocRpIF*8!+FH2yW?bz&2SCi({QhS`jeMbTE$iN+mt}5 zco&QqX1a4Zd11X1&ePzqS>;Bm($0pUEqSojK@H0|C4#Z}U6|@*fL+?^pd&sVP902u z^<_O^lO_PZiZSF(l)`&86ro|AGwxEJ!(m#@I7}49Ob&A8XG@J`mJBWLw4$rP@q++fA1eWGTJJ8Z$PN)dv*?XborRSt99l*0%pX7-@7 zy!ylH%w^hNKwi0EayrVzvNh^adcT348*T@!_}0Bs}&4=^2P3zb7k; zO6Cp6El*lOivI8zZZyRd6Pl3XAWZ$okMb@irAe8LYswqe!n+!kJo!MK6X*#uK?^r# z#lWQgJJ7Caiksc?xbTCya}4Z`DS&0}x}q-aPvoS>57Ou4AaY+i1rLhQ;zr|Z!eMGC zX4Btj-i(!v{IT6dL`i!DjK9B|?HZDUdi}m|m;w_O>@zO}n%mF8&yrzyNn|#}ek_5d zC08KlN+{gjF-eqh@E?hs(@oloXNp9&b8z#iaUAC7Xb$t4Vh#*i$Zsku;=7$HB2)h^ zgKu`zS(7>UP819)eT-c1=p%p!WcK&)Z`n1Ne<=E)_Mp|J-W935m+q*OQJ1vSxlLNhY4^k3_>CQxAU8mNkEYKfP z3f`~hLEOU;&>LO|LD$p4_+=F^J2t|FLuaTQ-dNQ2Ac`mid6B_VilXUvSKx6&$8wmj z5=;-p>|a#O*AwOQKXet6H&`3?RLn$rW>Tn^CRF^FWPp?RBe*<&Fzh;?fm+^OhfN_g zg!i?U%H1%?%AbcVxSe$T)FHR#wg_)%-6Fp6YjBR4WYV4*bCV`>TuQ3yjuew)QO`Gc zPw$@kLy_Zf7MXNiRYl6%%Prf|$TD5;3dy^hOVRBa|B%YY8Nx4H zXu0BnG}vY93{&1kA=k>OC~l`N?9Ytn6vXX|X!m{-T87>JoC&MsLF%s2@Tt@R^`tDs zO|u(l&J&MmE*KrIN8rotUg65XUz^08<+d)Nr`%cP0 z%!VS^Z}o^7Ii7*_cPzm2mOe_+=HuS;uQ|*}$r3Q9n6`DgOw{YG%&@C;rKQL)lb)Oc zrKcfmfrAQn@epG+Bn|=1?ziZ(PzeGiJ%bs?Xgv<67pR5F)z_GZKER!5?%#>Wi`GuY z1tzaJ%m@j_o?_TrqnY34=a}5T^z}TPgyuQ=!W5cfO>I=gTJE8s^wJW{GI;PKVHj)~ zYX;U2V?b|`JWg9Z7P|9v@rq-=L3-?U?v&Gd-4CC8KORpR^@PLx8_umXB*vUKXWli0 zF_vD%#JgZ0laX)*w7j0PBOVXJ@i*^r!m*=9LC`VbH29~T0ezCKV;V6#d=QocE`B?i?mm*uTdj*_Qg49Eh9`iEso3B537Ce*!cnFOiriys; zqsXJL-RzjJ2H4a078SjuK(iIy5oDjyTXYIUzo9+5%ZFm0&)4DJEPKoxxQx3aX5$6V zMR4ulS`w}}7#iPYGjuRg3KGmNirMa?D14uGkQrE0O5!J6BR~5elclFL$wXx%96aG3 z1fUmG1k=Txp+h=pZ`+(WP*$Q@s7KSlu-OEgehkDn_H4&C%Wpz-Z~_w|dj}OP>=%eJ zIa=Ikd??1Ka)NNH({x6`yo|`_TCu|eGKkxb^Q`>Z(KtUY95QLOoyXWV2tLC?iyO=B z0$*Hp@UlvIlo?YGPijx%iqZ`@cvl$6eI5iS9o^y1-W%Mcy;0#XCn?5X(^!~w$B>DB zS4J)!GegN|R7lr710sKPEau{Aq4D50otg=r5J3qIbyr-A1BcvU*!aZ?;nhz9V263& zcoP>K6-(C5ZS%Z z0{hI4fs(uQkbC+oaG{~=FM%CTF(N(ee~TrU2#SfWmKHRc-{KF| zsvy4)-a~DR<;a|evaHv5D_nD(`gOVrpkn7IDiF^A|6VGGGmV2&e}`jiK0t0My&%Dd z46xQ+U3~W3NL-eA5!`hzl693G9EPvJjpixE`1U5GtK8beceSh_H&a!3qm>5}Z(*eH z(^pe&>+B6@K_>M*mnl@4RtZk}(J*eG9{w-dMpWz8Pewkm!9%W&#UpIP1Ea&kGOK<2D<+y95l^)IbYO20ICA zq4~~jm{&Ile>*x=v{p`D6u|QEx8YWJ(;qp!zSA5IJ?bLr)2E4~=x>%BhY?XsO808P zQ=8Mg4yJ+_fhNnh>tN$<8}dgu%2RECFQi3^K!0Zi^eSdU{D)5vx#}1gYy5_nB@;wm zpBhMY{46|f{$%_I_Wf37O>2)a%>r_aR`w>V-axgVfi zo{aRCoFgr}HAQqVQjIbkri@|~Kj#S|gHJhRb(Rwu{TW29Wft>jxj(Yw-vfJFDKMr< z<4voJz;SOT7lAr#qzv&IL2zv9BeJa{o4xaSIlfsi4WAHxfVco%G|Tcfo6(cPErItE zOdZ9Hu^12p82381JuWA&-srGPT+gB3Rijau@?to<>;W=Amjf+PZ$N*fh$~kRMW>)C z+h)V2H!f_@F(>rQU=|)T)&cK!>4aCF82!i#Kz7>KSn+6-C6m@fG5jcL;nbO-JfUwn zd2oC-!k0Bc{hB^{`ez7iY4tFKSH`P zoybh{6mp|!R{wpkAy_GmQ*^m%pg2y*iu+#w+y#0UyKBHQV0xK<` zw?~)5I7n7nKgICoz7=>|g!6S@mJwgAf9S!D)lf3)G-^8Ag0>_*L0YcwV8`Is5aE&p z`4c+5K z!L(0xeES1sB>uq-v{{M=)h@?To5L^EH1H9{_kV)2bwE`94@G?) zg&OXd!;F)^UMf zLX#GT zIGu%9b|h$C_{QWdpk0uMep0y*!z$OwZaS`Kw-ZZy^u^JTfKARyA2neJ9f zCj9n-7bzwvt?fPvctk&E+O(Qz6?MX*7$+M47c07qZ#DwEBLvn99>7Bur>%fAxx^44&4IHwYAj7Ub!y-z^P z;4@V~3_y-?E}UNWkeUh)!eTRFr-&DTCjp*z|2rfm3c=;lb*Lxi7#HtF>K0!Z--u>z zrG-gG<3urafr{zVJytRrPpJ{w+|5w%VG}E5Sd?1goj@%@seuEnTv;N_0aL|DC6 z^*SxYJZTK$)~J!PL={x?I~k1MG=cmHY7%hkB^MVc4;_rfeW1j_6!U;oI4}+^DBuldrrb(<+muM&_`9 zt6R(KlEF1MvZ;sKeYn1UD9+qPjU9%kOQM6c&%?SaS7F~r1P}YH@Nv)6=&ITfd_CQk z!~AavtfiRZ;v4+_PBW&7Hq6++)EeDeJDxtX`Xsr#-}NN1*_)@cz;&pZ3dSnRVe<*aEPvlm*fmF;!#GPY-r`9sqSo#jnoJ9IS76Oj1>3y*S+z@{jQ*Mo z$bZ^MJyVqM>Rp)-zaScBFB*Y;%3DF9oCbqgRlMTvW5^5?Fjw=3p)=dIGXbMiNz*8L zrqh;aIa(!{qZH$(&gVI5sxhC7sENbX6)Z{H!%CSb3yc@M;$7`tKj9TRRU zG4}7@l6B{ou>s}BnMa{kLUBB;{!;@yIHJgfRQGIr0A4D?vC9bR#yBDe#$Hp$6`7C0 zGD1$|F|mMLO(-PA$Hs_uq%=dx#J?P7mIM<-F(zhNj#>^f%%|^fiHr9LGzE;=e&ivv z%Xg zV=9ABC#rGJ##Vy4OED3igm>fjAO4uSwrCVBz!JNsNjvO{LPhHOIrRKn)#)lR7hDe%344pYnmj%-Zx5(!MN# z&jJI{OtV+y_j4LZStT#pN{q0_0Sj(42PK#|in%xG6hEED(-tPaC0>V2U|Uyu~g6{QfwFL9{_&vkj=dfgCm zle*Byp^uSN^B)?Mw@H5JwDmaL!D@1&Ns)}E zo?_%@>oZID9cQLbc}rsJf{@<&BQzuH$OP2ZanV6BCMtd~thFyk*n>*p{k6tnrV3-hG7l=;aP z6PwV(=tfW+s!P4hid*Q}y?X{7J=b9gP0$;@q(-#IpMc7@JcxfxUrnDYv;&+ycss9$ zZTy?)NYx#D@aAT`eW5+p8Y0mScJy$Vp%kO;Ys@6gde5}|D<(s}=!gtPH}kLE(MIAH z6G4VC;J%y|ktr5}`TnQi^gEvRwx#`qUiLr{lS!+*FF_ynMbY zUa*ngL+P)#o5L7V41ZfUzX3{^^N99RHF6<)$LSI!oqepMeg`dBiUIw+Bp8@g2Qneg zsAQ3rV9_Nokk}7Jq5U+5QwGztsGd;g7OYdZ#lE%=!Rku}d_Ve#`w%SY;xJ|uvnI@q zzv@^fV|D#4;TcB|RkMA>OUjT94(O#Lt<k=0~NoW8@WZ{8|=*_S48<`T$kf79705g)05RrIZ=1vR z@<5?f)E!7Ki-K$2()c)S*Q%kTi4Sy07PLbzhjFEtr29p@O{+2U?tLlw5ZS@}4U{DT z3Gdm9rpj2HBQW0c0W$yl3%!Z-(X(~jv)MgM2HV#8qC}TPXwczX5cnw!T$jsZtY{6( zdoOp?0_oE>+;e`lrH@;>w{;6VdEw1=dn6~i`1dcD^1TgW-azSys6t>Bc z7X7iWA+>`}z>44qs8Z;I>^Y;rY;^%yG)Yb*#{86Ec2LYgc{6^ZQaqm@UQY0IFZRKn zP2|JnT2>rP5$6cR%9NI!UEp$}oU8P5zmoQVTrz!)OG`&-@VEv3nYMG_i-x|3f7_j`wKmf=^(+ zvI8P!)58DaHrm%F9MF$q(1;r?+V^XKz|c=HLQe{(^OB&ba3Y%T@|}1;FyJuTC8P1D zn0_ziv|xj4yg#2Rh}UpC!mjls{mS%(G% zt1*G}{TWQm?_7h=^7i1^_znV(H$i|`4Y+^r1pBBd@EMMPOJLOPZg$;}=9?35JRm^M;R>z^UN8z9o)Qde)2mMOcN7L+Qu;L}~ zzwb>L#l-7{3ch7o3PN62k+^0obaFk+`nYDWPxCdw>`)ZyNUed8eIL0=3mMi0&fDuy z=Mh=hG$cf*HOvtmTquw2Z;ZfkW23>>WiGlMIu~_WwsP;yD#@fpQ_PqDJT zn(V%-hn~SCBzwM+E5T|Czl(gdXg`j5@4>UK5_)MP6R`kBlwXf>4qQOZ)oSpwr5Fm< zYv46F- z#06z`+8;p6ss;?x%fN0(4^$QX1?SOUP`l4rw75zgf<$F7ymtuhkFA6Hf&yfrqXj1i zj&PU;$;pPLmAf@(d6kz`eT%sz#Gx#lS zd;AA3Kc^*FPky7(|NIb7XE3~9RRKajJ-jvP3#|Xzh9*rN3ai}qbC|i3&`>VLq^!6l z7&AsWU0+Z`77sjTTLyBFN%aXop|mv zGjw(%SgVc2qJ6DkpHP6#l*Z%EiEdcD1m;U7t%PD~{=5{t)EdN7Rd`2`{{q(hX&QQy zvW_(}1(1te4Epqh6R@#}D=6#O*hj0r{b20}SFm_Yt0Ik$U=3SEJdvh{0xW4z<^F0k zTeAjsE!N{cYriB*pq66RTx%2j%P->%xV=O4Z6-vnx*8N)<`jV z%VmWczhwBoXT2kz%EN^r9UIX-c_ZXjBLo#5J>b$d)Q-dQxiTMdA!gc?V(=^sgJq+} z!Hv5%h@5YQpm|ggzbOyw4cnQfsiEon92B_Ge3xL_CRVssQjght_MQnA zBNRRx>#?QYmr(tcH{h;cO~a@yT-A4PO)@7-aEh%5_kBXx-_!~{)(UvXnp7x=)WU&$ z9V~h`3<_2a!Q_MFCjD9Rz0swZ8FO0FHUrLR%xvwD?LUQ{{IzM=HM@GH0JkHXkTsxY-m;orrSio zlc|Sl+KS3%JAr47L-D>=ReU`1Ib&$4hUHruxMx!=IY3!b%y_-HbeD-1JXxww+o>1I zs?By`jrwQ+g4TE#ht`6)tWRxeIq$hLAJ4>ga5Eo(pGNvHaKIJFD=8rE zznPQuom3%lo5Pq$Fq0_e;3mGn`euV;>p>jrTI zN_^_vP46!%+4S6|mIs-lN(gMNgz1}gNkjb+R>o0_SX*BrH|NOV$0?GWw1EVJDdta` zo4{*xYARY;NjxuKWS5)q*cFfeAn~P8f7M6Y*{TPQDr9jh?H7$Yb`Bxg$N`m<#cL zG8rdTT-%MqLz}T*`Dp1eGgJES$Yvh1TzF_(2xb=@Z+>NEgE%zv6ZTR+3vZPuNfF9J zoV7j|hpwSmaJTV+c`j#xOBQeZQpg{m=AQ6?{mX2iwRxyCE2L@;|Noe(t~Q)Y%Y z72t!<{=t>p80ynuA7u27cnJ*n47#Nb@OhUBY;%``dLsnAJM#D_#}T6yuzJ-XxF&y% zy(0Cee)dLCuQzD050h8Y)GB!%6D~}FGX!(wcZf*!nR z{0TK})sU+{84Av*!8RF#7RjrC)4d!p`cwb|HTFZlQOlu6#gvVksEgEX_0Z!}7Lsi3 z#kB6tAN;%V6jlLug84cJi!KlLOC04~fIDn5(DNUoK|GzITFwxMKD$cT7TO;)h;IPr zXS04pEgDN@gT8MuyxQ#vl@HwEedh(VXGnh-ZlM52D}&I+N<q{!|v_R^}qLZ^L5qI%0epLoN&Q35Z zmUNA?y@ZB;*9PxgML5zg2)!LVk3JZ~@S_P5R_Fi@lloH>ILS$LX@3DOH$9BR9{<5h zl`bZ~uoYykMKJzhf0(pu6s$j2gAPsqg*?w^fFZf_r2Vsj1iN#vvi%Yo6QB*V7ZX3C z;sDfum(jXQg}Y~wfC(j-@b!HuNoJbJk<{WY8WxXU)R5*`Llju!U2Tw`mk;MnhC$|3 z3s|bA3S0?RO*K*5js60ywp*cUwl8Sholnn{d%&M^xP;f*gG=d01BLpVzQPoUA(+W? zM^YoEX;7zL7U2I%ra@DP2jpbUXSwpywF4(w2{x(+^*K;~!d-5Po<=FuGbZsFz!3Q)!h2c>&iSz6Z`l@#`=-Q0-k0iHYB+Ftbza#DWvB zWAtU%UAlqpE-T|PW&$ReVD@Ovrlx(erJk95!qG>sv-1vbhm}kW%jwfNwVlz60MLJ% z3fV;1V)`+LH)ygVn}CI(H*8;@1t~O9?Nsi2YUuu6d*eSN#qD&^T{9qblOkx9u*hJ_~S6ejgZ3n?)aT zm_w`2nn||@3gL%uzj#a)!EBx#EQ(oqmYP^xh*xw-q(*~s+4_PM)|qpIo1X{@@)_WB zh`1|{{s7sGgr5Q%Z*+ifVJ39!(4xQ1ehEbf9>VL{4}oeZfhGUd!<8B#A*t8GV;Tr% z;Q}|y%x~K$=5i6X)ftcTlC*HAx+Ug3x^zOtpuUY%5Pc&5y-Ox^9!-YqvmYRAOc%^Z zcnS_%<>vfbv=YpuiMC9A97T<~UX05ny?Cep z6YRWdAlB?hwlMP0xYW1j(^lSe&Sdg?=#3|-R$^vyzu6Z4q@}}$%|v;>MVmJHx&xS< zVX!z`mF_3G%DLhS+5gw@w6aiy2Xn~uX8?u z^@ZR3HA;ODd4O>OW{JxPaM=C@4v+l_<^%fB{e~Wa-L)TJu#!CeYXm*nKC z2PKR5P5&htxL<~6nTEoPAHy-jPx9$X{9nvcB2;Xk_EMU~^zK zifYjWvkhLLI*EnXM(?1O*y+3v9}C}=qWFjQ{wF^g9fE;Ha}q*gvP4<)OYuY70BG~H z#5=YOz#htdX&cQ{;1c;dmx-z7;}TwHWA!VIe>WyxoA9&AeKCqV4>se-4%?FfH+HDd zMmkcq5LRG0@>?y;v|$7@F|xz*ob@wX@0@3x@3lV?Vt@YWExNbYe%#I z`d0?dZwkP9%X?TbsRIrtx8Q5r67lKv_7LeKfxWll;eK>46w5!tu618{jGFM>j3t-@ zBSwo<4sQ{eW|rY=pD&3Hf1He`oXlbmr>oGOvIMYNSP4!Wnjzbx5?mvS;rLIY>bmm- zPEHvqWgNS){kjM6YeysW-{1lHbF#sI#y9+I=@2P5nrW^4Lz_x4Urz>Fp7i-B_gp4lf z)-Kngr&jT3jbjlz zCPgxJ)Bw0*pNwL!l|b?tV%NH~nh!#9m0n!T=12ZciT7_Mv@Ws}L?U+~L;hO9i-2 ztl&+x*BjKLsY#{i>BC3p_KEQBBS5zL_1 zt<3ZvnHD&(0$-b{PB}f(hp-3kR2s?7t8QVDX=o)M8sg$9Qpyf}I}To{ zY9czl6-CUdLR{&hr%x%Yef0^_r+x{J>r!R~it)ox)lOyjyh@S82EIUxe+hJ& z$mGD={``3tajM+9B_)Pd%vz(e5xewBYW0m63^L@@K8j*v*UsZvXplw)RO6;kv$hf216=3_S8ad6|^AJ7!`i7%4< zdbt4x-A@JM&-cL3Y9w+r3Z!<6!yqb4MBfW5gOlc#u=<836!%%q?>76P^NWjDrjI58cWH&v5+V!^-f85#y@)vxmbDj@T z12HjG&-@71V@MU=@{i#EPQp7XbCq6p;SzW@NsE4bZaBSnWD-Oio<*;_uR?EX*b3|1 z%^_h#Baaaa7=~bSB5RoDI78~{wNjk2^E%va(8pI@^uReMo!t9B@mE~+W%+z)$ZE(B zaPQL$KAP!JLcXVsWBbwzW2NA{a~gdxTZ`7!*#L9Ve3-5)IFTO{Fz*QF(2|Wz&2c$u zYmE$t4rqWldJ^_t{SUcflD4xh;V}wB^Fbj)3^5wS1bse{U>`_>f%b1;#aI$M$n}K6 z7^`-MBw2nz$Wzj%VDWpn^2QPVp11?qTd%>$3L=EvKY%_NE`r4;$I?`Y zkSUB8HUb&J42$}c=wd+{YMd&;Ew=aYfTj#KaPAM3{I~#QQ!Dw==r`x_g_xWNvFG9+ zU=)!C;te@)Ew%%4_r!u%4)GoOuMHwkTOqalSFN=lkh`)9 z5p%CH>$as597fyn7!WW`1T(?!3UhIkifHD+V*C+Z!h<6N*jB?g$nlB{tZGT?36EwN zM2g3_B3VwN=zp4YV@%J4cmA>9#uDYqm51Q_eij{YCJQn{H?fX)zQUy#AvBaHJhZX)vl7hsVjWy1!VqufrT0Cl5Kok2mL1q7msJcXcXLtWQ5X`*ym&JSX{u9scD8k3m5$y0wA$2~gk^t>*ptFcL!4Z2_ zPN*CdnhiT$6lu`Ptb-7YbzwuGg7$Us706Mv&gS>BpooxXL&K6>urFZ zsyt+MJPxq3Ate03kgoCzdcmcVWIa3z;1(jrr$o`!iwfYbYOu&xIUgO)^kBE&O@u%0 zs&rJ(Q#2-P5dGXCi66}tVIwdmm>-EJMDL0gGZXF<<7r(}BoYW?Zw*+*XV{Ymb-^_y zIa>V*u?i>N-DeZ}(D^%mfsaKY%p^`@l`~?{<O0j2EiB=gJ^)E3zPk|7(bb(f*0NQVvSC_vaTeQY7^W8BeUda6S-PQzgxlYNK%)IW*zX`ubGfyE>lF~ZP@VR9(+a(vCE)zL09~9+8a-Dn zLNnkW)ISU-vXU0oWA;bb`g0Bc&@KzX`$YsJSLa}^X&1^+_e=2YUGnVnBMaCeL+-PV z+uK2TyBzJ7PW+x*KlA4_Ns2nHU`Q4fgHnh&Q-~V!H^b1JaVX7Mo(_HK4?0VuSU0a6 zNMlK+o%{lY1C$NH$e(RV{BPYWW|O)M&-fTFvTL5t_H9jITZ}tEGJquPw<*w_e@OVQ zyq5QYGX2^{1b(G3)#(^&?6rVb4fmPI?cd?$Jb$Pjaa?k4cPadL`x1|tEU1Py5e#iV z+ad=gF=^*zc+|Iaq+`5VVYcAy090=yhU#X?n%Pgk4L57twb)ivFojv-@ zo6Wz}4WyonF5jp~A0I|uG3gbdHc_4CFg_$nd3eGI)+Qzr?X_%RJzkQk7OOJYckm7} z->O9CDJSxyp#{~@A%eNT6-3^31x$f;DNe(E;dgAMq~zvBw&p|+7)TUoPS=^3P!HBq zzCwGY8m%&?9X8?;xF6%nZdhi8{_gCHtJR}mA?f{TGo=bm`QDe_J2!*J1PCcSXM%~* zaS;tvDQC9(m*TnoebMAaVW$hMh_(7qXN=!|XxJE9+k?$nR)r!flIFK!3@ zeuAlXl~A$bO)!Vk){7qdeP*uJl;XYhx7o!yyO_AFGZJnJEDKVkUlFAPm-_a}{K|ix z+`DP(E`q%oQlxgW6iw2d$G#_GGEr|D9NTjeO?>$k-X=fhA6mFj=5vQ&hS?a3ri}Q^ zNWPR}-?uMWzvNKSzPHas7HJ(Yf1e_KYar>2{icq`yn3lh+ni~KLI<)jyi|rhJ*r^# z=c6Q-q%77idkf=Lol(f2V%V$rkjETXiBna(?Gxk?JI

$QpDwi0B7zLaQ=sf2=0AK-TO6Ex4Z9Qx0E z#$z0W+NfxP2_F8%60a_0YG0P(OKbx*Y=Z~Yo2rGlmJ}lk6=+U&ZRqut|8Djk=)+F| ztG%DV&b2SJ6_lfWOol|;st_W|iCf>GGBl~P24Ye%j}d9`qlqV&DmXe4Q486r6N&(-2F z=>)S{UQc9s>^<|HtOCZvpRjXY6j74#myl`wFZiQLOwWn?XyOOrRI#82>^BP-ZuhL6 z;Q(jamEmGVE|qtrmKXyOqnW4hB@z*_|bS<=fjNk-Y|<4DY;&{fXweSgP$SMdJIfO zCl958$V3p183?1PAeaHVTP;^)#xZ5)GMqug6&{rtl%L*JKI5_Hv^<^M(Lwy5YQb2) z8YbHd7}p{B;5$1Q>Q|Y<=D#UuM_e~FndHC_Cx7%IJ`pNq!i4Ul%|Enyf}zI^H$OZg zikVnlg6B^UXKyW)LuXc;N3!DYkhMjg=5lM??#Z=s;gVil#~4mNN{gewFo=R>-({%t zpFBOIe;UjU3_+WTM4rvrnP+k8+nEZ$_q%(VuH~)oB*q^MLq}mR~4eYUv7cndTf8tLspnr(5IpwD?Q$w36E)HJKo zk5<%BQxA4oT1}~e3xDP58ZMPb&S~5#U@(VRuWHHB++rhn&}wSKhz2W6=pz8pb9-4F#4%~#o`0S*k;ot(TR0r zmSv|(6cnrZ-IK#`2Pn_78d6-=0}?ahW~U~ZvE=bvo>g|FXW z?U`CQ(9;d8Y6Xn_y+)#sGKX~Q@nDvuNbk7*2p+u)LP@6mVUEEmel*+kdCXCQ8FF9_ zvqLdK%p@1%jU%-rtl49#ed!?L(NzVD-4yBMB`ri}+rV$qI^A6m9H2=1_x(tcl1&hG zWIF78GZth~iu8(~!O(Us95t|NkbXhv=5trTxDd?gyNj8s)%V0Tzl-sq7Z&6*eM*IW zF<=u5D`7(}IoRrvcN6g)jEX-)&GarvT}&MObUuRC!baG0$P}n-0}wkZ(l70U;YZUW z)M3|&Cf5lKYs-X(c7m;1{s)W*91E*n4F}audHRm*0sJ=tqhrJWl5n0d1ylup0Uv@< z&9!DMYe*~64a7WaV;5DH5=E`b9>Q{doqG3`Xim<<={mU^!Isj$pnaVfGLX^Ot*eJ3 zPea%iuLp&XdSHR*F%--#MRA9F(2P;SyZN76!hM3#nk`~hejF^GaHRwf#yG1}gY2I*( z7y(Tiewm*F0fH$*7{Lt58N*PDxryszOYr^PK`1fc0@WM-Q(^%XFn@p*z0t65?g03Zp#o<6uko08Lw=?`Czx@Q zwVC+B!--2imEgPM)lvGm^HkMcEHNrAhwatMw9UF^aK75iclNVMXoU`=J~Vga_%}%g z;}fe;&czn=qKVW)5u?q9Sw_&?p#=?nZt@uG5j-Z5V6>n77I$oZoM7~;1S_wRN8QuU zQ^OU=DsZA4)E2AI7QcUj%!_m;v#aAv^E z?h^$53qjVOauGbMhGH28d*?au=$^Emjqhk4Q%o>V4?Pg4C!|=s7%0PwB9bUY z**Pj=$6zM$Ybk69??VUtZG}y3>pp?O?)%6nBL_*%i9Vp7 zl+z7b1y}EA!9G=CG-m}%qZ)!)bK`{g9M-ZtLoho>{zJR}o~7z%{j&5S`OagbRcX)d zq@wHCA21zT&qr?c?x@i<4LNYoItScxT~S^{Jc_#h3HqK`{$UhUxkLIF) z`9UxcA|kIat|#fdA24$uX}qz9 z$Vr zK^aNUDU12uBAd}NcxtFdbG;&*PPX$H6~pha?36kk!e&GNEpH+9XdRW9?13iMlT%J+ z1^B&khuRayuq)>|KbpG&M(#4vb^i6V2t4m=*+FJn)uahX<8LrEt1v}m>Rkf1?rJpG ze%F2PUmoM>{tb4usnagwv*E$H6e1V#rlN1_p*JCO;a9>+P_KB2D$zvvzE-eoRh__3 z0d;~gTsy{cS$CABEs-eRS+0q;ng&zo{Y??)sGOHY-h)#E1mp-9eV;lwyRk3rn34sl z@7_Y-i$j#Sc?Y&DV%VIhJM6{x#u#PHf?JNlg}q(C=n_oRp@Ww3@3JjNc9!6SzQt7f zogwIw)&Nm#TM?B1Q={{fzJQO`Uw$L#rD~xgn54u>70Z}k8IX1JE#;k3gN=fp;Utql zylPqsKKo=A+{qU%?0W?NG(&>XbhvLBpVeP9gN&x`*eGha;sYeRexBLrPzZ+=)oFd7 zB2t6X1T{USATuulUn1FstYaKt!rgC%97G)W(ULi$e(k`QVI+00y@)17VQ=>z2NJislDKAvkABw@li&RTI zN{9J(|H7D?2wj7r(&#-p(!wh$(m`|7q!%mKfOB;oKLvgn^Y6x#duYSuME4&#i&Rx) z_}vvE0=M~v_G$JNIgQETzZ+RnFt{%whFKBOU?;r?n@Q*{_T@V`FjR$J=;MPH`m0Ml zcB@MF1pdVHQ)_Vf3s|ZUq7x;LMNJ(g_*ZHNdR=G;<~_QU4e6=g z-%f@8Or0j}DDDvh`YWIt>;MKY)ac}KZ=qkEF8z3f1Wn(Zj!%-hs*3O7_)w__?#{Uh z*Qa*#7<<7*aRI@6uW%Eg9hIVMjU~9`UkO@Bx+KvZzb(0{h=CWCXw|nfVOZ!v*krH( zrnVbEYMLr-EuREcjRv$|=m(Uaxf(a79>s0*2H~K6H`%l^_rO0|f#z1|lY;x`N`mo% z2O>whAN8WG1fR5WN5g$>p!d;MNu(nNO(zBV%?dd<`p^tEC2GKPhiWvL$PYQs`%CTP z>6o33=&y?orS2RqnL5-#(p+9f$#y@6err{DjIMy$NHBrr5|PHCS=1kS8UC_Cimvzd zARF-t3FkX_bBP@NeEdh0TR0LTv_B)WkLgI+whtYm!$Mr#4EpPD1<+OOLhj?Apg9$f z(Ra6Alrkm;Ja%jIn5zP22f-u_Y7jMbZKuZfmEo}aLm+z9Ef_UAQlgL@2l;B6!6RT=W?&+TD&m%pvNN z(+vEn2HL)*0JTo+1F;`(p})QXXk3jFSR5#UfhlA7(I5eHl3-R$n@HJ)gi=mZWjLkB z1bURCL4W&AiCxGOa22({)Y0lNta>_}4DLdiC$ype6J@&Lycm3DE~3{Rc#6D4x9KG_ zXZ)Yq&Z>u4AK#hDV@?Yb+Ld6~qNP-UwUl~kA;Yb5wvZN?0A+ojNg_u)0wd-Jr1{SP zrJ^O^cW?rfWvqe@V`aJqlm3J!*U}xCzG!fh0X=PfEG$s)<55kizhTR?1w5u+*l)ZD z=4$8>>b-LnX81Y?-+zeIjJYjURs8SXTNoO^L+|ryt>n&l!3_hbCy7r}B%zIPZ%G0En-Zlnuy zjG$_v9RJYP2r(O$U>?Y7#aZ7|snzdF@tR3)_}HG8xWVW)<0^j(8hU^87U3?jA0hc| z7-$)W!zpu3n#-`G6$j~_F=1$fcm+L0Z3>+e_ZHoEolQqty+sF=ga#Y8ga}j`!9?25 zW=?L1pmvdP_xCOO5H!{md!MprLx|8)=U6vih{e= z+I0-U^_sL(G_gI*O2xBI4V2FMpa?1k@x<|pBJu=tdh+to(y)YX9&hp0F@(Wnw*-s$0l@wr}sE44Dzj(EsY42Ou86gJ&#erZn=np;# z#?s@riALA974)VRqMl!a=&Zk!q^ly7rQAa+5OM@s1k=5IiRjwXKcZ}xO8hY3CSL7w zmbBq*Vbj%p`J$!d%_MM7?AzPC>%q{I$a+Idz-RIW=vrHcR}V6j&Y$}f6sRF|^d55* z68jUF-a*oW!!`V9Y=zMbA()!wn=B0$Jr$iCR)uwT&%^23`q*P{9lJwyH(0!mfhGfAtI9wsGRNzmhOyj3>kuB=B!W2=-TtR1|cW`cCNJlvVZA2IO1TXWkY*4-nN*O zt4v6i)C^T)*PpB7o78cm;X0Rx^z8z>uuLe3m51g=2|CIu!poTZXpx%=Xe`jDTW2hQ zlOrqO;kO5uL$nKuAbcuM$Q?qd!QwJer5_y zd*f*Qz@2{AxCs2+$I(VBCqihv1hUaA+Np2_&0#eA@)wWY1fy(h#`NqYb?jy}cq3`^ zYEu44CgX4La@@z6) zWUUI}9YIh#ltuUcBPvPqixnoc6T!R-bY+HFG+X8w*Wf`lfvgsDnEJ6o9T^!VfOC2T z7!#3FzBN%o`1JA^&U#X|7(;Xlt%Kk7*Sq z^cjNLnC-*tuaj9Gl2zl$b>rCP1Cf%E%yq;CA=B;B`AwP&KiKypzPE_LAo^~R3ZWs>zZtN0XNY+@m_kPsa=(+=F| zCGN`aV7X~21l_HHpeA|x*d5ZID2rm~x$;#!TF=hScpysk|YnjV2KdyDz_CmVXZz_I*pL^Gm>=d`m+n z4WzTjsL+l<(GU}`f=)VP4Q}&Zz>^d|KH6WpC^Zj8I%MT*`#ibI4ZM|ZQw~#st@jO1vO)!^PR4Nn^_hN zNc#bL=RJ9hSom&Y2xgwtn=#nlSF}W>3LiMO60LpUClZ;+k#Z7JgGYe@X}q{U^+{Hv}`TXCHIU zvcXdEQYCKqJ&ARHG=xz)e-9;-E~Swt$suVvG09LN%jVdBU~&$_+TW$TWJEhpoz_|0 zO}fqP2l34qxKVcw_UieWBoj>awabj^sa(s;ij~+V_qt^KSvj`E zRE#{A)Im#j8N`Ns;6p?Et%yj8V07BbdCY+|%JgRaI>@-yE17^1I_+%BJ|DN7GVsj; z+chJ2Orx-^WfF{R-3#XC{b!cT-6}AST!O>hD^;d1RAcZ3oEob^y?}I)EhQR(d)*`jE{6O?)jVd5o(6qra67mx{EC${ zKjWK$D$-XIigDoH90-dk zSAi_zBbc<8!rxj3dLJlB8;v!k`PKcT%f+9u;^(1ss&5dF`QJlpC72xVKt})A1g7Lo z88&=86_Ch#|IIkfqyKkgi-U+Oy#enCB$1uZVD{v*hPHkCGSdsw`@}7fdW&xh0 z`wb_5E5=`yAK>>tr_v9)Qh3Z8VKlu2qd8(L^R(~TglF=R5^{(!0ly{PQ;8Ymz(ljrMe zk%K>J!#64w+$Vj4kmOXDYBNN%_MW0lOd*a?#=#kP-G(Kh)eXK&r;?5N&^e}?S_t?&iugPV0Tr9lgDw=S`2@{f7>90_{6tsQ z&7k|W3Hh5A;oXcS7^Oppn5Ci;M)^=F7Uzaa###+$GzN@gD?AkcG z8P@9!hD%pB!|rgB-&C;VF|OIK;HUmC&?1=-4l}CXc6yVW89lnzjt*9_qMzD`c}$@o zwVFpTdJp$8P^To>dbJdfJo$t&^S#1Oopnl*m_WSk_O-y8SSRp#5d@B<7eRlF4{$Rr zW^gQAp7RxEXpsQFiynPfehFl@kAWp0<4}9;V%lzC7LWNVV3re%{kXZzy;Hgp-S|>$ zN-Kf?sc6YytD~&*HPXRn_it#p`4j@krx;=o2^-VIAnPgveG*_p4U>lRWi`CCcpNC!D>ma@cZq6`#v<$@Je%x?sa*T@a+tS>lz%Yy$J!r`F9 zHINvLq8kj2X(O`@w8HHl{AgSR%yEJ_S8E~CzIcym^eV@Bdz8@J=$Vj_{F?P71(;mS zhU@Ri8O?B>DHYBn6%_Ir9J-?6OUXH~cgTk&Kf_@2hEovlIFV+*5W~4GE9p&n$vkGC zpdCC%<13?+;MOW z`)B?Ol(IvW$Fyv1hk!Svof{EZ*pZYShp{{S6YR`h!M_11@JL0D{&}(sc6L7o7*+!V zoBly`=pg!d`d@zcY!>9Begt#h)!%{TF_k(GFXiUB+3{6$H>)hAgWa-wk@*a;zs zbdDj3e9i=@A-WJEueCzhtk>}9O9;d+s)9^X$P`!@56!7Bpm)?qIH3LxZgk$_NAo`m zy&!^7ST{)=WsxARK3<8V{_9{)MG)(c-IrON3{pg1LOjxladU`IGcV^c3NHfAOVyoC zfD8K+(Hc`zijibO^YTEj=|?=+a|@v;(+dsglgXQzgb1432!grnek?I%^;NM(b|oIu zqlnFsUEAqNAn6*PJZ>Jj>_z9W}dck_jH_)F|44lBtLUrJv!+i7qHvrX!s?N=eF%=AVFhM=%vW<3xUQWEQ3;s_-5K zKdRZ*kZRFPl<2Gph2&@1kZ)cH=9Y4F@+DHRWLX4bnS2NkUxUuq-FSk|K~MYQaUDCzx1iZ=KXo7 zVI#rmQ332!B$BIvjr@eJSr`q{=5?StT#Ww~Hsis5K_DqV56{_;@Up%dwAYkj>&ekP zW~#74%Lpd0MnR;Z$C~K{R^h|_2C$~i5y|U(3_CD;~jiW_ynHs4&t#bngT{xY(5i=TR@SeVrEI= zVYe#0?`n-?&4qeN&>0_U+f>r?&RPUchPiNJmjbPDuo-%Zi6$dw3FA9opvrMoR8*2K zdo<+{s4Te*uXm)uRL4@-6@E{mw(tdi_skYBO$4(yL1xKTEfni+tipFE+ESZbDE6Q3 zM6{BLLZ4l<`PivuE_WObOdAk(88DiNSc2UF+IJu$`bHkA8v2GNbmkH)N zN_54#RzTS~5HVO2azoD{->rS%$i7?1=4CL5!cW2(NgAxXoB=nJ9w4Qe3c$@YCE+Zf z;7R18Kl3boSHy`IzpBL9DK8|?+=jB@%|2-NWGPCU(}QGY>9944*yUXP1KA~6pt@lI zj9+#Sb3Iy9KYxPdoNIvT3OF150ir*xhhbL*IZuB9V@xosbiZ4iTdT>0 zmX_oD1D8tPDCtr8d!#n}g zay$*JOH-ibAPYtBRB0}3ryuYZT3&ntE|LFIoGTf-bP4jD^cXhVA0hp}NmJXAmC)9L zAjrUsp91p26&DeVZoeW+|J;5Id$$a)UYmd-z93XNsV{^)tm2~_K2I6w*rZ0k3+@6> z?Ihqjl-b#)Lio5p=#q&649qTtVSYa3+xZ5vzh%(pEYU-eYDwnH1Yydzi}Lc_nJtESQ}0b!Wa0_d=TD^4Z#esxy&r@z95$3Qar7c#g_|}KyyFo zkkCVJ(Zq2~;aDt;8AD_u$2*9`R}9XbrBJgs12il|ba<)`9T2QX?^KL{!b{nZ7WW)% z@kQ7&{RoetgvDkP!8|+{!_;3du~<2`6t`z}vg>~oqj4I)ka~O>@2G4u?ka zCnN?W0Oy><)qBdqXVH~Abm+-0L{562cy!dq!Nf~Xz(9*wxjv8KF+Rcy?LaV_(!!Y$ zk*uZ7T^Y6?y$wC7k3k+UGLXJ;3CLc^Aeo$EHuP%n@8*E$4Ut(_!XPp|`sz-k?Q+%V z%R|3Gm5VEUIE^8+?hWjcg+o`OgvWdm_M1Zlvu>>)GjN%%$ef6i;Lu%kFWMJnr-Y-L z>7c7<9C-sd z6JNuIWT7zTwSaLZ7+ZQjW3_j(XwbV7tg$o;X|8yL5~f~8)-y=R&W{wrI>f^l+>f^I z>;ZP@D@a%QLVDkRfY3>Lbi^G}Rdg$iO7XO1f8INemh~w`pV!2~wnYp-nq1+bT_TvJ zb3}}MkF99S?h@>s5QI+8>YyH`97D!IpTOs04Jho4hkNp*gWSe{;J7pnLQLvmBMBEx z2_=0!^K)S5-MzSRNen)^eh*&vP6yZMMT3YEwCZ8P6!0dPstL=Oem6FW0*061kiC7V zr1iHY_pi=Don&*~xR4Z=&s zUcdYmzIQ}ST>k|*kG1gK+##5mTc$B>hmML?)D`2me;Uz^^$XFq!3&Y+p^tnph3k&} zAd?9B>|0>$?=Xn(-^gQ@dJLfbNVhBJCMD_i#l}*Hr$eOH;%_)D_8r(r1*z2z0TV(n zMgIMn_k9kEI=qPHHtq=eS^<>0y$|B*f&7)6jP8r zybbx+Jm8Akcxt9im=On z$aM(1&wVYi&f1$)!kjpQG@N-H&IaEn>btBvT`PA{0C>;T&pFM-_^2F~9SWN`Vy?x}K>Y-^L8nY3kVM9^J` z!|a!#_RXhRS?ntb*B94r4Jm@rc?o0N83 z+KTl!H5AehSBZN1CxFr4M1C|&h0*jQnCi&03?lyBgJ&1v>abVr@_`|e?Zr1(SF$pz z&+R5Fau(#<G2Sd)ywyd;^NThxryN3P(ZxZ z6zGkMUcjQ>iS+fAmqD+ArYA(af?M*M^u1hTdQJih>)h07ZcS?xHiFRvGh$&|VveeZ zD7mBvKQl@qmH?G#_YY-B&1|Aid;gF4ab!c#`(hyL2=6uYU5<1q>5Yc_rW5Jgzg%F$ z{&#TUv@e7|(xC6Ti|EnIBrxfOV6DGe*w#!4=E|i+%MsgyMbge99Nv8lM7l@NzPx*E zB=r*1oaJaAVr3ZMR>n6%3tL61@7^iVo$sUIp`;&ea@-UGGNJ)BE{EN@6X|Qo3u)8g zxll7eFlCSvHfb}0+3NMtvfL|4l(DNA%k+lf)?d?DZN$I4K}=e#ZQ5o!cE$WV3eh2E$3`5 z6#1%_U^Xt7^|L-prTMk7Eqmg?_O&7%Yn{hedi_7D&ODr|?*0F!kR(ZxQc_Bqq?vuz zy+e~`jWj;eq}kIvqB54GfuxcoB$Xm@&R!>T<_M)p6hbA5qVl`<-p}`QUB9lYfBK`> zwf0$i?X}+PeZOx$*o;3$^*Yv-?@eOhumbG42}^FT#Ijgwt(Ty zu=X1hq0d%~5bxd%2BKtPcFzN(nIEt@$58f0o;x-g5|!Iv5wjFA+rwX4j-BwE+5O=q zT`(n6GBRg1ng8M-SJn0iuC%DKeBzi8Y<43b>=cUNj)4|y9hd~;&l_MlT(;!M+!%OJ zvIu7DeS|k-hq9*Ds@z^@UqQ185`UYuh>>l%Zq;U|BC)fopzae)Jnu~5V+`yqir~n_9xSgzTckE|hhO_rr)d|UcAXi#UWB2W_lC17f1_#hhvSr= z&`IKic0tT#xe{Z)L=Er6DyUkw3b?yEUgkKh%##U!($$utQ3z&`K>$w{-;4_PPe^6aA zzr2DzG`mY4KOHD@%Qxlh@7#y*P7I-ck9+1TKf&V73%trJ5+-!!yhu3w_6tqkJw$Fh zZ#g(DZX+)OFz;@y87u2;D(_gKEayiPCt{8wW^?cfW^6YVNt@a$y7j_-QevXVZT6YT zd33ufbc`v+`)7;Xc1Yd$3M@iV^h&P-i(h^)u={tqwcbP?skFS@#0`ZM20I*J~kRo*~<7R0sX?O4Mu`#HBM3F;+Xh znP1BYA_=)cPrHcd((oN1+G=(XuwdO|oX)LjMLW>kZ^ z4>m;o{8skw(mX-4sTSpjNW`R_Jk3Nr_hts}dqrpaM3Vc9I=G^iAB_GLjuu=R- z-$Tr-#4C)oh7I#&`77FT1f$ohesP`y-blh?9uU({?Iaw_MxHHGU@b?YNZ;@jFuon! zbdQo=pSogvTLAIs83N%umO)S<_A#!?@s zS3NsJ;i#@bi`O(PGWxF7;Cw`se;;e&nBbp^rx_8GSOc6mGFHE zi&b;L-A$1_TK)yLpUZ;fleOVR*%Q*7sR0RB{7Ka0yRd8Ba@d_x4JK_E1T^9->EZT> z<=-1uvEH))G56l3Gg*7$Q*K68&_%LNNnzw5y7~4x64qA}Y!_%jOnnBJ6k<84^EYs9 z%79RmTQ=D!L3L~*d*H%8_V+0nxE$XC6W%s~2GwEzF}wUfX~;^P0xu9#usf59^<|_F zS5;7rlOvb`>RqU2&>W&&Xb-z*+XG)mAQ`8`a!nV^%xw8?#>CIc(z5!o`?{eyqFKVy7| z#_mvvcR35Z%F*#xiFI9sZCV-0NBg9QQS zevxpEFM?+CpQEc0F**klnaRfYq+=hvq{fe%N&G}DS~I1b#D`L7u8cz;hZHWPDYK&^ ze+d|~ZAHQ@?(eW)RyIe*k|BLUz`Suk-23zia{H*Te^XW1!CR*aqwyCXS}S6@>t-`w zyA()Y^m|F$GR?S%i)vgzK)!G&bZM4D>Z8YSdzgx#3)q#QGXHyob z@fsX&ZBLUn`2O)1Y(Ue}?QO#Z%rbEgt#Aq*#Cta~9=o!oAFjTju}0xE_w!5H8dy&F zLQIQ@BH_~OJ}Y9%wxtTv5Z}`)qRj`Y^wz_jx!4r--$KYWm4ggB$}lLvs5*%^h5y~K zYamAHQh0LQfCOn77RfHZo=!uxCg76kN9_EuO2r9Vh2WmdAquM^cXWWi8g4u8lnV#; zU8$$Q1p7zq@2k!BVx;g6V<&Qd--rFtZm@Wjhw$Dsi^nKk#Jo;jChdH&L0Ty*r-cIo z=*cDH;MnaZ!Op`gQ2b5dr4%ez{13w`P+zX(La!bMY{UAI?7h=%;1}@}dK+=DSQZT1 zeox2v@Yw?9h&a;*AZE?QXlaK>R?6}&<+M9B;Ewg}1wRH?6PNJ~f&qq?A70j~3cpQ_ zcB*jiITY`7jECv5(SgQn^v%~0GA$k=YjWZHuoz>K zRM}BRLreP0zT5N#Q_VX>C*qTUadk+7h9l|%CIr*P_9nf9MB_q;&Q@fn?NwvbPt`!b zs7RRHkpZnS(LlythCdg?^UX&QV}Y2v2Rx)I@6TG@Z7ZegFWJJMFP+3}*L~6qpTO+d zYtUGd3}cpQu*D@Eps}9`IK10WWUvSMtP9C-`A;Xk&h(nGNWIhguN&khJ zsEZStL5xe2p481%nTg(AN^|@cg3ajt9PUt(~y)nd87v4L_w?^irA-=d= zVl9LA<4@q?w+Xb$(~aH?mC!!BJGntt*+8#}7m~FiW;$Z#kTWUsJB%2YE~PYlRR#%( z@J)$cdsV==q`XH@XEN{@Ubf@!r01=v1-=k-f&EQvk8}rY@8r_pBY)}gb+720H+Shq zyy>mmC+Y&#;`e3&VvZ@tB`uGh#Wcn}rvXzF$-ukSWJQ55iSLCTsM;!UU2zw@c4A$J zMiYE7iH91;Pr%nnd*i`GwIKygJyVt&|2C4xzt)j2aQsX?j}$}nPf;DT6ETj6nYDbE zWmWJlCeP+MWxM4_eh;%GNxh`RfB;>C2`MFlA}DFw@S77-z&NEU>n$zI2+|BQK!=53kBn2i-!K zX{li6IXJ5tV$9t@=PddK7bHM>!4b4xHvnHM@AaSw3_ezZ&V*{phINxa8PG|+7s%+H zFK-~+RMZ8|h+og`h#8^#D0$Su2u5>G3FTgSb0uTDlIDlu#7PaaQwLUo_e@)eychxp z51)d7Kn7eMGzhusr?JD*%Qj_pj@bq3*zkm&%Z;WQiVNwuvxP8^6)hvr#Hxt>h_Si& zJtbV@0h9Knn692Xh4xyzm|QYEK|-EXfaUi}D5}(il~2~goXfL-Pa=)yVVfJeI~pA9SIK&l?0znvf?+0anFPwTgS0wOElR|Ej75@{UUKF z4kih=yFhXI9avr}-moYBSAT<;kx#qJ7M1j4$mC+W;%TZxDTk%z30LC_;&qnD|BD?5;J-fB=EX!!8gJFH5Fd9aD zZyqA1HoB|Kzop4?g;0 zGZ{=S4rE(@)&qBNKYN|6g~)tAXjgQH9t)nsbp|Vq@y|=~Bh4YEY^#FI)LNdhu75FA zpW2tavvj5l-SVVWI@yA3r*SY6jy_3&s?mXhsV_AZg8=ZfW-+Hbdmj%Y+q+DM!IkGE zXQlek9F!%C?AHL3PKzn=|7|(45!1cmyY%_+Y0|HD#dP>7DYv;;jmB>B<%%n_grvS0 zS2=n*i-cZyE}PSVPlMz8;?4*h%ueg7%uZ3-#`fMhj9tpb6Z@OHiEe`oP970ONLO)% zE=Ekn=@-(`BMwNHQEtKj~i z{53{?B`UHbWp?aI<{4O~JHq4sp7{NF10LV%gokD+?gd^WMyWJdT0LyNw158+TJ(Jr z^nSmBd{{b-^XQo+7+~U2J{@|!4EWYzI)m}cNn0Q=?GEf{YJ`njF`}hPn+;R1g~{$- zFkxyCv`JOiv!lg6g@;5;4PstRFEATj(U=&^qtZ%p&o#W-nse5wqRzoR!7z=~fd@J*Pzl z%c%2YXNkioMSAdECOCdaF&Nc#4HvXoV^|}fcCB&xFSPG@0J7fou=sivcn(owC%ugY zHopawmng8kjij()W`OY9>=rR9r*Q*S^yo3u+Lf6%rIg<5^MSj;DZ$p1Y|hsPf159D zP=)K4$Fdrs-x`mZB3ERSvlAi0{{xDYr7%w!drIiU!=17WSoow3%un5d)lSz1%o*_{ zt%aECL%mXVq>f=8$CpxrA%@bXQ^n+4#zl^QZw?-47u*j9-5S89Z<+AWWVjvYE4`@Z zL+wZSJ;CYT}g^*;Sfv1GQPvqPJ?IF}7CJw&U9s|o$MWE%? z0@M30r1P(grTi)oBx*Lsi228Mc*^{L-I&F0Wi;u@Lo)STfaIdC8^^cbf1x$CO^QC<=Yp)qX#Cs7dKveZKXLdYjOLLjsj`UaAGe7)sUN`%?p{uJ+CC?i>)y*6Z@!W76_T!dAA@V< zYdAU_m2?aN`m0?IM+Z?j<*@_YroN^(4|bLBf4v$!gUw-gA4T@UpTDhE=|_COVZai8}&@yT-$iIz`swogVwSDU2SwJXgTPiVtluV$Nj*G3O4rF&QJv zX^C}TvOY9}3vQ* z`2bxq1;{hZyFaVL9#5~7P0Vu@G#e%Hy;+Tz=xa9_?%Q<6Q@@-R+jb$lZ?$o^Z0|{; z5{k&fY6C$UvOFwmHpwl|AfQqo%pU|2qrV!YG$UU2JjNI9->`vKV}62UtTvmpB~?1M zKvj5eE{m8=h#7M}iCOia&1zV48J(-SgSgE6#fALtPVTKp5>yUe8pcJ@4;Ho00Q2?DFnV!!b}8Ox+iv_VU_Of&SHxr_XEIrr)U50h z%ILa>J;d=Rcx(cH?juwO|W3CaC#bMyn z!ydBS+u-h}uIvVr8^qwa0`L=hlX#3ej2PAQ0_M>$_mt9YWprTuJ;}`ThICHDT%zw> zMUB(#d zu743quoO&=v;J9OV0V5BxOsGEUysrecRIM+;YZUdzBd7gVSY9xV`(&-FT~%o_{N$7*cI?}eb#QWE7IfKS14|<{ z*m(p>yF(CjqTgrcZ(+D}iAyQ%vthc`l$MuV=z+7u6+6Z!8=e*n zFeC7ta2kvI0(1>2t-23G2SuRPiDhyvmq`84JjhrxAD&?DfPaEIYkP1GB<&m}{5E~W z(L^BT>)=n!39BM$bmwz=-CdWA-e*K77M2mqS@*GnY%I#CGFTL(#O_^;j@7T(LZ_wV zAE_WO9n0;GTg}8&hrzqi3t{9KRn~ll3Tt<&E30EAj%Jj&3dHf45h@Z>n?KUG%b!y_ zSvGf?JHYL3ctzT4@v=CO1B1tyn(#r1)mVW2a2&FsN;_XLk>}Z4!@Y%v;C%uj8`pyR z7A8Ypn3l=82<8Ld?DUDNMJbR_Xd@CAfH;q`%9SVKk^ODaLLjj-T@& z=J`WdSEa=ArHhtpvhcw@2bZ8Ha6a`6`2UN2r1tk`yROI8Jmn22AG`xvLwm4b|512o zeML+vV(yy1vvQ9ACY`&#gxVj=q1%TmgQoQ2l7N>dU~CrP=+V%laDO4}R8 z!1T@UN$P|~;j~ta<-KQPl-d8o@S06(WEQCStFSu#2Cynw3hZHjIedOm1^Oz%kU!ue z++HM})QprRkbmhUS6!xTTo zZVPDl-SxZ++j(ICEB*8fHLK!YEL}+7U#lAn{I6PlYQBjLloKk z`*&a^ev3%pc~EY+0JnW2gx_YCIMeD8(=mOu^xr$9Qo@X%Q7$$NZhiSiG%v;pwNbpv z5%@I;ZvVwBj#I6$v`ac{pM#zKu*huM^w%)FrUBC2M#9SaPGUI04DQyAgHk&VwhRdq zFegMz3t}96Yf`rU>29^)Y7tGGHw+ByHAsbRr_gVWZyjch*}^@ZbY+j8Yz2*5sSvsI z1DIJ9V27m;@XfjeUmUBr^6OLRVf!X7{@Qg;AzF#u(q188o{N~jh{*_iW|m{_=={$gq<3K;nH!297aE_0Y1_wcG4xVa*BYcX%DE8-v=5r zIGHBg521$W{MtVwSHR2{zn<#;xI$Z&S@jBSuv#rIq&@DN!uX9{K-FtA2{)=0d^S2S z<6(UTUa1~!1m0>@fqHXAS`ie+qZR&F5;&Q6P;+Mk`Fb^V`KlftDPz?D3D-nhLX-Ht z(Lv1BsP|U(9y6I@=R!KbbOzV*E}Z1&xo>K3`3=oB+NbUlTz3-16h{%$A2HvKKD6?TJi(0kQb0pSX>rR- z6k(-36<$yNh#T0|8}{PNvM5c0)EaL=Olhrq23{5opw*)qbd8(np@lu=kwaDFw`&S0 z`{*_7J)5kt4<~%$7@v9X9kB=|hFyo^ zoU_38m@j1B^Rk`PO^uz0T^IihxI=?AJ3%{iF$Db9L6;o{0e-~0>4u@K znq5!!esgI`)YuW+p?xE{&R&ZoWqEfYdD%1p^Ix5`C1T*UV$gNp?*#btFNWR}^m)7y;L@DYE=&(28F`s)S>@Kk`vCLd5c&{e=(7BTY>Q{G%J zJwD(S(-53bo4$7A)GU{CwpBAEN~ZaOo>uujn~XOYDAY#r1!a6nybf+duB)(Yb!;zo zc(5YO>IfqfkKZ6lTNJP($rTKIULj!GMa*)Yq<1M{nU|HvQ;7?@vfv zw&Z~E+z%ih@{x?!H-!Z++sW<_WvGAp4VvF&f$G)CtkZ23wgl72zk7v}(yL))s;UyC z`X<0hJW=yAO;uC}oe=Z>tCFnWc5mk9iF{fdMkOO34WXu*evF1eHpJYl0n>lG!0$KX zpe{oLq$T_0=uyb$=Z`X0pZJq_U@5%70ZGc>0@g5_QV*tebeV1Dd0y!w5M#CZKCJ5;B0 zH7DPK)rq$PX10iNLyXeqa%pVFo|J!X2`L8S{Q_kgZX+ort5}GZ-L-K^?C$8B=f|$bV0td(UVfSRb z$DTL4*o|E@S?SHK5N_@TlOo?>o=1s*IV`Tw=Mm%Z_l9(1kJ6Oby#-X#u@Em#bTKmf zkBmQi#;bgX=Cmi^l3xy526>>W_zIF2{ea@5cR^>D4l5f_2Kh6U*|y&pM6Vf%twzgW zKzluCT6JalnKoAZ-dsh@p)IW`-mlK4^te|*b*53cd8LS$TnOcO8(jSkjBB;a!n*); z4KGBs!=@a&#Enj5?#iRsjYq3tVPQ7`vrOFFMj<9A zoU!`-7_82k7E()J7xMAEIovNhCtxb_z6;ev8VBD(&f#2~4y90~+Af@=y>@A_p~}x- z(Wp1jvgZWY1Q@c{3`euCo;<;}iQ+>WEn?yk(`DUitH15qOa?8a=C+gQ(0?%w%(_Fs z*gg3Hd>ujAj`zYtb2NS~Xg19@53mtOH}*6(;PgeYXz$oe&{*>x!WOEs7bir*2uIPS z`b-R?mm;R?@Z z@t15_a!0-7M7LmJrup7(hd{h}YTsQC75*i{Nt)MeoJ=1>Oq&PnnLQmFpya{u73U!r z1+MQ>Rrb_wBS^b6M3`wsBBls23eNjdA`8zlw``tKHqTKKW`2WMb;NSU^RbYu+aIug zg~iIF@CY@tT&Ta{(??Seq(Gr!ysY<%*Id(x`%ozR7gYRmU^#SUKMydZN_(3)ex@ae z+rbLNNL3#tpNoxTBCb87uiqagdF?~VvO|6xzu54>X1r_YVDfk13(AUTmH{7Z#>eLT zmHW_}{iL+ph5#@c!@@tfwKw^##Ri4Hq$?Z}DUZ<<-p=gx01 zWzuM(QZb2h`i<8>7g~VtD$ln=T)OU!fO+bIr-R6NxOT9bM(TE#cla-aFZueg^;iQu zo}kBGEZ37)?C20M|JmTaAm-mUMoi;iIa8rmOuIGc!mRAM<7!?^9j`tko^@JW>NzUY_z?uY-cJP0#?|w;kPq#&7$YZ!<3hjcD9D0q z=xsx7xxx1JFeR!lcqRWrcX2;9`lN<@XxCC}T8o@d z4dfy^d}ZTzxInXQ2()7ha-%s4YwQFhb10nFW#{{^o@Ci7Z-mKc1u3VbAzM$D` z6ft^;=^horY&&|K88o4o4h^oAs9dmbMQ0rnGMP*E+uS3Oy?2YqGZ!oCO?HxXlm7}I69nQ7`0#tQ{S zrFkdFx+g^(w|fZT?K}_F6yc!mb69vyfvsOz2WBpX5OAU^6d8MxqnDK6%Fk=$uIo9_ zkdFjKZ1mKvNtgZY8bhuo{Sq{rDdGxkh8P8!!u0&}(ke6M87*1qLabh^QKKd=5*3+2 zOufDlk3P>}TYp9NqO@MHT6veKz|SeC$>?$gAVhL$LfZ1!5*OfNp9JcI40Nm z123lNm57>+%F?yq`~#zNyd2mmV@I)%FwTG`u&}%KFKmj^V%=v**hb$iEdP4yi%X|H zVqR>^W&WaPV91;zdN;ivS5&1&XC%54i!g6U-f<2m`pJMu0kBfF}sl_rqX0qMJEMfW4^cP376EWspQW?i1 z#nK};3g~EaLOq;=B=Ojyg|ArQH5;d4N&my}n$5fiWxyq(#sJwFSh2@pTh2N6TY8Zq`Ah0=(T1+?(XJvu4oJdyMWBffc6pcDHF z>`ER87{1s~D<~7ofAM(rF%#C9od=Ve2soBt$cCpqf)9sYLr*3VV~wQXeeJSPESq-che&HGbswJ`<{pNrQ+FhtBCPO%)c@x>0k|WX@*ih4UxOko`0NR zfOQYx`>^Ny#i);*L^%5z3o*UK(bV9Ei7zPI=GTjD7-7N=UZ}<@Das+FTQaozoP}&t zFEDc#V{`OGOfX_59`KiLNOMmayd{s;jZ)=8@M3ZJn0n$`TZ5HdZ^6SaNziO~<51x^W zCzp0CGJ%noZAp)1>BRAPjquQTpABDAxcci4!3Jk}xJpnt=FhB!{g|op%xFElESdyb zF8{!9v+ZDlS4c-rhGIO#slhg}Ee?tuDo>Z3?n+=gq*sUvnIpim0tG_~b$sJ)dOU19}bHunC#9EOb z2bpo5Pid$|m{k4JHPYVvlpGw69veL3S|s{ovL$Xc8ZZN5cmO!1h!{yxDQGRsfPsb` zH06D7`Jwab^7MBVRDb(-7-=RdP}9ZF+FQh2Gw`*#Rept0J^GYR9&5qvvCbvjn-tft_K4@X*d$bO38x0k+4J>EEp%=r8YV>U%$clH?|Q zRmJPo9wMd=F|@O6ivQP#Oo_o$>bFpxmT8_R2Qf^}cfc#bc0GB_Fv!E|hZg6xLTt{w zw`ht*X-KE854#Vu9;R4Kpy#XIY3sQ8)OSH1H;86Jr2k&wp{0nQwPwT&iOfj399_Wl zdy-9ej?$uGRVn1t4iA!ir3`qj)2L4qNk2lcJES%Wo?|wJQqZv^oy|aTz=ZC_;ycRLqh;j7!B$YnM zW2}c~)2|&>+$Ebv?ngr}!l#V*F02AJ4-@(uh6)N)e+?zzT|>MRvSE~j9k;0~drn6Q zcB_Vw#9lW^7t>C1W!ybTY1}1XhKLvg#4NJ^BUL;U#+0aM)3qM=W$Qe(X=u<3iRBH9 znM8ruEl~+xJhXtd+ti`5URS_aCt{XB{3JGe+kZYA)NIDg^<%$E?y;ZC@t{94O28C| zi_H+k%oy1rZOUE6n73uolMgt_;-AJ;o7_&xiOYi2gEhD<9|gAl*kbODIn0qS5-?8d zpTN7W=B)3pZ*X_R19rzi2R7WM7poDB*F^F8aQLSv4Q&;B;f+Sj?xT&;A%^u<7fQ2e zq}y?_=I~THQ|X1ot`E8&(9WY{JL@qis631IZGJ5AB3``A(JHqGB4-y-5LeK#eh;LyX0hTU~ z9-Ra~>wB|i<*y-szB`*gus_R69boi)57>p)`NxmMhvp<^rp!Ui-AyUdZC003P6TFC zhptMXzOf@YC7I#)(#0yRCc)i3F%46D{j-HiuhtIi>k;(;2G#aqKUTbhnma12EE>b+ z&dq})JAXK3`wOO4wF?hzorqbAn3b7xrC)ySPD$soY3)c~m|xc<*^t+pi!n_TYzgu4 z8A5Foui5Yy`5J5SQW$Tc){atSrEzJ{f(6Tlm@lA_+lPG_Zp04G(_p)qs|fqFv*JTr zis##_@RSzx^@D3weIRSMGZ)e-x*t5SCVIo6chH`YE9e5L-&zE7l6$@; zyP*0FWLLd`Sxd6*rW?~j(3modz zh1HIc!j(p`C54^Xs&Y4C;=enkSj-&9RL#wyKb(JX_cm!m@2QHER|k1>lF}4R>T|@# zCury4F;(aPfPH!rfQB}E(e(o)y~WwsaRFr5x#V1c4qI~Q0xa$nw;Z-&+8_Z z*%PAnyn^n%qF_NM+O9DJFTs5W{Pp-pcxX-{#v3t1|0blAN_?36GjnNU<3QQa9nQq^ zRvO2flPu?oK{LE&&#geaJ_bi$F(SGlJb z+yu=gUwmkRh}pf-Jtg(sW#+a#mwsEbkhCo{A@73jb7pqgVEpMPR0Wj@T}d{SV>f10 z2S<&<);m!gI1OG;r-g;lOX1gHN58f3ZfQQ8u}0VG%tv@D6-N0J!C|p;c_?CvCiJx2 zp?I6=?43uCU8*6Qb@mXWq3bv^_YC2;;VZoyZ?u6{=4;T~Q!Z3U@&a*&MLBJaSCKzh z;|wFRM?jtseymMw%qqc_pXQ zlq6iN*dIoRH)=L<-`@%tzMu5!em6ntuPA?Ww4eO+vneoh)*q7C{2NUA>$47r`pan# zu>@<9h`EQD@Xvh) z6Oia#4^49Pz#Pu!35WKen84C;q^vx!F8)H>k2fVnHK(CLU#-s8>e$_iz6mFLmtZ4Q!dCa1Wgu6D9b zf#b0*V3&{#tK{)lXtt%-S`1swT;TZzHL#jvMDOf5L7BkIptBQud+lh10pE1kiI*qS z)hCmLnN}k%HU)@T8yLtOJ9vz7%+I60$D5L~hi-EB?(CB2E47dhY9j=7koVbW?EV08 zsn6i~l%Y^JDvq3&7D_%=*UFBEo&!rl;MT1sc(berJ8=1A*_nM(L9XPbArVM()1q@aZf@X9LR3O#06ksuym*&;LUbAP=Xrl$*foI6#zlzX2 zI*dH8_k*Hs=J4L(3;g`ngWa?%j#woB5Hy=5;zzm)F@16$Fd==)tavEZ}eOR)H2zXi+H;htjv>5-}chi-+FqHCAHMteN;%xQ+HOSRaA zr=rNLYaIgSzY{?tVq#O18K%?U(#|lCRz7_oNzvA$j;`CueyxN2Sb~*k z-v9$97YemeJ3a4_z6qVgeQyNW(|QMvK9~m^?l!|^BMsJiXCzskBIb2AiwBQZ#CY1t znTc~Rr%ZpDOHHZ@$Vt|ihTYyunr8k5+wZDiVVNt~d0eeOqZCm9Tc7q9tXBLDlydh# zHg-=U+*V%*+w*>5KS?}?;=l8M`3e1B+?2vu+zyV&XL=e>l!mzF(q8?}NZs%Cq9I#? zh6zjlI-y zg0=Pb6EF_qd!vCE9j#pE$pbHGt4S_h=rD@2l_=49^R|!(orAEr{)n*U;Ds*U&eQIS zm&Uo5pbDFA4(!|j=ljlvHV!+PMJj(8C})dlXr)XvwD~NM^OzQ@ZT% zBPfbr1f>SpToXHK`?RTn|9%zVA6kdF*bG3-edj7B@y0vpX5$=60`jp-Tm!e%wg>Q^ zHM^@)Xuraz9ADk3FSx-#by`6P=Ryuxw(v@EL@!$N`I$$?)D?NeF1- zbJZ;tl)}W*=`bz)IE>l49jbaOu*zn>kU#b>z_bsr9_=Mr&M$<~Xo?sM#FRKYFt_@D zl1@^8N?#sJrjz#Ql9h!~#G?CKaGLW{NPyu-eI9_rJtel@N5tg3d?7@$Jbr!$4jk`oUYuB*CWUeZpvh z#ouN+VkTORmF8)BOOMrM(LmG9bZPE7m|oK#a`s`(?UPDDv*9zk{tv?kY4Yhjr62H0 zXy7n*TmiO1tWSe2!MW&=^nz`&GhljXhk!XMViq9As>)CL!OTb+C&|JXkF~NfUVs^P zKZsL;D5mh5%@aQ{ql;Gu`EcM0tV`=_)`xW{7{msd{DDcjH^IN;Ej)Q}0W9h-V5hP{ z0>)3=3pgTX#I6g{Qpa5>Tb^dp&GRn8(S`-Yb45I{8;D{G`UTpt^!m;~RiSjz@kbV1 zoQI#cq(VqE!Bp~nDC zhfL}f{EQ4W%_plYQUwhE+c@Ht5HAh!6_N%|akqog5bsQ>mdoInCPq({o@Cr=ojL2E zDCv3oU6ON;zQQt$Y~kOVTOwvVKN`v6l=&qsmhlxCG_cGO6qElU*_(pI(eyyE3pJZJ z@6_3LDfaXjn<3bF_yc>doMt6=Rox^qHDl0qa z$be4pJ}w@kZi<*wh;h6YZZ&L(F%y}WPM^)HkwnD$ll<{XBn10+=!DeawfA{2xcUqP?EbYF_8aN*OZrg*3tP5Dr{}Jzc8BhBIY7uy2=k& zwccIBoSBD9!PPISY3|nEptN)cYiulQxg)!}gi0!bU#XPJgIfqF3J?plUmN z(zU*?Vfu{)!f2XAOblYi?*5cg^dpoxekF}Qx-f*^(!ELUr!6PGc;CrSXudsF>~uRg zf8Gpso^2z1auVM_&}Q36_M)B+>o&NOX*GW?%l3LAt0vJBMNS607HS9>fALWG5Haz; z-KD|r?lPtu(&)aO2dQuG0ZfkJWa2?eAUvT8!X6Zn2u(9sd0GMFNu|V5yHO}zEK;>( z|CIG%*G0CHNhj}+KBsS!S^a*I{!`;&Pv1ge%W+D?aEQ^V&5=GG9nEaFOQS!uHqlS+ z6S&%8SB2Ur#|Kq{X2W;EGTl@|iZ)jezMw3osQ}E~B<$Jw{n%rJJ4iqEX!1sKoBaCy zlZ=nM4OPCD^Feypzo7h#+HvdD%f^djMMcN zKLj<1+4!SfdOo)(3G~yb-1j>%Rh>#V^*SQq>u)MnHGqYW2dLJCLTva^w8jStnB*BL z(1-yuy~9gD!>kuOZOnem!qtL}*42{7|Fpus2vM_oaYFxd;4yb8_XwvDS0fw>UHW_z_5u?x z7C^XNqTq+-!?QBm6QRqu0qlzRbHT4>!aQfl46W z-y~#9EoRS_zI~lWE0*ZNjf;k4o~no7esJ84#bdZxGA_axus^8C;(?uy)2-?G0E(UU z*)q*qSaMQ%U=4oKSoBDKP4F+Q> znSVPpOuh~8t-G?SQ+lz@Z_6P#_nI)8WqMc*&O$!p?gZM--d7BPx5WhtviEN0%u zWzx~z&vG&=7cw>}LC|a};(iGwSbUe?)~a$LhWhb93}|>MgNu6cWLK(##0=w)6@1RY z7cDYmPw75d*;{t;`Vcnm+GT`XgOS=vc$*uL_d>gjNsHj_*Leu0Vj;XXXR zpM1hXG3xlg?cgTFEIhBzoLcgL$$XJT>;BdfgO}ctYu8mcdp9hF$2;kR?_Uc=OMGn< zZ%%S?z~yq#8Mrm3onF48FIPG21bas4gZ=jwh`}yc8$a}vN0&AUqcIoPG*`s99GT6W ze|(ooQqHDtHZ34_=6u0i-zn6j<7ABQdR3# z8kpk)ZEb_$Dwfa{eb8l%X1=21(;@{-r?}-fjF<-(cQ8l)y}|SvnoUoP*+R084dnv= zv6t1wSVPDsH>g-rAq36voy&PU&(;qIpsuYK9HKL*O;QL|I(ZJ_R*eC;+yHG$^jNFU z>*x%>E&}F1F~t)x89v9E#>@VUFJiL0^(3*5TezmOLz0!@PEi7v55mp72o8xmS~OM9rqgdJH&i{{&lR=(6nR{j%;yt_YgVA@L&}fEeGvGtAYO z>zP4+v#7&SLR{|L;;MeB3kH~$vE2j_a>X+&S_(nUWb}MXj@662Hf_T>7!4BuP_7 zOeePzCwLC~<|(ok?R7Bks%Ym~e&`(WUabf|+pm*X7-rI0X##ynJ!l=)VV%Fkkckq} z&XXpJDG`VXS{%VF?UiD+%_)nHscV+bPsNNUtJi1f*VE|w`dAzfeyiblG!`De+uk{>| zp8o)ceKh~K)8SWvu_7i3FKreWW+0X42aWy2*M5f8_?odJ)@*jj-5%yO5|n!9YoH4XG~4K|36FGd+3| zMg-wCQivC9pYjC;|5*ywOFqHgO{#3@yQ{DT_i;R?ulRcAA!cPq7-KopQL0guK}Q*Y z%u*|l>qJ{Z>WLfRGCT}Y@gA+=ff8#r>6_3!&Lb=hibp1mq`H0Zo0p3^(I)pN8U9t+9L)UnbV zF$bn&D%_dx5VPnhXm~#dz65Le!AH{fyAMbtCa2)utYJ`B)s^iSr^7}~AIYX2v1j?w zJQUxXO2iyHlgc!1yDl9boKBr@TGJOfO2pGQm9(QTE%h6w^P+2rmmi8v@ZJUw?0lkf zl`IX0x9x{Q%gqp2@(B(va)f9vC3ZtZ7dB7&36A%v5+2$)5mS$ti~h5jX|ik5r^C~! z(wSuH(mqr+X3{a?wB~5=66-sXgwceI_%8Ttcrk^K)5X2BTp))DNMj*ikKF}9CeFJjy~ogeJ)R? z_}_+)q2~K|@M6k5Uv)OuR)>{T^=Z3zrFCy+yvU)(JQzStLsrrd8Vzx@}2#7j7It!A%@zxcqkip*^E8? z&o@Xra0}z7--6G-6h>Tig}d8b1x%2**r=aF+0M*Q>hbaB<3Ap$v{o&QyLsaWSr=I^ zq>S(dWo8Y@uuHSc|1g=2?}TnX`{E4PBr^lnA>aq>T@wUaXu^1{C6kaA2B}LtfY2Qbw>Z}6DrZygy>Jt zNq@s60mJ_`skdZ82^No;xFbyvQ}{BU)#KiR`ot{o-@AkuCu+zxEImp74V03;5zj$A zHATQUiK7{c80*|SDPICjm|DXpv|_P7D5v+piq%U*V_lVC=dtWg1v?LqY2Td+#z8f} z>jK#-+0grAG;El$lKL#WM7PXxpuPW?(1t_Rp!7@3>kJfEXmiAb4D?Mtyv&SQk|n1F zTV9j>vV2RkL+F0Us1o|(dK{8Mg1Nd-R%&^lLSkT@5HxeQDFKEyT!WS0%jrH{Rr#tX zmDJ*ml*ZWqfcN+A3ZqF8F_wrKuyKf0ZMZ#C?jxseD?-SrzKe+7LJtAMpFR2ZyR)(2 zg*U^lHh2hC7?M>}Q3Au_6TxBiO|ajfDi7*8Nba{vTdoy}>3yf#zz4+O=1TFQ*&=4I z$6BlCs~eaO6FGg_-AH1v?YpF#>Mdfq{XK;Iiv?u|E(^_1DhB34)v_x>30AY_bJ&5m zQnJQ-u(?oGzVQ42`L1Yf`Mv>PX~ncZuwak)dOi|IGY>IQFSlDwT5*E$zD?=mWChua zS0QBWnphIE_bpaOegxeK$6&z4$1rht6y`u47V@F_5FoWKKcVN)0w@{umU_)smcLJG zpzq!%QrY`v*t+9C_k)O8j+m_{vMonzpJ%LWC_UKUo*UXag)B+)As&qtz+0{E`P)FI z{~7RgcLQ}xOR%3W`fTDNwAq@&pP}vcX&Rw;hX$Ptq)Im=)Zyzp(8%x-ew%LMXU&Pn z_#aORjl97`{Nm^u-@Y`j-G+27+CW@$$^<)4rEPZ@(r+=m$esvAW?jH{R-<5m`F&#$ zd(am*ak?av?Pf^pDOIFpEXY$X3M6zc*ewV@x8`C4r;M56q(# z8?q!%^A{2qtPzM`UIj(IuZj9GGq^Xc3&{0elY%{;g%YgAr^d0TC-z{Ce+5hW|1(L} zt38%De`+Hk&+fw@KLY_XK*a1t%)5ivrDy9NFh9?8)Ua&>4KC`zg}*NlG#l&rRZt0q zLTwb^>s!0^1>x^K`I^EVL6g|3^*U^TS1ZwoxI@;2-XT^Yt;FF~6x?c^B49eihvtTu z6W{Zte@&v9wH_Qj^ZOh3{q{2MRHmn(+3-0~|BtFO@u%YZ<3B>#B1?;+(!NRBnS0*T zuDw)}N~K-9cI}c%5t1ZHl3iry&Yg2f3zd+B5F%@~vR8g*Wnu7BJ2Pv%I2)F$}y)Ej`HMs#`JaMxQQrV&Ao*n1D<$c|oSY#lOg`$dJ$UN)J*6 z4x_yAEwm`jq=QGw(%=1iQKEAoI&#mQ-_^|9_nvsJ`|_B>0>+bI+|SoA2O7pxwcA+y zVY!d!WSJKBeL8}g|6FLnY96fvfqUjdLxnCWl}_U^Y2#i(Y=jXVwx8$;NNGqT@G-r9 z*Ft*s;?wk-kNI$7zwohf73uaurV>p`b9{dR!6=%>{Mj_De<32bwT^-Kc_yszn3;EGJ6EGnJ zGwoP5Gxr89HYKCc@Y#&S&!*zW*y|Eb&ZBAB01l+okSQhgo0+~O9x)b>Z4;aMLs7#WQCmqTq~u5Nn0#Ra6+?iG6; zY2h0OT-o_muXwj>P7ggx=M&iI$MYMg|10O=>uA@BQQ)~V^!nC`^sSL7^{!F4Ku7CQJV25d5m#sGx(5F17~&I`sxjT_Kf-1 z3|w@W%i2M-gh;NxSsbG0JQzf)UyMcvr8B_mVGS^4tvu#{aO3fsVD#G0Gk>lbGYbLZ z)OAkaHr#>@i`mO`6Y;omehWC)r3<}L$BEzI@qFIWXg=u#H&^O`9V9W^hbe{|t;L}J zqYaYiesp7u7TqkP&F|9|3z%$z*)N$Y9yehSbH)>6QxaF8b969-M9yS0N2i0mGO5{+ zRFZ#7N+B$tMDBda2Lq#4s2CXq^Y8Yd)rWoo>1zh`3S6MKVHiEeel$&`_dr{okX-&t zsB#n$%-qaAri|GEadR!kZubu`trJs`ycE+md(0V?h}t^!v!mdF1rldAI9N z+4PL>ZW4PX=;*5-!7r4rMY~~CT(m7aa4Ry7VB#GH#(26 z*|d)T$1A$DKFiYO=9ysVUkqD`0$lM;2Auxd2`@HA!Z7LuKN@!d(@8MzyrRWnjxS7) zo=L?Qn_i&<{f$uBGY7tAWB#IxbP{KSy=ue%YBrpAH|J`lBUOX$G568_{z))m`dt_) zn*-I8WNG)ni^zZ3DgHz-MyT1yc@kMi&^d9?bv3HFG8J#$YcCr5`5qb~e!|vq|4B(V z*j0Q2dm=pIYBrnzrm9+wHY9tu(0+>ez&k6vSw9lAR^9}a74Komqjq>Rh2m865(7m<{IE>AT4&Db!#k~ig*)mW%ed=PcA7Tj7 z4=qp-p-Kl28Z50_A}8fWvp{%nMi5MUlnzz5dKdNSRT}=`O+wJFzY!^o?$2iK3J1-9 zpTNL@i2Uz#Lr}QjXTx2uD*Kb;7)!t zmj%p3f|(Udq83dDmc@L#@b{>^Q zs_F~Zk3qJLT5M9zJIRexYaq<|CSOnUa{0q=2j{b&Am;jYV73g0>@~;npefIBORPH_ zQ?!P8Purk%Uw^u-{05dEV8mno314VLFhlF@sg@&yD4TIFiFsBlYPsgg8inRim5bCM z@W*1ln8K-s3<@eC%Q6=<; zr$wkhnGwtYKW8d_cBZM4%1fMeeGD3PCy~vxP7`rWOO=tDB!c2I>Bs#Ce*b>(rJ>tq zgP_2`9qsm3MR(VnkdW{l*!jZSw=@>VmmU?#g!lz0nm;Yvu$qt;3JXKdo;n zUyz31$*&fj9#X~HQMyQ@fh7Bgx{>o6b;=bM2fQlW(&b|{0XCeERz>^+)KmDimfFI!E#vi`Y4jQ z_W_y72(~#h4P@x&^hxlIxhW-#vKSk1HL{7CEeq&%cTl_PVY2_NDe|V--(O$$p?H37S|rPjC@Qucb+{TQlMyB zILJr(qqg^e9>iur_&j^4ZTJn^K?jtm!N9$qNy6*tN-(Q(o0h+P-^{5BX$rk>c~+6M4+ow%@So6Uc~&`kFmvdF+Qg{ z7zUfVql&LJyk#pFBg&12({d<|C7oWzU!gAY4g7lN2J5etz|XY)^qJv_aN}$XSiZy1 zFeD7VKfJ{MH?%OJ69~pAPK$ZI(wC{KB711v>sZNYGOSWk0L~fK#JCJ}O%iww6o)aK zLJD0Zo{DS1YG1BPXWNdT=j+MRljgsM+fQ;~>Zd291NjDcC+^@eXNA#731;scC#Jps z0%qP!7PD%Ktlq#{RCN0@pC`>#Ih-ZL^3c5xKN=2WOZ;rO7A)Q3!E~hAVESfT4}@sN zK~dj4*p~1ZHpRNZZdRz-tPrY$nFRB?j|X#wjTiepmSBr5-l8<^Dm35u0rD~W&b#w) zy-}Py4_6(`o%EWo*<=|JKbxoR&=}PO`BqI3lH&(2L%+dsokU>Yh{5TDaFSLKMw3S{ z3ogxL!hVer+s&8YR1JWj={*Q0M;~o!wQ1HWbUl?YIoEJS`Fa8v#>FFpgm%;>d3AxdrbTJfd+igyou`{hlw7 zhYJbXB&Rj52>D_VDW;IoaPB-@Zxp8*`YmFil=SSh86?kQa7F9sk~%_ zGj85T9?XHoKJe?(YdoyH4PRdU5ns2D#=q{hkob4uv{ojRA6g0KBYV}fS=rz8?|3g7Ox@(&(sg_WVOI$47XX&K1j2m(#@f(WGq3+RYJFo_dU|?pBbt#Tw%K z@EB~8s`{O)|%6?lQ4X{!JA-w@1<{)5E2!(6CgPAS;p?l^q>@&n}Ia0vyZf8k3*XN#iJ7}ycA!kY>@cp3%HKoPKcuo^v8nT#S zM9`n491Nyp(yhWO<2un~}?--M2i&*N=#IOFE`HKz0nbq#uIQ3pD(HUf26hax?q zxyjz+2Uk~4;4vXWL)jdHVJwoEuc_hG(tauU&@c(R-g}$mfvU4e)9M3{8IhdFTOF@) z{mDm)zn}KpjkTkIexy3$%lgdYVOr3z4PcXmwePYIB zx>3=;ld+A_1@`Q?@2tVaV zD_I7vCIz4uGXl~6b-f5*V&Lk8hdf4B=v!MsFwOCKjCSA#YE@M-9_+geDKz%Oa=qpv z?ij`O6dH|IhV@o+VZ|(M7`@Pd$IQp+pp-tDZjP+sYc|hc#?Tv757E?@2Xs(9`QGIT z+QI)eP!62BMueK723zQ9-9Mr3t1nDea0A8aAr(H&Ot1Qs<7hmCW&rNw)Z}kf} z)lf#aF8#hYA6{En(O=(p0}h%6m*b8=yGtc_wg?YxgRrx?NH7;p9c4PU+!J4nPr=*C z-OHW$g(&RIcZRcOQ6AV#DjToBl{AifIArp^95!2iLH^-bSVHd6a`wD|;IAdn&)^L# z`a`N74|V9YC$e--iYC8-3J{J_HwY#{PfOfxIzwz$mV)I^#uGh8FWM{b#OiKKN8Zk;$N zY0{&cs4|$*tUwoyO#t(`edyYW+O+-{21<_#>&;RD<4Z6P*Xff7_Q`Z>sTf~URK~Kd z+Q@%)AwL?Gy(PM6B2MCZJPv2~zz?@X_#CQDyY&AIPyP&`hmQLQ(=Ham)VXqW z`i%%k>kvw+BLz$l!9@Qc#gyO?)TfIK4lT#0IM~^&L&Bi0?`ChvbacG zra6@omos=e{Sj?m-5+h9;mq6SaE{8EaXCUf)mozFA|eYe2(2|n4BdA(f^4A%%wHJ; zw?5y7UHSR2-dl;jGqDs^8Wruc%6-IVkg*4Er86y#QW*pSH95o zqKaThJG|QdM|gwZM?A*Y3FhW3hM}58FuO;U4!m25A5_2MF@FV27Qt9fE;3Ddc$|uB zmSCUpM2V_xB)Tp;o}X!4ha^|!;Nq!#?ht)#3`xS0`@^UF7UehLS0e{VAMRfU^0lOs z_+KpqOSI`FBxPagtzI6pS-=z!OvsselxNE&%4`yg&D(mBjPYjCOvw&qYGi# zGNPfK+5?&iW#Dl3GrzgD9q|B6x@4tFCx%IXpIQg8dQ)IhRx?B$(V_nh86tf#@*j^` zF3hwFfXx%(HPz)k%!P5 zCMs9)y-}(^mqYZBQsl8{mgrlk5&JCfDHKgV2$x=z!j9W&G}%u{T&whXolTT58W}IL zNUPtVCJw!CntYzcCfkRh*|)`P^to8k9Q*|>Y#PkxuyZw=7@KO~jLo9k^gzlyKpT3R zMR6b8BrC-C;Lql55L#XZc`w!I&^T8{l)dH6u*Q~7qHD)eo!SfI}=@NwC`~x_yW&zsEYe3_* z3a#Jp9GwS2&a+!s*0c#`XH_V5T=AM%OM}G^qJ~mq52<2@Cnr(AP4Ce7q9)`+vZK>B z{DrK9deBt-2nEr~ya`bDvksJbEduS0eg|u-W8n19FR+cAQ6IWTq233-_^-e;;Y6TM zFuR=nsSlA;nS*%}{9~7oBqM1$e(ExskEa?>Hb-@~nV|gZFW3)kOcLlOVJ$yN5ya@pkkqAc1~0?-A|2uMnJVLtx0QkI;Et zxSirIUAT`;sPK9k6HH{^>r~l*H0GI=1fO(?Vs(ntan1B=XuCPhTOD&j0UU<&Am)P5 zM&CIJEBRAmHs2m^N4z8b%f( zNpUyioQ#99$Fg9`xN>kGPlD3=3uQYCVUb=;FdZunQptPzO8lD{eBTn#aieZ_lcp~+ zc1k9HeF7h|V{)FvB9Ckb(iRLqE|KqA@+(L=9WQ2jEEy$-(0aq-+2;4UQHypDjxatG9I8%*y> z{0cSj5lR(a!ik(_I7Sq!+!U}EFuMrmlJ2g#4Uc6d(}ps5_VGx(Yey@&PJJQL%_mL& zLo4~*C=RpuRvStEeFe(`3&DrXK4#x5$bHleSJ!INiG#~v?T>G8LgpnbofQpJo(lq) zRYKYBFu@e<8^bJdVws24Vrb(NA47kw97j*Hn?g73>4BIh&%uxQb?Lux zfk9V<(P#=72ZFJ=70I05Ys~bF6640*@7TM;3y|e=v53oImz(nqOtvLL{3dxGbLwF_ zJSW;3&SJv+fG%CxZxCI2ONo}MlgyRgP#C4_1-{Z-u-xM^|KEJ;;f2b#3FbrY6DCMe zmRX=6#!=%(!|uWNQC;17WbmMzcyN)1G9tBdxk*9*h&vDGXJe)Loxfp!GhdD#-@g|m zgNgbsSR1kijsmZ86IiJc3uCSe$EbAz#*1K%7Hwwq<2=OcN>cE?+Hq*?7&9j6lNFEQ zF7mnDC@#~BGj2}#m`0+It4N;L2Y{wx2)~jG(Kp3x`{Czy(zKg9$3nTYqtreKwh-RP{+b)+_VnrQx1qO&2^EL@@Mo=;!?p>dgBHZRG# z)BXY4(mp^RDF%;-P|S`lz@c+7p0D;0Ps_}KK5J5WjEis^6-F=?tIfnx=lYb{aVfZA z=};J6>w@;}TEK9{6l1MwsMCny%Xa4KjbMK`iEs1qx}611vT@)xSqzEe+A;N2M;f<5 zSy~=hg$>$kV7hrakLeLGaRl=x{e#JZ8TU+<1f}5fkqk;+Nuf-;9ubF;n^gmKzn+j} z`9`o)B362yg4HpHVM8OJ%{mxXE$Jtfoi|dtw4aXjy;}!96D&uU7v}PqFyS_eC7AG5 zsp*K&t)_2wq~MQFyO5{hGvr(3f^tpDfU7`NJh%ym2fPD&yJSd+yTQwOlwZDw;x;j` zb&;@Crwy;O(vU9Q)kpgA>_g$WMWO`}IJ($3_(;M{ zqv1H!vMU*t$UYrv3;Q`e)C>h`Vrj7S@grm#1 zw;=OVxqJ}X_UiX28js;?HZ>n}5LbcXB#QU_$I{;?DbSBzcA&p|BT)FRaP%an6D^67 zg7oGU9y49|*fbN&k|9Ono3md~+sc!$ky|yJ_vH~f_RJLdkZ$i3=L$Y-E9uE-knyiV zoYgTWfZ;GLt0vGR;}vMnjK4_HCJ3D}4nqN?qhfkC(R?nl=P?(B*Rz{ori~oV%o0nf z&ySLD&tV_-@J?OHyk}QXOvXFjHixU(aPd@cFL$Etv-*Hj-)6AM%Yd?}Q|Z!3SsIFD z$+fCKI-ehiPA}_4EqU+2CP47z2o^>of1l)go}S0-)nX_u%Ow2w&@S-?=R3^d!DOa| zlB@5l70}$#4{poPg`~eq;Hfg053kQ0^ai4`Cee)#NmDb~#dzC?(AVrd_*`yQu*2aumOCn`IJP8-mGf=Lg5qrXU2{IW%dZS3$&TQBM$V;~aDZ2{f z8*PD8rf_1|syh?uu`4U!?AFt?>!AVk-;p07EJ~ezda(j@4+}b*&UPL%m|)D@M>ENe zfmC5uBL19x+u=Wc~o^4o86X22WD$2;*xu-Fs7E_UjRJ{oHhD zv@j;dfjOdjhY2u#zY;3>@C!C=5Z;^S4jyAbFxyqNnWx%5RK&wX>=^zQ54`rA(Y5(a zapu6e#2+oJB^_Rm$N_XC4(gtN;Nz*x$=)qs^c4DuZ8a31x`(86&Vtnj zt`qz>aHBaqa30#Ti=jInH;dw z?BtDR1}2!$dX;7H>$w`8wfrpVEB}l0|)Jg;}J_*yICv?^UAv9Po#PpdcO- z|BJ`$BbeRuJjL(Ko>4m6lCZ^4;T`VtC+=>oCJ%Ijq_C8GdMK(Epa@;=Z|pWCVnn=0q?j zNR009yCKv=IvFb``=d)o_EBdaUSgNMPX$iVWq-Ap*V)KxVV+Xy?d77 zrS)o3yX%)Bdx;r59QdAi-Kx^r+cl+U760<1@e(j@1d}{}0_EIGnq#gdB*M`{Ag+gOd!F?oSI1~ z)f}dnIVm_QRh7-S`X@`!|}hm`qWzM^kWn;swUp!;SU$Y{Gg6 zjDv-LckuC4TynVyRmD$esmW$2xI*moMz^zh(>LLyEfKKhuQN2eX227oYI*-V@BSQ^%-dL4_viwdAJo>=1NUSIh?794_JFscs}U zAkH?23rJ6M6lykQI~94=P@zpXN_`uKOzz)@h5OFIsoo;!NHx2{uz^}a3ao2>0^ue*u!LalOjO_Xb zBee(oe=S(D!b7Vgn54d5)W<3>aVslj`*e&GHLsZn>x*ZAhiV4A86!it zQqAyOI}_F)-wpc|5iHI)PRH*vqDS0)39sF5!~GNGaEOS?53Mz%KV@0b+)PUs7U|yv zvuVLy>Ok5NhEf&d(zZ3s%*-G*a8)ana@Gm#+-~rW%A9i&cf-!*M%lFogQnYk7^gG` zCU%X0VDp!--@^$?hn54SqE4?&od}&a^MS*J3-8T8f*G{cox1kiof*`cf)85Cqr|kAuc!SwQV+V$rpTGz|~hm?RyBfI-TIQO)32AqfS5C zsS4L#3#FkK!f5(=lO)-UNGi7`mT7sCf@2RQp%aVuvD=T{N6KH{0v9RXdW7XowK)S? zP5{H@Mrrny!r`t-u-Hl$4v-2*@*v{QGw>hW3(%t9ubDzGtrL>VHwzd|g4w<56qPth z!kk~5f_E&B#*=@&lDyycR#ZfK3DcsoNFS~k4r%wHxe63#r^_`hIn}>{Cw&vZ;E_AX zT^>yz%=U+C;bCy;eg*`7mO}V5!GN|)zzic8PsahKXa1!#JB(BC-GrNX^og&c*f&~y zmBZ>m33NY=hr)ewyw5FH<#;~57)sB*0lLcv+_PfH44Xl_7v#hJeUD)(L_>3c3!Ggp zY&pyX%vgfSubaknUGZVGo0IX4RW|smg(?hqAHjR3aF`Uuc-}V0T+#-vy+j+`Nm_qN zr&n$A5ZX6jBwduKN57Jk!Q;7)p!eBRxMz1Avi>>pQ(&&JRW~A->-#+!{|)n*=f{$< z{y@B;h}3L|DKnRX<(x!%phz+0R1z@(Byt`MBk0b~F?9D%dAiT; z6!1k+Ak`$dgS!a{dt7b6OAd-G2vGlB@DBmE}<1?gg&u!ljp+u-+^r zn0bpGn3@wMDch2h@Xq!w7!-aF9iMUv)wz)JLr)1m1ws`Sd2`^P;#A1$UkRL}@?BsUuLOZI@4jRTneNCk4V=O3D^Fq%~a6HutYxUZRJs%@2ozp^9Xb1{wT zhyXdjoj51H{>FQE_go;>-^7DBpi&C$Syg;AvPvFHT>N99GjbK1;Mv5!LZ?~B;#4Ny zl`Q5@^LWfG0b@xpJLIQ}kM49a9nzbKvo^j#rCNK@fOC&{*Iq8RI&A^V>ufkVkKrW@ z_Ty^!py&I}F(5U62Ek{1@$kPHc%MT6ev^F`*N4`EhG{mBc_+*?8-m#sl4tVn-CNTr zaw2&3-WMe_$D{PZm zDXo{vO5L;ba8+3mT$W4ZF;j$(%|U{BLfJrGMm3lZ# zE-BZ_e1-bMFTq@+7fa}Y(&cB!7wByv_8RgV%Cy8h=DjeQ%LFrBBgJ%2mIGyJnSdKy z(%cR4a3H4<1q=eVhftQYmJIv!6O=*u1)kb=A$;`y45?)7qzCQJrp z^~=1~aoM1e;4r9x?GV}tI*6@*f@GcIw)u^+-{H}^VuCqZg#153hWS`4HTylBA*fJCn zU5Vy@6#~+kzjJBdW6Jb{u{}suAr$3VMWO1P->CTc6O!<^jmNwciYYM!qd&=)Ng19+ zSvkdFe~Amb@W3UuWz#iO;Z6c+2xi2ddbGW4Jb6eBXhp6ZaG74*$7Y%jMH|z7>D^a) z(af+w^tB-Zt#Il<7sM|hI>?E~qzD*>V9xtSGuIsBsEsS*@O!s6qKJfdtmV^n$Z9U9 z6DR}vivoBi&VZvMB8 z9TbtECLDd;nD`8k6f9DQHmPw1^WV=PZNg13UqO_2!~y1FPby?SpG^DC&VaSLEUb#^ zLNnb|;pY(}5xQ6o);`5NCPO$B77>iHmj^R1MV%_liN#Mpx=WUwxxrdoG?Z|90nXLR zey$Ws9djUNbr|TYkaE%7WkC z!e}Z9W>#xB6SIUhebpxpm-;Pcb;dYTJw`sPRmv+q)2rejDFd02s3UXC3t%`!7kBn- z{VA9LP2a*F+*=S!*Pi!)30_{2!l8e=Uo{{hi05 z*sMvC+^yLX18F+gbk>sA9>If{lk;%-Hynl&CtbZXgkGKe5}Xd@!jSaqaIRX0u70XQ z%g*~vL=ZyF##b0kC&5IRREZrG|C-jXjl*LWJHqSbI_RvyGYMyP>@lqlCf!An0Avp~VmM>9?Y0$jxW@DNrX=IaCSeSAA8AN7`0ucyAo``m_T-P`HD# zib`3o@t-RVaTs0S3Rq>4!5?wCur035=ScNnx?A<~&5Cr-f)v<` zg}s1^fEh?ID#4E8u=u@HiCa9L6uXWMHu6R*KFMINZ!Julr1+7K4riOwy6`=JVAr=J z`QHi{m<&DooWU2!9^DSsF@bR5&Nna!Cs|$rH(_^zu(L^N<&U@{2WkuTL#j==$gjr>Ck6)+PCCR%Q^_>bCMO5sETelqcqXwl=D=;+iZtgagIRVT*H zT+N2NSm8RoxNf4|Au@E>%QX0AHU=#i+9Ek-8beA)mw`R?4vu8W(~I8SVHfYd!*Ww# zmhjMK5R6(@j!BunH^u%;z}j^K(Z5}WNY6K&b(STq3B+s2c+6MmHXzcs6<_$c_a|am zI&0HQSi5I84wrj~HwTe;D(mGi^}t6s++T?fSQ&$tEeOOMMqij|h+ul2rkPIt^?>rU zNW?KEy1?4mOIDX$;zz^j(<&B~l6Ltva6Uv*uud03T|1E|go~llun3#<$Vr)2OUTq6 z0b_c~;GBU5t@TVvnt7&;$A|@t8NpoBn@YW;A5e0UiMXTW8}g~OlJwO%z;Z>%3Y%}R zj9eET?%N4mh(l>8!3-tu(tr>+GEZKrcW8+8sN-_*l^qC6YAaz^*+4qHudWmoDoDA} z{8t(>CzwRPos^xwJ5|=2h>eK|cGIeB?8o=(S~Rzm-^~=lv+D0 z3ID3Y61QDm?2FXdtk141Q0MLkxmrY&G+nSa42mKdQgwdt_QV>nq2uxJmU8@ae;_n3 zJ^~IgMKJ!15`C=CE9@NO&0{tQo7+7E6SeUmReFC8_5MH-?&mUr$($L)`fsa}$P6%n zT}Kb`4P_MvNsyLqIp0>A_iiuv)+Lq++M<_g&zXFxYg`j2KmwpmrjEAlK zz|XYR!glZ|!K_a@O<7&9H9c}A2?xBJikeEJSU+~AgeE?9oX>5pv=DMLy1*f<0@_RS zp}3BmluKif-mYh&F)=BU^-J%-Gr2AB&7%^oyjP|B#`lxRQIGkWO_H!3v?rL8+IJ{w z%TCkRr;~8$C0m3XKC;2Jm-rT}e!2e;CmiEae0ZhK|&|C>-k8={WV`++5X-*QZr?pY8)n9fc@$cSupd8h(&3vcV!1iv)d`*=1 zq@;RYUlaU$b; zzj3gvgS4@^a5;J%j3>bk8h5YK@mlNXUH>v*P4ZQcirc`uOPMYoxu2e!bA#son_L;}M^apn9T{(z(mqzT2SnwbXN*soZ z4&z3X>r2)ha!pj$e-pahbQyifbcUYhZIIuhK@VN4Mo(C|k*;;Oq&ZBQ@X#^|=J<&Z z6dvDKQlgcB|D2<7&q_&C|%DitW9 zKb`?-*)j4h3nMjXvRU%^*a-pWe)6r0oNW$gb-c#L84e_QK!V~B+FFzkQrjjt?)?J7 zRSF^Lyin!1C16Sk1_oT5JI0`#xiB{#|2gQ2^|ovTZM9N9p33J&C25IE;W1p$GuI($ z=vxFHYMI1(;u%cn>VT*aCHli^&HGZJq>1D z9>!ty6Z5duVoR`Y8U&hwq##TZV=6=}|4rjC4&CGe?0zw?O!+xMgC3taj2;yJ7p{Eg z8vOF$_y>0=&LV+=RzhiLzJO^Zm>to(nXaMR7}uUyoMfRUvaDPQx`UcfomwrQy68+c zvJzU?(GS3Vl1Pg^X$Fi5hf7ZP!1~@1l8ZeU#H1f$Dt zL)RY)wjvpNLTNgv>kwO=)xw0%7XF*j1Y^ydGwuC7$z)FJ3rzNkIIK*b%DFlf#pKk3 z-NRZiCh`QXZ1?&^6Rc|f#2d}njVgl8OXHwE<{6CmBmwQ%tHe%+f$<}+L5O-NbS^^t zL;LR{-;iK_j=mwze9>y6k^KT66(7NE_47oB3tdHNGfDqC@lxfA_wE4-v`1Gfzevvt zZ3N?L61O{tY^F|R!tMp%!F75RSWi3+kIdxZQ|JjuE>ht!eTALP9D-3|HZrif(q!h_ z7xn!+8Y`|@z+kx9aaZxVM)xN?&Q)O>=`UH_DEkySS}DR_bF1}ULZPz!yMze3o7EoimO1a!;v2)ca_P@e8!IDc&^ zk8u|k=@kTHIhkeZLuQ$}{ds|>=31~94kR!|&N8f~=TB%o)&e$Hvf<0?esmGJb2i^r z49=%I!D(g%+*Zqm*6K7c+r0(rsb0VlZnk)x;ZFQKWhzk9B6*CHut-}FjQ+6K%=eCa zCTAzd;LVPgBs2e>V2zqKvsThZ{zTwo`kpsvG7Rb>d6I=B)3+Nu_L6d|MH2k&2_@05 zMfht?8+Pi~fQeKQf4{H=Ruek}ZXwty>}<9ZOz4L=X7{bzDZ?+sVAs{p(9Sg!yQ|EM zwXBEVJ zWd-E4MvlDGzTJlKW7mkgSbyo5K6=uYYdX>kHGQRp+QCpXQdp$Dg__L?f?4{|j`>oo z&6p*|U=R3#Hh)fHFMo(k;r<)@h7OSXcN21hqO7}VE@<)e#kmO;HafwTh_rlk=r9NELeXRp3+aTrFJ~tVeg5}fA7UQz6{*o z9n8Ns1BAP^8w4X0zMSdj?ZA9|6GL*?7f50%Zm?~8lq6y0)sSh~0bH}+t`j@pcZn&~ z^z`KoXtSI?!kD$$uu&@gDyUS43YuGAg1I;-j!~Z-$aE0Qvsg2HdEx~&VbM|v zS0J8$rw!KFi_vY;?B{L$4SBy}(Z8E*{31R2trnfLj^ujJszI)8V$?B1f_f%YqXy-> zaOcoP{-GTdFhK;fZbKDwFC&S0R1<^mZ0Nv0W!2bKCzeP|E|Pm1V$DMD#7J9a6qsd| zAaCs)6z1|949#D|&Q+u6qQF0pI<65F_DMiS8^xpxuLh}%y8*|D*%tTS)C!nrf;nWN zAXzryGh^^G278xc_QUW>R$JsFHX-L4E`fRbwE|SR*AQy%|3=ZPnh{q_u_ZZQ(>{!& zA8K{Ms_nnfig(ederqCfd(ePxv-ct9R~V1kBFL^&2*%)uy2N>Z2Q&Le41QlTMY6)^ zD=Us4C0aHkAMF490wYo~J@L_$IKisI?LVr#)QW42>D)e^Ug_V;7a=+Em}bB8bd=g7 zdP{Buv^T%uG5dx0CY@j=SZhljh}9((buqXndA|5qy#}^jY%a1_{lp7k3c6>&;hZZl zLS_T}QQOJqtvSmifK|wN+E-c!>@{CHfBPU>-~17j1v~`F{sh>Y@RP@A3Ll#+g88Sf zDG4|>R&pvW25TETqE(MfaAsU9@6p9QG`rlpkUNecv95QC8_Z)UI@Cz6grebbyFNXR z&IhFZ1Vrw!qRdg>(CZdicEA8)1aSHT7nK8Jm7zuEMwP8IrF>OtC}T%Z1WHwTq?-a@t^ zPvDnQERT6FJhTdeY4QBcl-xCuIFg5U-sci|<&03L={lyHI4*EA&CWj*CVnT@1w&H# zo5W`_3b}!E}cMg6Z(&^-n0|U4nse&=1c|2*MBh>4Xc8qLjxgygSEuG zF9|*&c2jAI$uKs)m~Y4C9ALO>A}eyy;$WjrYqyrb?!1?fO|62dB)72kuPNPOAxmrI zj^;5#h1FB$A<=cF{x+S5qM2I;u{gZP2kCc`T=gL#5-xtXXk`;0Nx}6LcF)M>PtqRB zKjGrGNKpSeiZ*j@g$O4i!5%RXY_H9yy*A9FO~aGHZ(sxe->3+C0cC=T%*r#>YZ%82 zHjl-L?|tye(tc2Xc{R(M(JyNRZV#;-S`Hp0v|-t$Jn$jA%CvJa5H)rfy8XKzXBKtppT7;&>X};GLT= z)2<1pHGP7Kd7L1AFTdAxZ)q%kQ(nrhQk@MU32!B7#59Y;a8Be7t4PbdPY&N!dU0VV zaN+guy64i4yJTtApBgk$egf-qUxQq41I#a;1MN4C^ABy1Fq-iMV_Yd!=cS;VRBz+UOCKaSIRGiVH%OBH78ZVb*ym98dtMPIoSsNmlW{Z!3X35h0_ac|42^M zkz1fSDHu*<7o*KPKEsWH{pd%vPLSs&m@;S!qghNa%Qsy%z0~Ip)#ee0U5?y>V;`=d zZKc;GoB^%X_bxEmNbEkQbc0_`5lJK|hQG^+=PfbJ7)LVKwCDGQEP4wpsqzp#ommfC z-e}PglkY*WSh$KuBn_CFoY7jf9JM?J^{;JR}5#v!PaWB;6}Z%i-HIMVhzCyW>49@9jem-RA*A@naq{OehWQBADO}M=0OqL~3O`xr#X5 zpREXU7d6aQq6|o5a!Dw84~A63D|wPlRPr4rDprDMHF32#@EP24oZ!m&C{)rh4SwmZ zMN_&$;mw~im~OQXZqGfIe_zlK1 zkyxr@wQzDuA3Dsa8X7Zxz?45qv;nbnzp?T@M64}D^zAJ$O5PJ)p5_d%TTf8 zcNUL1Ei7wi2^J8(Rk# z*Vn?K%_?+$)mNAytwZT@r%4ouii zykOFhDJM19Boy!e+u3*#%$|w6Oq;im$oGsmoH!{1W&TwYJv%BVvf7i++q5aCG{MJs zMcS5l+E0wDhaq*u5J>MeELz)Fx^(GKX~cjwG{B`zv}tfSsP0XJm;Lmm>aOZiZZvm= z4U|8@q+7L`MovznVq)WPyiq#Jeib8mTVx_CGM0kf-x83!(ZruUIZW8FI>=P4A{kMk zu%<#qy2*36bodnm7~5Y5$@C#fWi~~?WDS*Gy`jWoRE3_xFoK!gF`QbrGKrE)io<%_ zlte!lO=tZ#-Iv6C@`KDpDa2K|0l3^Kt~%IF++RHIi6N%q8W?}5!w0jJq;EZsfqZ5; znlvko$mPml!0&E+M)p6`IRO(#FxTZ~Q)+EbDchVloO@~*+MRTd)lfVynK9xBOe88{ zW33wAQQ2cT@#rG&P3tjYqTPpr7)MWhb{m5aZ}x;?radUiIU5SC>*3LCFRaqOm!ATK zf{g)7Fx@*>QIyUt>PTfA{`6xMnl|JG9M`h55JyDv$QUv_o!^n^sP|u2Ujl-V%&e?=i~a;~r{k za~w7txDbu?aA9RchbXh7#VBru8h?Mo3CHA8YrtnkDU5$K6t;g3M_MNNqL9MHk`-F+ za3xOx4(Zgvt(N~o)tiUa^o9NZ&5{bCNTwu&kg?9$>s~TvD48=Qp--k{4j~~WL#Bi% z&89ThIcM)viG&c5G|;3XLz-mz-h1!od4AWg>+<)@+Gp*x*SgpHe!sP7`v(_!ghrfj zNAN}LUM)b(Y2yItw{wH=>N|<+zjFc8zpx8ud)`+bzbuVtKm0&E-ViGOd1XDl6xO6!BJ0hcoXsoMosHL7qz64DdRp1C+Td_Go=JE3x{2kR`*Mi zjC-HNwVv+AGKU|svo~H<6b(!#wOSHm`ptaShK$vgadvag)1m zSIoHhP8dx>`3vBqDh*D56ha)_>beV__ZQE8C+fioL~mOQe5^Qy9rnP{-GifKhO&ec?)PIIy=|f(^ zw*mbixNC!;>wIDvOBEY5sMo*<>;kI?Qm^s*zq5-DzbH;dy)!2_+ zTk?-}ym?kJ%Ap^ajm0=BY`WyH@N73%3z}QkJ!k=@Iu)XiAEWy77@D=tfVLcq#g@fZ zNY?2{XGllWA&s*rzY0ti`=m9lU@*;IC+WqTu5vmtnLB36u*%&TY~}n?x$XIbP(R_Q zQ10gU0xg}<5b*6&?8%J=|CCF>{JH>7oovDLY9D&v;{muewL$j*YP2*+9b?Ayg%831 zxWwxt#`fM|X}iC_JR31i&Oxk3jxO6((u;BWdK-e!y|Un~0^;I-2$*SIo?t2O8F=|; zLB6{+S*Ci2>A4+acFIz~;*J(APuHVqhB4&AjIiY!_7%Rpy9;WojA_Kd z-qgu{67||egojotzMiItd3dg`bi(FNX3*=J5@US-b+~4;S&6Qw@|>06Fc(9BPMB3pxm-GMfPqijwZ^3T{V3i z$gP@X_4xKX+VEx>Nka1lzfa>^eswOQN+t0DEb26os$3k2cWHxY^ZX8UP{}Wta^^ks zyrh8dN5!3ullb+dh#500Mvi3yo7G*Dxxv~wimQHxAZs5%_zhIT{(PZ(HUHgb2)ZU> z?6M1hZ~3**9Y_nj22$gLhSX5K4QA=8(D`F4Ku@m}TJh`3Pw0MP7oHtr93CH+_uYD1 zl3ts{$=noVY{Mj2J-vwuau6|mJGSv7u@SQ(AJr-7zmZj#Cn|_{no>v0j&!v4OJHtm z((9wJ-$0dx&O1eM(s1!4y#O(v)8@#F4{1wNam%si@I>g;79zi5n#`Ck$H;@`M?!Ns zpTI2id-Bp=qc`A>`i}D<11Yn01Wg#&g`T`xh%#(#+T%jmy zKW~GSxX!{9m@Lk;(}?MK`jp&MYq@ltb`lrR-HM%Pd|zQ=8OyYf#N#b$Zuzc=L?2bk zw<~pMPjFX2xGOlicHUzCpq<>W$aCk1>xzY-qI*8rW;eQ+YVRrq@D7BL}+8Mr4{ zzJ1snsYNZ`Mon3!sC(K?(cS4d6W15bvpd%aheG~Dz^5z3eJvF_BwhN}z~E1DuqQML zW_fd9TXzdoPAvt)BTq@s@oOM#ZkB+VB9?|C5My~JM85a$1gU9hB6og3i~L995=BX; zC}~LVAA+LG^K22U%G3~q%3js)!R6ZzFt4bE!lkhgQ=0;H{qF%Oj(|-UCqq!kUGnW6 zzI$q`1k5fGa|bc7E?9oO&rs<#tPAKZ%qD&T3s|=W_EMb}&ESOPH;Z}i;KO_^`npFO z=y+5DFSYWIs0Zc6lko53W$3&o0fE0e?OsE?K5a5?tst1 zfuQr`415jn1HX#lU}AZj1gbi~5}hOgb5UH=vJhj`WtaRURh625P2_whjAPWF8?pK~ zCn&5IV>20Qpd4?O!^f^2scr5b(04`!MCdQ@T+;wcj&A_Q^)Q&(Vb*t^FN7T%3h6&W zi7q&T@8gF8W}0{+c!HRezw70ZY9*439h11)J~`5y_yUEmW0=DKBRU{p5SkZW2@M*g zL;oA9LLE<_LE!yAu=#HT7~XLK%Yg?myxtc&clU)*u0QyP#1e1$957UWDqyU|t@>-k z6o)U9S4fg2^GuVtO>@(vpWpf^zPKbQ^17k#a9tZD{QdxS9XnBLikFf{@k(#uKdhyF zfue(};mnRhuv)_he9wD=?xjIcQk707-kt-IgT#k6Sp2NLN6foB^W~dtuBMTPR1RW@s2Z07?&{yPdiZn;C^ zbL?K(_?mREo(=Ao;)T(uiF@dJ9<#(we%|VUWWIY6w^-{0vG6^iSTz5k!nE=a6mrkw{a02V44uq z?aNqsR{a{uQvW0_yrTv=`ggLz`ggj3vFh{(g<=)(;-4-J>#a^Nq~YQHhYB@c-2iOp z3<&DC86NAnf$N!>F#Mb~B;D)+*)!c>*e(rWvH2_RI{zYO)C5C$Pv?b_G^^)mIji7_Nu3Kqp3+0$vmTLP1akbi1cV z@2$f#j^#%@WV0`pW@BxAb zh`Cu5BO7zySrYIui5op*F41bUV5;IyDS~?a1|AaX=Irc~%*5@O zA9cK4z_^FLhmn^0v~WE}?X9a6FzlU=@aU2&49{AK##(D2#i#?0#1-$`PQ&lELog@N zMZlEl3!^bd%)zT;WOE;%mvqPbF}sp$jOnx}CO^eeQQwBXT;wm9dX~eu>H0KwtUC3? zZm#{hs+3=$M-Mvy?zW5IT+${OKTHK2(ze6yVIgqr@L^yB+yu;y&H`o>VycLqY_of^ zBy&(Qr1n^OkX&ieFXof_@Cuw0mFYWQ)sTJHy)hOGyS zA={w0`)4$I-V2NKqF{BYFAN{FQ^0iSB4BI~^KI7Kj8Oej$w9=}?U>GNTK<>OHX9)? zc#UF9oX}ndr2^*A5v)cHE`_bd*eZvgwRfum!OM9yjLY|e&f`kS_+CD+zJChP;v+EP z*(r5EuC8z#+4!s>bCFEGw5hN(gNbY_4mbqXtjN1iIQxUd}dYn_KC=LJwX z&j*gEpCNMN6X3AB5Kfi*gUg6uVKgn>1k4h|JTGBwt`(1$y7o%uMorfv``!#8w+zdq zE{$J=H7$dC3*~q8>FB{|MU6Ry{F>IdrwsOnhr)p&b7A(=JozlmzHC$4Z$^D`5Lx#A zG*s>k6ELma1&j+~{5MXPYaQy&kuvh-7%9$j8~^>bw!)AZ(vn6_ zzm1e;O|3m}M+Inwx-N!+9gHwUhn)Cz}v zkHh2H4cv~m+REWoEu6-SY)-HJ6%3ppT2DSQ7BJ@!^L777>CT8U>7ei=?#AEuWbEN` zlAt$==o~{q#iLI!#A-emm!5+=9ge`OPcxz7STj7x$%oDl&E7+em!%xPp~aD~6o z)6QWD=h&eHe0OLGCuv3;O(Ort{Cd7fh$A<>8%TskE2B33m7p4;$%e2z zdpS4{uoe=SdG}G?%;fb;LweupGPrksEnDVf=1=g=+^;v(6t1#nHqd zX70+;%Up=G z=tqsW-+<){E-*(M_b8M%9?L7wRx_QXEuizbyMXE6TX<**h*73AaVzKKBWK=(Z9T$hw<%RcPf80;f=TIDx zO7D_!&zs0&R2!ep?jGM76Xw!?r=iJVL$5u)x-f=AcNg#vN7-)rc9|2tVS(oB#gjJm1`hE?^zOX6$K z*wBh2(Gc}f4eXbPl8q@*#4P3yS+uV+ReL!`!1#&p&2z-Oach(2HTg5wG7`DT!M{+` zv5!1GcofVLPtIH5HPRNDWL>v9vpyW0RQ4)F4c&a@82EAT6HR`>P)S4Vq$ z$&ilHoFZVVx(dHdF=7H%_F&llSD7)siQLZ7fh-aG9b7@_27)1K2(7)>QAg8Jqt^azEs;x1gS=I{$Ob7AnS%sL< zB_o)%Gvb*Jl0@!OCnMNqF#?vgni9Lc_aLbC5!hTn@e8_L*Y~{uJLkoK)0vMDw2ec- z7^QEc_d-iTv|@!{F#GC|E8Q=@MEkp&(3TG~1k54P>i7#{j;UHOB`ujuQA+|hYqd2~ zp@nWPfqhud`FFtJ#X~e{x(8lfao|4wGCeiC%vH-o?pfhrWqn7bVqu&QQCoEjbX0SN zrSnT^lHfsXSs4d5UZ1d{o(-k`Yw5rgXRvQjp$_Xb>F88Ly6gBpI=){i{23(?Fk8ez zms%(`#ymYO9Wo__Svo$EGt8gOeXgCsO<1F@$Xaz13NSC)IOq*{cf;C1U?^NT9}oO{ zQyh>D?aoK&Blnk3u_g?x-bRD@n)C2ncM_c%vl$b!M7=7W4Y=E@LGk(9^8ow|vw3TR$}?xPm2`QY+B26Vhq1jz`G39R;{){Cvc@YiVSxW$wP zwVnp=pAwpLIt2IE;(OC9p4JQzQwX~9iAkrJ%3X=vzv*gRX5B_Ef74(lsO}CrSQG+( zDAXz`0C(qm7=m|FPJIcKHpo7pH<+Dk~gud5lw;DRoav zC;5&iV3f*rDC~fZ8Sd^>JL47@T@^>OT|DAiAjWdFxTC5%^^ixXPZrxC<-zVJl)Psfo7 zyr0CaLKPjiO2&G8dC%sJc!IUfdPo@hMewt6$#?`>4tc^Jn(vSt-{CA2^`6dLdBPRcToFq$w zF#fJ7+}4K|I1j7EiYqneSgVt7g$(R; zw&O{F58KkgGKBx_CZTxG*K7vmb)>wm^XsoFkeEo}-{BF^Y@&qVnEuQPn)P?cY7hm$Y_Gx(sBf| z8=K4h*BBB1RDIURCs$GYsR{}n{sUEaRm!U$_@HP0PFmBi6ZOGK-VhcAbFXv&>El&I z_1$?0>WYaO(Mh0j@FWQw9Ux#T#Wl?rF=74mMj2@s)n^|>gT!RPqVHk~^_Z`ls=+O*p{@XU-0BlYC zMdGzSF|$h|A;Gnp88!3-tZhgp3kMt$Fw4X$M>t|^BA&_0I%_doUZ!$-(!;E*`vtbY zle&UGMlDPgF{VAy0j9YL47nc=sj5$d&V7M1GtR=4k|E%2=1W@118^Q_!1ma+3~dkx zlB|6dQhq`o7DF6vAx3kal|188tMqGWDmS~KkbQUd7CXfKn3R|H{?yc<$FuOQM+|TO z;oiL&F7?)@eFMJ0uYtkv=e;#-y^}_in8jK$M1$q_^@GI8gUP1nw-r3*mRL+lK@5@X zlUL+_kZKjBay_2@WOMEvVGCX=7#{PduLdm~qE2}M4DZ+J*{cO^W8b>hs4wuPAr!La z;mSO|mFN{=U;C71g{zhc_(p3J*;7Y`#~6!M4kcn%M4goznm(3Rq2t()02emvfIEA5 z?l}RYI#Gir-&CVPCRkfTOt^jvgw^WN_TbMD6%z`ZWB!9n(?1efDc%>@Y)Ic8Uk`gy$O$bBUU-`5c6=@N%@$8$P)(w_gJ0 zXks(`XQM~?%B^12S=iWVHl!X7BgZY!0L^a;U zNNz~Kd8BerUd0iYBP-Y~H!O(V$u9zCshTR~Td?@i*rH?d%q6;13)^{Iy9C0h$+j?J z)kPAN_!Vx?zD@@1@q(zKgFx#@m4NvnV#*M6f8=zz?~@>D=SivD+&@xcwqQDIlQ)9! zvTOdg3Di)be1|0OnbI=k2OL7jx49YBm!^uU&AZ9|LoO z^@J6=zgT{#Ma=4lW8{I|e5BQyshp?o8Rq-1(d?O@6G(By81NzTaQ_Wb zT9CrEKK{)9nxoEoI9n16?Rv1bQK$6|*n88p8KPGFfOVnYpcmTb^Tm{l3CYl`eH5xR z4PZ5<#{D^<3Kr+qz{?2}@m8c-cxW5N(fmeC=-Ku1nGufC6&F*ul^guo#voI6;Pmk% z0W}=F&c+t2>sEb!0I_IsD6lPq7j7^)ks zpvmHofN2mhTGvoyp>s(7uERtryDWtpdHA(rteqbF-%caJ&jy87G*8k37E8W^;Y)Oc zD{g=R1sy2gFFxz+&I>Ri2OYPl-hvp?#Il3T5@BAKl z{Kr93l@Tf2c>i1y7*(Wjy!eT!KUoE_#j0q$z~`@j1-@g&w&!PP?%08PV?<(Chitg> z>m*F-YYKU#J?YS!c2K|84>Ee}f>SaZ0aGScIgAn0SGruDFs{3Fn_3Dt&}}w(lT)j3 zvw6$-EUOfRWBiuGDinJ?P@I%9w;pnapn~Y%8(0~T21~pTK$pLIa8$b&&0pvVb9-He zaoT}EuKy=sRK=6D8Dc_S4VD{TRh25slew|EcS-C0CyKSpH!zN?QEIhImAcEmL0LXZ zd9c%Kno})kuFw?pX(RsKhULvBCk)I8K*({-l(h9*ys6j z8RV=fA>5eGw2w;&%rZ)WT(f9c5-N5@6p5ILh$*<~FH7~$lzhxj=8R3IkypR5AD~T7 z&MUf}u2iKVIjB_i_zZk+6kj0DnTgtsnit^qFB<3*XMmx_WZ5f%Fr$OV@cJ}9MwIXO96zxN z6h<1maQh>xpLhp+q0_K%iewd9IyT(zny-c8F zM?*5#dZk%<<%p-kV%#x>&xUg0p;_@gQpNZW)pq;_s!xSF<+~!*EsTQ!!7IUgz*ll7 z4YMQvUI9zb3>ZHx8bbG86fiOovj{OW2ARs7LiR~sbV}i#&`_yelDZ;8lBnP-Q2c1r zI{tr{`nMIpM^f<7Ve$Q9z=v4}LrROtl?**Pf5#PYG|Yh@Nd#=TDUK#z#5f}+@Wz{r z(DCcAsVs%_TKSn=UaG1n3&<8Qyb`khP5u9kCZlVGFdE(;dMpWrFf3Ih?&3(_W7_oK z?^v+uqxnfKjBCQW!Q*NBT1FwJ@>w8U>q zR;>8j@VZX^x8Y9&bz9ED)58An#>17YI`sRd#FZ>5AC=bHMoUFr&q8+7Po_&6WROVS3mIYja{GjQ278|l(1u^z48!jdYw;Rb~(n}o%Rm8HKl{=@-NUQ z_b#Z+xi4Vc`wAF8#7G8dNYg#1O72IdaHoFQksVfBrK1ge6&bI~VNR%sam>aBCgaZ- zd|D1aEi?s8zl8^(^2}4R$R&z-ybvRJpQOO4{@-EPEDW%vV)I3lIGP~DOkx#yattH zcVKGZSBO7x1G*Pw3!^C!M{@-+LC1`w;h$GYTArqG*L&s5E9drQ^auWv=b>`A*A)@- z<=b~*>Etm_owS6}%v2nMf|^vKy{ik^zUdkK#=5}^^KY0ZbrBx04+Ko5h>1c>$e3=@ zt?IiayYYPEX4+NpdD~Rxb<`CBGp?5=Rr9JBK5Kkuu>s~meMgIrX_imH;$m8_5&{KFD5CrKdr-=8yeq@tJ4mg=ygFnqJFkN~K z!Y_)L(E|ib24WiXbod%)tq@>;`avIu{YW= zz3;Ki@G29AAI+g%TEas!*o7ZzlqF=%FN0Op+LYJXL>xE`8^>7_x9wfY*u;1=atsB# zKoxrK-+t(XM#B7i6E0%%5o74sTRK0ZQj(OD!pT>BmmY0-#n_BGEnqIa(-Iz<(~VZ( zV?=rNgWe^y_`o&IXWDDu@G_R9H61yd2cm=JhZ^=;?z4q{#i9nP zm#HuXJ|iY|x2Ckpew4J|krb|Al@_~VUr*BY-b04(VP6{Effmqup(EcPL+MwZDG@fe zeCpx`vozRLU`h&x93qFqZ^EFDN8rjW+;G+RL&d(>>D6_hfN4R@kp6EZlNQdD`me>& z^tWUy-y4$^L-HA362JCs2bwpjUI+~;7=&&xOG+TJqb_y9072(iY?s%jWc>E)q~TNy zSce^iGPFTFFkK4{!4lx7z(f(FavhB{XM{=Se_kVXot47Hds(t{??^IQCzs)6aQ`(T zM!#M#pe>tMQnB>6%raNMMa(haOUmlT~>ZEYn zT`wu92g6+a#4;J%UI|-uel$FWPrl$=N%%dqA$EeVoLI<>G}lqOMIC~N*(;&Q<{nHs zh*nc-U6khbEds_%#PmhXplh0vwAvHWrXR`Nr$RGk{E13t%7a+O&gcPz7c|2EJ~SR< z%M@Wj|2OpAlnf3k>dNNJ1C(R`1VgX%32;>7IV|LqaNEyRIpLR%5(lGFYc7mt2x9J@ z)R%1XIWJW!P3D$V?q}CTcr)==sw5VJZwp!9jWsopvGymZt!fgSlk~Mv2G{=*xCQ;= zCiLyC+!Fo;);3RqgW=y{y!CC2)-zJ}wEH8B#%PFuu|f=I6_)OM{etu-dfSDT?Plq+ zzRbuE(-m130pL=73-X-NO)(6^HE~Zn z&^*-`Fuhg9)jvoPFvcQAikO;7`m%c#!BVrPWX|Y(tUPYSU8(IvbH(+Wb0F*9A;=(Q zi2ETpS_(>k$XD<|&#%J92$^1aPH6vy!ZF@U^|$31Xsdfh zB3AEb%>I2-d@>qKHO5AhR?VSQ|3fVNJ?f&+n?6^l3v>`M4v6`y`97n@@TT;|uoTWQ zZ=rN?ge|%H$&!speokC}st5^XE7yG$Tzg$6+y~#nP7vG_Os*enWk{GpKKRLW`q|8Y zIOUC}>o4EHuA?9+m;XsPt@RQgniFC+Jn1S6{+%Mdwj+frlsr<5a;jmrMD1n29mygy zn%@#WQkDmL#ydj};NOfrX^et^jnR>%mc83;w6& zpdI`d+RjFj1A*U2@6bf@pY|U5W8ik?S@UQbaP$_;oRdK2l{E^O2ysGhM$8;Zv&?Dv zE9tsrsodN11?;$x_2g4>5j(`Jjksyo5*@slbgxH;gi#;iWI>t`Pc^D%E_r3}gFNUN zPnt^uXz#P#nUU2)=?C8gFmb<2yfei>C)Gj1gx-yqx|%8SI8rMe+JN=6-9NYio6eFC zQySSBX?mcMqAs{4#FX*o#9DW zjSiwJ_;*#@-1;D9Mf?T%dJ_$%{z4k}`1ok<+b|7?|7gIqxjVx4S&rcEkt-OR73`^m zjA8d+W7Qt;?YRzu&G%Bv^r3W*##K81dOGn}>qQItuwbA!9_+>*0Upy++^U~IOobV4 z&C89L>#NhbHys9Wqc39Vz+RK{_Ya50>`*Z6`4C=j`5-tanPXy4#ia;nL{HoD_t)X? zb9>0F3c+B27V@>E6Rmr#gx5Qc$+bH65q}%;Bz*xfKBGU%mnerZBmbmx=LR2FgdY7y zzMU-*S{Fl}-4hHm;-cRR>2XK5-GcnVGH@A^E-HwJO{JO>j??F9XUGGMZgi2#XV~_k zgq#VuD_~Cc5PqBMh*?-(C-myJLN`#Qo9Pq?CfYs~|ptT|j{0}~c_GgbF z<&ztAKRt`ubdRT#UR(o$heYM2R2bwG0Y@xxPmO=>;=N}QVse{0D6%?@U_x4C+)Vv0 zusy(v8#M4C%VQi@CqV^@`F&9Bu(EpvbP3yy~I)&kmbCL<1^k z@Lz+8i%)8V(X5<+Esf}BbJxI;dVd0X_SiYpqAvp1jgR2&%Y3+M5)XNy8Wabk5+D|c za}o1qRKC1rdN;<7m2*4gm)Q$?-t36EiEP2DCt!CcO$gZNyQ&!Y#+U>--WH-Hp2y7f zokb^xO`t=X&(iO&)`3lR7$i2|g}Fv&;5&AH^O&0*geg#fnAp{ySQJXv8f(LbYzQnEiGiyTKj}4|1R-L5Y*B62R z@q4h~>nTw0dJ4CJuvc@bkyr+x!sfk!CF57 zqjp1gpwyb6a}r*!W%IDVE;nsTXTXOVX<+%fNhJoRZpl(!Vh){@U4qw z+h@_p?HGKv_Z+KrU7Z`)c`dhHTFaR4Itz0jiJIGI;*G~Q#Ei?)S2PA{GR4($Zq8Jh z;%HqqyQ%R4areVyrG;qFwC)LbuS7vP`ato4PP{)f?_@Dke>zYg6T@dICQ7gK)2{_K$g=6@ph zG{W#h@c5&=M{26{$22)tJH-Gt2AXjW1AIuFOC@CWeFHY{6JY23hw$a_W3W3O4VHEl z;D4+b&e@NrH~0Gzy?r`LQ-z*#^j;(7`i-Bt4n<}(@1UQ6*(W|UeZ-i4xFugYX|MFX zik$0u%>$|rkLQZwFB8XkH4wME82yJY3Fg3#f1|0M5vITx5z`YfZTGe09zG`0x*Ia?a66Vrg9dU2ffq>L zu3D(5EC!8*yTHQi2YSc27wXCYMLg)go`St5{c~^Td7ZCs6BH0!4SNp(=A4nC%@5 z@289a_oL--5X=V&Z;E4~kcK{r;!_1~Gs2 zb8P;taI=ooka1hK?Id62Gg#O4pO}K0Z_xhw9qe}K1pAEo2!Oqj__hQwFP>(vg^wNsC>D)`q+#EeHw^!Dx&?TGUkJ^y5Ik&Hb# zcw+;5uve!Hn@cSa)V&x~et#pU=XQmONy+5&Uv*eyS`LdGUVtyvq|GOWu|_0?9BybJ zPHMl&)_2ilbH6|u9;m|c7zgpUp@@lHXd-z~_9|njii{gPqz5~F_HHJTgvc%C{07th zMetnXJBjGh6P%0Xq|4Ec5Y$*EB$o%L>CtEV&nsSJrjkeheI}s&kK7v^NgjrtrZ1o?ZS7Wy z-7}(S+}b;+8oEbsA3aGsm0v{P+t~ufMC^)Ki5Mm(&H9~NciEmpGA{pmSH@%fO2+$w zDf>N0je0(R0l|^;;6m;ZA?y2o{(kUkN4KP{d64s6joP=2BK9l0(COP=!oQW8G&M03 z=7)vQP1_QLDX>~>$96-EeX6QNPdQ5#|47Eg#C#^j_hz$HKbD>JU7Z>ncn0B1f`zQ_ z_PgQWbn_-mLu+upH!5W1H%PvIitHbAgS3t?U;_H8LKp8dBvy8rHYmj@z=_S}o`}hf z>t%DZ+YXu0QaLw6&atO-#WRJawJH7MVL74$U?yuQ8z9gAG>3djZi80G2x5Y#7N zxz*z)aXk2rG&SUrn;myE10Q&h)*+W@>(+k4L-P||t@a_tM}1$0`So?O7hM&cY}_r@ zET)hwKVi%*T!@Xa{hmUcrxI+eDg{d;KCP7h-thV~E9c(S{qGE1O0{Uu>R&M65caNp z)})<+&d{qz{e*{RDmMNfMa=2E<2JMHr^`m%Q*f7i4TIp#TiK>tO>Fuubs91>4~!>r zz<+Oe!DVqLbhAh*g#2RkyB~pymDA72iI-P^PPhtgD&6R;gpPD-*I4@5sVngB&ExNa z&+Tc%MAuhK_N~*E5o4AM+B1h(dbG;BMIU7gd#KTZhzDSEA{*k^O6V)YAmK6$IUD>E zoLbW0ivBaWFGh$(={1g04!_BQ;f6B$&p?&6^7BC0C3YZYYq-3p=DvfPq+7T?b z{Lmowapw$j{JA>EPiU)M_i+=2PVhLI#zvHnrark$nz_<#+*3(wOj9Y$(> zg+1z%VBe=Q=vCAVo(DV9>4!2yLnYpZ$DO=0l8te=T5iM~#4aeO{4hw4%`U%ZI+()M<^f6P>rV zH@M!&5PqBX8Ud4qnBOfXQU@mkn|1eK526<=)ajfbb*$BdW5Q^1ss+pw#N?!FOP{*M z+qC~wa(iujBv;DIrQJttQZ$61rSaS>+<9VTSXC{od-GP90zT3r!5>>I zt?i%XP#-s(Y6oKcyL%!hKkFd8p54TU_8KuNHrmo+kEN2xb|p8|>;juC>rdkM-(f;R zT7`7%0v1J8d<=hGUkHJ<8=X5UEARf{zKqkSH-_24;!&1#@B3(wYO5++ zkK_xObn&6RM@)$1ktE9ex}=~$$#s9E#}59!n@rJrD*xd4=Q}EMvf2eqxcJcO5u@s|#3nhN zm9$qWxnq5sxE?bJ^WmHZYZsgewjGWEmK6oeqBW?xi+l`*gRTmtp?+nW%IdR4oMPA< zYL(p^4o~Nk>-v8 z99bb*a%nn9jl`yerMUInh^df+}KR}hZ5Kg3f3 zHZVtQ9R$wi;~}$yIcuOZf=Qpcm5$EzCE35`(yhC$kw(AcX+F7q@g|+?2)f&16)`=RNCbvXL>>}m3*GfqEXo0{C{>qCj; zk(&YNCG8X5n>7`}Z)1X(-7zh)aQuUBlhT zRgiP5qS)Z`-C*n~E%@Kpv*7VNSfqI$lAt%-@7Mvf21E%O==i_q=%N%ePG#9rI(_m7 z!FS+K*b>VBHq+h;7#qZx?b|PJe*9ee@lX~Qe$YrOy4U}6Smb3M*Z zWhR9WBo&Xxv*Eu|z-4(M@b04px5UvDmt~?V@&%M>;H8Rg0C9SoN|;?|X+?Pvd#07p zotAINo;`<%VXU4onkBCV%o6^gwPwi!-t=NJ_hoZ1tCmTaZw@D;*RbLKsgNKk02j3< zD1xmMdf53QBp*U_yjl$RSmpB?1 z#3VF4k%!If$1vBkIo~_0!N#;Jo3F@aeNY&iG4L($YZ^bApr|7Jyvc=p&&C8ySI{=3 zUtSKNW}C0kv-_%8?G2Qkp1leR(ni9mo0o-$7EvIKW+P%E@1)A}2bnMtTKBoPF6uDH zwTyk=Z@8k~NDe*~m>6H2D`0FVy%mJYc%KMtS_aI-X)%1OKAp5WgjOHazq4xX9FxAHn%$PGiDjSdqnu8@Mv7N5hM$zXs>#2b8M@)(Tc=_*3RnqJy*_@r<0B+}vZi?3$=A>Oy zDWv>{?9UYhFuY5Ai!Up*{PH%`#|Iiw_G?e-wdWeO3@Bt{?-^kLzG|?iP zt8MtrZmwFTC|#u>e3C35@yd^ems+*B*9c)-d@n8^;vm>qk?2yp(+SFpe95X$mjHBe)+)mpET@4v5}Z0W;@`@X!(v zv$y=CJUz`{>S&$C&DmT+_IUqdJ7b-nw`t?;4IL9@LRJL-+wh%Uw;NPxMspVQ{Vz_ou?^X)I0wIby6EO66y`(b5sAnOx10RZPI) zRos@qM}*Icus!e-GTz2O$dMA@(@Hab-v-4*)ZnhogiX#PXt#6g$%D_@%J|(~l)bAv zD?dc4DL0?#Mh8C}DEu}%Ma%=lEbM<*p7f!MByd3{=ikK*5<8o6b7tNp24kLp!H(Zx zm2wjDwkyFdBMI&FPD7%W8s%qNN2}pf!}YtO?R7hsqN1gYYgSdBwtCOK;>@Y)KkrRwyd)N#EI2fk_Cd(T|1B;_7=IN&5VS%;w;ZN)vby7+n)Bj!M&zwAWkG4h2T zO0Ht+MHbvEsiIO;tF|^0>o5Ex9<3ZfAQ&~tM)XnR{l_|9VUFY#FRUO`Lafctyhf=M(DR5<1p$Y<{fVY;0dLaT;e z5HN}2n)U@T;tJh{n3-M8Z5-R|<=a;% zxhXeu72Ll_vea3h_0-RUtn;|i{=6^rt(|WBNF1{8ngM^Cyw7*RCDD%_>9vPz-0%x~ zt7Ay2b|RVQ_l;-{>_Hc{c?g(yB1Y{7YM>;Lro;7+?+jIPQPEd3cCjTyD|H`RFfCVT z`Th2}niN%z13v3JM&}RV4FTJa+(oySbF^^a3GS4kD(w9mM%;C86So5`#MQPl9UHJy zz+4kCx`-LNBFbjM-Gj0L8krm_IZ3mbA!MDo#qtqIL8a~Bc1;VMZ6<;9CT;L@>IPTC zRVjZWh;6z|uWY%%@pi2)8&A^R<70)LPSlo8)PAa;faxK=H-?BQirXuhG;^p#b}*Bx zRJ}+7b0)zemoy>GhqpR*o`0E3oM*NPgN@* zns%gLJ1?g3yE@X73HJod&OBkJ^+!yrTZ1HT^$_WyznNUo)FXhRp|tK@u6`dW-Ma1_MRY}KJBYi zTanG(nt6x`85Ihl7mfujM+o!PQlrHFi-k?9q*Kj*s zMlmn8{l;UlBQ?8zi26@dp}PyO3ZvQeP#6tCO!$Q%(ovB;7`@W_Txn$=PS+rv9DFl^ zvrWVMv+>xEi}pF*2``~$CkAh0m81Hj8bu`+Y<(Zt<7Xxe0vRGMg%_KDzqqTI`suJ(x4kxF(C=UlPe$`JqCG9oDJ^VT5{piArW(Fa}3?S z)QbC(n+#58pF(z$9&P=yh8Djq1IO-o%e654iucp(V z)(N2T^tpiflqO)-A!hH*cuDd3(G0UImz%vz0-i6AlJqk+oM%u9xXV5WX+G^mg~Dj~ zV#>wlHRys&34Trgw(F<6t|r}5HWKD<7BR~95_ zct*JA)3mNa& z@69O;e~j{+_Y`=C%i?=DsXspwg3!FYE1>>EG-UUvNsJT&9k zPlQY_)39{#pMC}$3~IT5&`Fs*XE<$Ka1_Sv>rPj6oedgOIx6Q~trRf*M9eM3+%R#I ztw_*jeh|{SHX*~Pf%?2 z7E&;MgmAOm)8q}?j!F?q#Un%H?(*s6nwd4(92L=~AOx|?N?JT7OKE@{&7Q(UQE zu4sCs3EC@J!rOxKtHA$aoU`*tm-KqFrZ$pHnEa1)++aud7W`EFEj&m^*u*Mgesx62 z$SDC6C@wZ-h?yn7XQMYcOFCvr9_QVb21|{$vM!fDDi+vuh8Y)M65IROrZC~n|6!K& zsU*t6f8^WaP*QkT4RW8@)BnfQna9=ieg8j|Bn?C~kR(Zl$dtNwuPwa|ks))YWJ=~F zWJ;1GQ!*t}5|T<1y62vKB_gGynNn$zCLtvG?X%D4`|I)Wujga$yU!lhdac*m*)53Q z$Oqv)^+)+boF<$}2x1sF5mQSsgUT-3)epNXnHZ8z798e%VJpDDfqKr7Th&;S>js zSE$!LO&aTV&{g)DD(zN$0MEX!VLz>FPkEn@cKvlgyDZ%Cqqlv4>%1Lr&YVe3Uw1-F zv#zq=rn`vgPBAAJaWW_OE|Q_}niL#Nmj~esa=(Z!ykN>;*_~P((n`tRN^c;{jT+KZ zOqdzX;@*-&k9VEm#t9E}cjp3Z89fg4qkS>PrlccQ3BUaG0EFLWWGowvA;tU|qr&w+ zP;EEo$ZK-)a~7FA$(=_pGWfb@8Q?a9c7+*K4d%2njHBvX_IU~oooqjHfYP+F&Af3q z%;N}FZi$Dj$2{@L67*Y4b`oy0DHqUwx9*e zRzb@lv=N;^ZCj-GN8!)WTW~*Gyfmxd9;_1NK&s~J;e`K{EA+j^Fg6q;4d1|>^~84H zo@bB;2RhRZR{p%k=7qd17y7@-9l=n949d`OZ7Y!8Db+ zup0IsP6NLVT8>RI_9x#%vNsQ_Dj&cyciR3ieC*&P~51Lz%bix zFw6{!ak0|pe(1ckIXx$n+&p&+DTUkeRlR2Nf^oCZAYHeS+UVVX$&y~_G_{)Z>H`a= zY&aAHb&;BQ-9?(G&Zm9YW?rV<=GMToHJ12(v*+t|C6~tFZI*M{X!36|j4Q>wPaeLrSPyA8o&@vb+hxrj|kOtwhq}y9R0c>rE=HBZ!)Z4GvB%VxOmjxCA^X z2KgS~&g*=UJ>Hs0T&Z8cc>qgI6y7K-xXy8AwyWo{?f5q^~ zMk32sQ#=pqp(yrWh#f{1vePq1{BHJB%?iiGF zW9lzSM&LC5su8<#JXGBce zk8pL=H%)kZE;8r?!KxD=FwOvc?c0$c=kW=C0<;MrZu{qioVs3?e~qw|***FpOPnc_ z(1#$Nf7F*@8pQ=2MKN=ZhH(q9f&5By26^-JEU!CLnS?Bz!dGl81CQDU)*V|=rZi9e zjV!)oBjF%;(MAiD#?Hhl7pKYVj=o0m*9(z(=xY=nTZks69K%x%|6@zQC5o-Ic#4^M z_6GOS#!B7=XOhm}oaO6m?(pAL4)Sdi%fM#_ZKj#>9{HMEz+>YkDF;0&d5dan)6wHKMd+)3AU3r#Vxw6kVv;Fl#mX3Nzde>83(X`WW}W8w zE_!5JULaplLMMk}@V*+9I@=l+1^q)d$zM?Q@Df<-b07Mx+lCus)p*yI0%SWO1D$=D zfg(>AAh+y5e0}aW_T9)tOe)0~G$e9;!<^+#o!^kvj(w$;KSKF|O|g6s{VYwndMKOR zf%f`hSemQ}u4~j_!MFDibow4-oY{|)&i;@KHyPnyAEjs<`|TcH_$3H;IoFA;G$L-D zZzyKsqWhfu&N8{p$u}f(OIK-Y%^m*Jv@+gWs}z*Y>p}5r5Ujqw39e0_1jF{*gYBDQ zh!`IY-#zx?H(8(MBTFx0zYpth`|w_PW{vY-z+?LnnjfGKkPD~5`e+E4dr(bbLKJMcu@O%=wUsZ9 zxekBS)FAUqAJBRgfmUUnz()pkWm~7#HHN96nCsdXxSINH@|wIXqE>%GTJipoWaMsB zB4C7FK;u>dg!Ik@H{*x&)%K7oRf@syK7IQPeWXynI0bc;zXr>Pw1_4m9>o^~p^WGL zc;Fm0_S@)PWte)3NuPd^Ge5am9z?Q<=F64v^X?(^ZT~RhS6|G6_Z9TNJm*eT!!0kF zadXQ^dgk~>!TZ6l*z2%0o3!~NM(HNa6q--4b2c3y-@Yz~+Je#w$8JYq#mye1 zSX#n7x*QM6pn5gENW~XGENvhtV1ho~q<*%G@VBkKkZ+R#yjVFKo>w6Jsmo&A_m;(aAmaiv`6iSJ0);A@b3=@6VgrA!2u5#c2ra+yZd2fv4~@_dLm z^%iDYzlY7zJG9_`F+P~r2c=gBz}1c=5VL6{4p_JVpPmtbH^qvHm8LL;=|wU8>(i1g zn*%t#F1cjg217D=sRUZg4H?GoS_!QrdIstI2XH);2jfUKAX*}qax4~{f3L-hLvzt3 zs`G57BBq3NT2MP{I9_nU1D~0`fGudFiwt8-F?-GXNPOZ4a?;dX;<}_S@&CLE9_{bW zFm;jd!P+qmbYo~a2|c8*^rw;@T`DWxlK`KJy|8zK7F8AH!=Pmx=xUe4(0*nZU>deH zkTA@n^9*AlU}DGEK3lV0Hf%*6;g`CT($;(kCW>N#34MtygF(zLaF>$oqo!cG<=+is_EW zTpf_N71hGjazBLw?U8G3JN9jytMJlYrfE|`v-XGbEwZqAiWn3Bf_!P zeu0fKdiCAWz7i>Qa3 zs|uLqE+<Z=pi}88gxpWC=n`aiP*nP}>Q|+JjX}3afKH6owI+_(GHy3Q-w` z2ZqJNE+-?!_@_z=VKj?Hj0?r=`=-GSe3m0w`y-F&1*f9D5<{?`|4MG{Ag2|@x4@Gg zZxvl>+scwc+A5?N+)9!lnwl~C2B;`btEek%O!Tosq93QwmSXpt7vbMO4TXl*A2ynm zSJ-G)Q;c_~Te2Azee6l;EY z!aGLI!Bzd7fOz#L=e;H~%!uo3G`lFqZ{&ZnBL+s&;`#Yx|I=Umy-UZDZ@;T{FWpDM z_tDCrd;Aj{ji4RODaePiRcf%+Sqsc`_sPGdsY;!$JK_2RIz*?_Qe2wX1xEGCk}8!( zu^oDxi1DMCtu7MTp)&)dnrre&OYncvZc%B{!s%7=;D_BHuvZ!qLaKs|fzU&;Zf`zy zhR;J&2UejT`SIxJ{O>3uXfb|0%a&wqUXMMUFQ5nORAKDWFt!Vf6(1hK6q7c5o@~K+ zGpXuko}QLaPg+a|0Z-aQ|V}oGSO6(LgZz61D)}u zHSBk{;eajU$g128_-(A0{7QNkSawbf4N1kjz&VO>y;m;lF0+t+xsy*+X2vRW z7aB30jYY+4HX1>n)?t_Nce4p&r=Xw`aI4B z#mr9dYf>$GuXB&xXnF($Vf!#lGVbibtB>Tcn9aExaaj0nZiDHgI8zp?DYA9g7pkpT<9X zbSF*ryYTJ<@AzNU2l3^FBN@g*Jk}B^=EQ;hTo?UOQoU;h>+@W7m%$#j<&SUZr=_XW2 zzS80gY273_9=VrKaCycWY$Vu~gK=pod$0=~m=kssg7V`ySly%x3s5Os;{9=h>m_-i z?m8S|wTM4@vk~nv8Uey@b5J~Qawx{5={i^HG(zfdtB{y&D&tR_OqVBHdGXHaPw9lc z0b5#@EqL1r-Qya!(CBUOXW0MeDU=WGk5^4xh$mg7GVALt$mr1=?04n|Z;&62W~^H; z6)>~TuwCE-#SGjM%>}(MmF`k0BAxwc56?T9e572L1Wif<>(E?qmQkT44G;^x@RTdl zSpz{qWWfh3W9!4l_@BikTyi88_1NHw9TJAh&)oP1EnZ?`<<2RFsiv6Mmo9ON9a_@k z=ZZ+bMFU~sV`IXbEa!84(!h~AQwZlx$XObzd6flM2E2lbq6XHauEn(w#-$qI;Ui9C zo$gzZN3A=49wL+Ckzaui*TBMPb{%J!W{O#Rbt0E3sg=}yEg}^mdZ4jV#4v3XQ)M)UyQ`5SS@@%fe81gIvgqr-ghSO6`Tsg#%2treem$3}B* z4>dLOmBEQmjHWD*VN|1N$C!9OZsv&u zNw?9(q|3(XWd4wBd9%tWne(n!Oam27dvpkxoEZg7a4Ae$Z`$Mge26MGU1)|=uN;G0 zG>&uZ$}@N{I~F|UG`trT&oD;fXtXKDepooy=x{-D8y6Gf8}d&}7KZCU<2o8vYMq0e3o>BLm`MyX zS;Xj5%)-5L&M57OBxz_dDf2JoZU4K?Z|U|+YX3YFte=*F&;rTwbTPYfR7>AL$8hRH zNaF&v+xp>`2Hzm;j1NIJoypvNQ^?uNOUU)(<#3?96T@^1W|L-0F(zY5xwughNmNG> z$?0@QZaH8qSv}kjRUFKQV!tYg*pvZ=SBk*&ZXpN-%tDJ-YkIGqFswK3IB*9z*H7eZ zJ@v?anN3#rE+ER)dN|;&5yNaf!7#%p#=R(wyKaBaZe2_fQHr2ZS@mZAfsQ>Adat_u z`ba62eu8$%@PyQz z+6;yBoS<_40m$9E4pyhzLCzX#oIzg%@4i^!dX2f#)yC&Y%;jTbXZ~99#|{w>`5IiT z>c=LnQpC)o7;V2G+4q6hxbA!*F+Pi>VZ$o%R;$5M1b&r*D z)AmNW?(SSRY0V*-2=BIlQ+Mjo>>ku{nfgNuS`LH#n{b-jQ$A~0HG174M{gfJMJIMv zpoO*zaCZ|+hIu0%1fCSr&G(w@n#MzJYeyl`uTYbhUsgrGPU-V*p0q;cLla~NeL%iu zqnOTS>V{@E8llDOy$yaidPxI6YiA>xPOHG&mdjDnhiX)|c{YB16*0^+5wn+K?z)A` zUQE8j;b}!=*nBJ0wm%Z_b-uj4ZVpv*H$Z&mFBJMv3NyN@gHY)uOq%WJ7#J}>7!SOl z%yc%@eQ&Z`ju5-qsXYU~Ql88(Q^nsVfMP~(KOhS+DT)bP%q0)w=X3je6_bEJf#~z-t{|IuiT629oqFjm&`WJERL=>A3UU-C zH-xa!gmsRFY4?J0sA@C6-YpzD8Gk_RT;6WjYKdlV*LiU$7ZajfDwn)lIZ z;7-|F@;0f|Lhn}r`ZaeVcC}l`FvmqqB*hFqKEQ5<&LLUA`uAk5p&UKYH-}(6oVcvW zWXhBv1A2;j6hhsZG9C8WE*0RiJV z{2piy4ZxE=4kWG)y>Lq;fsyq+@ZYgRv2o@cTpcA!M$!+nNqbB&e>~<$3Nj2NN83M; z=sy7excN)N_wYYA_-qV)v&!Kf>7Q+a?P4n0Q++R0{UpQheb&+2L z{b~o}Giw%Mn;kUKvhODwjmja0Nue0)h9i<m3+4=CC&dXld>F3*djM08t-3HBNIA`s%&ss{2tuwXq}WQb&mh~ z9n$600%TASwp=rT?;lhI6G|UJUH9(zU-2ZoYUU6;Z;z-Qbl=Y~`4kiVZJ5MlbBv^q z=ZkJZ)%{m zQx`)Z;inGXe|icwEHT0*ZX#yQUWO^77$@~Xl5F=(iQ%)4q{QwD;#b^5dv{dxLNj3@ zh1d3nW~HWmWGij?>TISUwx+G#w*K6Sqy8S^AImO4V8dyMQ}2xXthd9OR1$RCvzh%i zEqfTIj$$IqdP!>glu8t%%E-&&Kz>!8F52z7gcn+h3tg}*6W>E?=L+znZpuQlt-98~ zAn0toPizAN<7=|qvvHtvbv6L6jdN}L52({~l-c8m} z@lzY`e9#GR+xLWY%Wva_gFsna0v!}{YQDZ?+{qS+V?-I*Ht95f`(UlqwC18*d0{rS zpnlKNt0Szc!7}F!Yblg5wnz8Fdff^kQBzw{JNF?G zFoS*BXw+}fSZB95yDYtblFt{*NPF66-r`0#>Cnj;QjZPk5cDvUUNI_JL7AW+7EFNZ z!f7ImO09HOePc*e^ih(2 zyi!IIZ3hs&Ax84r$ez60%w(welR$f}RWVFdD0L%$_5p%&=<{mzb+{h#kC-0TR?tRqSqOJbY)0=ZE%D+}Z;_{dE?MfI z#ztfA$0p63VvajD%7)ndk_7fIC(+I4`0eo}68#;2YG};qKaY89V>yy zE^}!K$#l4`a*7Q4=S%kYaH7t!H&8;pE$-U15#9U?>jn{lRn+-~`U}v}2pET49Z*`@3ts5b+Nfngl8DTO zxG8F1a<7PHY0U>IA9(J(jQ`a5+GlH#*r@2sb462 zNh^sM2a3@&ZD zU{TKF@Zb<$+1G)emwgboZ!semtS{ryf#VtGmUs|sq?qC)BTi3~j%MvA(w@AUk2v^A zZgcwqzk2)zNWH%u!qO^PId+|LHZ8|00zscvd1EIG|MV3eTK2RQT3z~yJlj^u`&xFFn|R#eZI?uX>76*R|3!1q z^ikM0CYzR((C~NRV^$j#|E)JQ)wBT%zhn5_;vh70-V*!_O(Jc}TBV$~n8=?ZVtgsa z(BL>nj(?Xtom5Fo->*iCK97|D{2j`N?MMS#e`@`usAT#yL1&X(nMbYMX>S76L{N_7 z(8Lq|@M7Rz{L8v0npmCRWM?y9rwc*d%XqJkYAc`qFafCZLNlAL)uWd6Rx-OZlpiJm0FI=F6 zn2m6H^0}1|Fp zMzj*FSiTP*@Y3T;)%xSl_r(4;FL$xc<~GHg`qqytz7;8%Xh=IIy(>oNyo2PojHdG; zZuELV8`cV#*4nph38>}L*L0_92#V%lOl<``R2zoFXKcsQrk_Oh23zo`$UtcyYCUmx zZzCIxd?&*sP>k;IuH3DNGm?@0s!4V4_tK$HOiBC49J%M9EJ#0@4C$S_sn0TgYu+kebNvFjV4EXc z2Zip~+Qr_ZL9s8BLhN$D!$Sf5R%O2^Ch_ z2657|DQ4=YGu+0%){;EEYBF7EB|p<+74MoQMaucP><%qx)nClYWw|vMQ~DkqSO?Cu z?P~~a{>UwBhn>D_$-PAZ{P`qZGJ6e>*g4(sRi7RVqwT{+Q%o_ZSKj87Lq6N3 z-$MA6NxjKSn_v`?N^8}rR=w_3K3mX2sk}W;M|J26M4V26H3$BJ`QRr|e6pP6RfdtM zi9ETLpF=*59E4|hbzzum;&rf+V$K9#;j%pIZS%HK%wz_ zNHIn8uW-v|?vyRkuOhuYcJdOKP1;jepfJDp;2ipyUcnQfVlf9f%Cyk0a~#7MPEb%E zXf2$vXDV1(^imXfc96i=YKo61)f5~5%)&)u2eHvi5HY_fX3pN-oMu>muJ@ZtqB+YL zP0p_2wHJD$ z-;1xX>bOhjJe zHX1uE&X7Kv6DwDVnk*K9OciEtDMb+@YJt~y0RNqug$pEWr4OcANm_z8 zPH>+09GUJeMSESm@ZyHY46|Ltm{5$#&LP~jijSO(VjN>9+Mb$uiI)u7EcZ;N(vZ20 z;2WNc;>jRzFaLt#6LXNz&`FSwo+?>}uT*y9?Wep)iz;8DxVfpQ-^h;$n|tB#{@x4| zDq<`tX1tX>XSDb;SD;r(rp!9b-!t!!YaLMH9b1anr1`cLqe#2qaG}dLgflCV+p`)N z;TsR@y*=?O7|44ERwA<-1lh+vLl?J|p*c4;W7`nU5xO&hqcvSjS3o zGD|9b8J;6`I=6(cYc7PgZ(qQ7-Z#|#%NDkps6t;2Ww8B2za<)h>h;GDpR@^MRZ;!G ziJQ$-iaGcOQ~78O=h`MLflDamZ5-v_2Zu0vi;TE2lpzn zI_w&XUsl4o27TvkC+4x3jfPJY1f)F!^KrKzB8_IJB(xx-+a1^|JBZhqz2rtohoKN^ zj`q8-6dkY*N0Cd{;@6iA7$!%=ETx!HMf%+DFi4J%$Rlnh{}#4w*=6 zajE33x{6w}QSD&tq)awx3G1WbS7`vwJf0}c3+{s*wCbt7!5Q>zfD+s^TY~vDVnWhf z#H^*59(#&qEkCYuPYi2_&8^X(xIPxXZZjoyG&kURw+eLClR()h2a2y`f$rgV>{u%v zbyvs~V&wtl(hc%{c!}Q=IHlDUyT{RE?wAWcFmnMLji-1Q*h(>t+dtVlhRo(3f2bj! z6K=uAa|jklx{;u*w1TLi94u*$O%V7i*S-eyhGwMbT|i^cEtqt86TbiVf!u1OFXWe< zfq?_`@r((sI5BxMKJelh!~7EuX&;KwD_bV{R&Y)>`gAS1VIKmWel3GVhVOYd1FAxy zVpyTLT+rDVe#~T14q*wj^u7hl&6nZZ-7oU>jgGMSt~t25O~g<0HsFDO4&bvv-x$Vf zJKJphDW=P)1W8kB54*hepNY>D9kTe}eCXIThv@dof#}ag%w*I= zx@Ye~zQJC+D8~>y!U>F;7!8m5_roQ$GU93fso3O!9m9lsGRz5zxvjZGQdF)d8SGj| zR(!VMm0v$bF`p(Ax7#^PnUe4}gO&UW7$JY-@!$(+*TsRd$0}@{dyMZhoSJC#jDqE# zx?@$e}i)8Z+cj2D(3Y2r|70kKGfzinvkaf1g3mV4ZC%?6@aOK#& zg<&En=FW4u-NE@mlKh%4ByNSJWXzIl$h5YdF9y1Z4U1^@iAs8@!{z^7ZiW1fclbl- zT6Pqs)SN)Zp>IH|j5@}3{RFQ44REpc2g$tP-E7kSh@*+2m{}tR*{v_RD*3Xeo!5;SEL)D+=}*p=JWj7CcE*RKr-I{=?CTHCaPM2NT}Xd&n)-GQsA1}E;eB%j(HOzY zBpA_AP0a6TDpJ>Uz>V`SQR}$A`0L+SFyGEVvAw#EVJ?c-!E}mA_Znw+TIaLmNM1du zcF>exzP}m$%AYCs3!w&@Lmoog#R~B5TPtcgV(93Wr$Jq16g*w1qNv-aqsVa8!OttU zqEEAi;3}&)$c*i!fL?zY=9!4erI@u1A8l{fw@IcNG!W0tj`H2;qvS&0FkbiFZTeY; zGG&T@5$@2frTNqd;3{~03x;&FdXjEkPoBLVg5$CVql6pQIH>6eR7O^j5!(3-QzdRT zr4)1A@u_WZ%|DW-OB+b{Q&YK>!!6K(Tb6vW&Jl>jD;Oq#)ck);=vCT*aheOH?~WwS zb3@6ME~D{-9zk-)-;?n?tIg2%$eScCIKnU*;;plmV*b^JKK{M?kECKl16j)j@%9JH zF>dLEM{XYVp=F>;vS3SQ;*suMcW(5#Q6Tw&=PgN)$o}-#-a}d%8QZk_SCST z+a=Z6l=|d@`X+-dU7(r*_{-GH4>$rvX z4gZTm=Pk#T8*=$hJ2&9#I}Fgc{awJyN(>Dx5J#hShhCsoLvnsevn2dc12NIKC$~KR zQ=Sp^S{|R#1uXoZGmK!Q`G1&Z%R;0S{Sp1Hx`eV#RYAIOBVKNyPHKF2;I7BRbmcnPP3!lih3=Fr*kQgS_N> zUKNrVJsU}(Jcsu;3X)rfOymRa_k+;uU1{4RDvg(xGdWK{T`qj@I{<77y2GQCD=g8a z;dBTaU2o@?{XK*|J|AE=oz$S!Sl9(RiRXv4{RYcuJ{C3!AFzSOpmj$a#cl!L3my_^M6_c5{1!P^J$~*I&o)-_Zn98}2epkT_`zC?@sO8g9hD zB#HlyCUWI+n*6Th7vCoHVU=FO=_zz8RqjSdMek{r9%7V3C|ZgQu7tv+gK)nwr?F>2 z4ccbviQk=&@rzx1Vd<_n4D)9*ThOi)<8f*lcd02t;_TlgZXqck7!G48`mNDUReM>{`~>cnzj+oed5A59#O>uE{Z9< zEh5H)V$MvP#=VnXki1&gL>_xSM~Yn$yf5{+6)?i23346*)ApN6N9btM)u<&fz3|@h zs{o_+f!LwuFwU$%& z{i{#&+fJ&;g*1^6Oc5|bg`{8zD8y`pjEBn(ITX^+#JWafEcHBs|9UndTlXdS>z{9Y z7<9q|H;K2-?j8)YpJKW;IdTi{tdrcZZX*51pOt?dYr=1Hc9y31qp3T3>lA*Q(zOLl z*D2`J?1$H|n9c6X^>C$12M@E#LjN@V!1(AK_%Ns!%<@&oKT?9k(TJEpis>Bb%B>sY zD9P?qyZo~a>SU0)Hm;gDmSJi(u+fB2%$@v$oc}~qiFH^b8D{0kTW7ZL*V9fQYn?o> zy zshuXi?R*q^WveT$(>Uqlgr8)!fr`Ta(0F`p>@$X$CoX{~iW$uB;9_;NZ2x=NKmy(M zd5=~ta;^VeloL!B^O`SIp_&K@CsUb|McCm)h%y#KLj@1%)jV<d*xf{H(YLnPjReQdfT?(=$F3kGmhq>8|eBeEwke+pHD8n`DYv znB9x3aMR`H={JySRVA49&xCwG70NI|l%rSC7C_^UL(oBA*r>V`)V@+TCDUZMKhgy2 zX)Td=-uH|YuSp=wzFi=Wb%A6?Z~&gNRF7ej&`cr5i<>E51h?0P+k|A4ZLVDG)p95aznk+3n$jdK1zbmhqa7`ZR zJdtxAxd(q+e4kC)9dS>4Lowfvcjiv#1ar?0)DxBWzvY`EXYk!O{g$+xFMyEvMmW{^ z7YfcB3%yQsgW4f=Na!amm;iMNUyhSBH%WU38%XS@<#RDJqwHdq9FYET--Lrci{%Q# z#T~kkV*cA`$>p67aKI7~6K2WFuedo7r4j>WVBh7oF` zy6UaP+qxg+x0P0)Ax=-x0)rIPJE0sk`)$XgTMn_&bcmy=pcs2@9M|3HCbu!Vo~+tn z&Ud`dko+hc#M@@)fwMo2Ksn?fSDj&?AM_pFj;};QpetSS0Frti#N3JreDAq+$iMIj zI(v(tBcCf#$WwPbuP54DCrD!l-I1@**vbpSF(GU> zduA>2x@H53GdjbJ9A(y0+`cj%K5ROQO|G8gA5CgTpK2bU&}}>#*Ib3ZF4=%97jkSg zvqelR#W<~=%nebG;rt~H1oYPCao=w6!lO_q_6xLEg<;u~L1Eb&mYy<#nJa1_ z!YmHHCk12MU60vKrYSTEKOY=|ug<-W&kSCV_qTmxm?&{UD@D`%S1E9*!|!lo6B~%{ zq9M{b@y_Vn+yq{D-v}Yq?$;;7h+an_GI1@Kfj3kStYM)c>I;SI`z+zt^Nv&_@DRGh zWWwBkRS=`J0vqhKWefVL_<3qj%uia2J16Waw`OD`+4RsD4Xm-_cXoW?g$%o=7Jb(^ zh0z`!$>2Qu8nZeUcIcdc(ct$l0C)f9$)9Y0fgXPYyWLI=C}8#l)a<(+w_Kxc3iPi+ z#Pp(=K_MF42(RPZn3hJ8@fyiC zc`hXMSV9C@g4=HDGfazMk{h#`eS61gdRL?E-q-$#fd}V;arut{d`aht_;O$wE!5P- zY6phnkI$Civ&%#!qfp9|Ao`S`m+oOmG}j4!YE? zO)xVNL>9sYO2E9xjE2dThw=DHX>xnt9njHb9n79?guf3SkGIFK!J*E_*`$@NX9s~b z#q1tB-fqQ`AGTRZUrEj)D@gI}3SYaLkP2#R=piX#2DE}uS%`9+TmBZTgJ^e>cXvQ9 z#t%1c6(&30@O01<$HGTdys#+TLt8_*M%soR-Yz zY%m8?Z$yf-U(-viP^Ci4O ziMxAR;`VpR?6>JEj%G5&oN2pd+o`Xcq&n#vnQe5B?}wkFUN_xotEvnZv+*300e%BM zKwHf#cI7C()xdN%pQT6fv+Wa*dQTPHd_E6Cx7S191aoRdH56++Y+#t$b!;@VDaLZZ zK3VMdGm@*h-^p^tATrjv2SmQJA%f;sDEznolEq>+LOe~VTN5<5!k)H0G!Uy>C!%mC z+IYkH6>OqjgJF5b_|W5C_)u>rHfhU5j0?qle05l6yFXT<6aItrT~Q>r+WHVp+uog| z(Enb*M9@wODc#DM%ZPC0I5+th6fb`ScmLdngvqLqH2niCet83Y95P{#hBm&KrH(Ss zg)q!Uane>(%(~yfGS9s)Bu9s}lH{B3(3p{KDEYmD?E+zwiy{4M5p_@e1j_5E>Yl#V zqBVarF|6^crAR|Zmn8J7gH@-tfJ(?$SflkDR#bbFj@gIUOM0z%v)N2B`zva|7O<`lGi~9zq$$h zP0Zo&(9YQMSr&|yw2)8zjuW;Eh~LdFifP*KCwu)&NqVWcm4wH<<-*iIp!GW}>kvc7%FrP zDj7yY+y(q7CVJvQnciq^sd-*2dARMW+@p5^s^8y@GoAGubg2(?`pGJ0aw=SI1#1?e z`H2vO)PJX>cr&|)LhV3zyv_M4+KdO%7I5cb=uZR1yG|Vp6DDGUDaNljN|ySwkCbns z#bKlLB+65JBQ;$U-g9m&ZLf2QMhL5+?jTKm{ST8f=r&XoguuJz7P7i)JLxvs0;@im ziYoVw!uz-Ef>Mv4WCYby36qv0UOCQD%%Rgn_V#RlsgnLraxj0V)Uod{X;NB(Jk0q7 z^m5w-*3NWup_Z*LEZ>2p`g>?sc!7V!I{54VfauDjNy=thJa2ELBv}r)dgmZG;&75Q z;j;{5EFNpuC}w!=N7r?)KHe`Eh&Dn0K6&(F-&Z4dTF9dK$x`K zjTYdw%#vn2^5qVWgXPBSXJGq2rE;~3Y54q=Td3-JS84BtX13BgiP6DmidmY_iQDjg zu(UUww94Ui(v3aFOE(&PmYUQXgS%=KQ>F;boCJRX0mICJ8#+Pr2pze1j{xc7GjnlA z{yBd3YFe%k^j&)MsxHcUx|?AJikL)-alcY7>)L;a^lnBgslPf5&A6y3@sIG9j%ih6 zem2%UYr$`3E%SsFFtc@EpxTg6NK-Qoo#@|+ZY_4fUtKzrG}BG^WztxA!(h74y+6w~ z8&ff=&Qnb3Tp|n58YQhBR2jw)(UctxLI#D>ZIfai&&@z( zPpi?ZRgvgzniAN!d*E*KjcFUPefYtRlf2zY4H&3(f?>LgvCfwib8Tj%Eam4AX_9{{ zd0}cIT{%ciZaVb6#LSbXhiITnzzCnG@b+vBFNRa+YEj_QHgqvA9ChMVK;xblzAORK zCn6Bv=}yf~sde?#(xVJ>OvL0+Owqm*vhpQ^rDT6A89Dx*v^L#`pG)%fB^p@;Ft!QIF%rDOQ3-e*3+Xf%$Sa2*89JaMzBrkKHNyK`U42T7lK zx02NZ!}!5!>-g|hCQ{+Mu|9YnOck{DmhRBnhV%hXd*N+f6-7PPLV@~IK~mFHSl|$V z8v_#fltupd(`GYLcYi5Vd=nG-U&LLYnPT>YXmM*M8A%~U1RlE+i38T55DAV>bl&0IX63^=S$batxX^vHnM35*74K@T!i(V1rgI!CijVNgK~sU>Y05A|#nGtVRZ{w5TP*AQr>FG5 zlvXm#{}q|(p2lz5tSl9zy#mJa6Lm-ULF?HAUqMLUy#McHVZON>rW*Ca65R{9S1&5A z2s(sEI}9S53wq)00qG2LLOgG@DJIF!jH@TAQj_DYB*R$-hWV}x+ zd7=}Aro_1O<~q+=(UP(c%@ERm2)DDx>?TL(u6>)`k)0|6bm3cDZ_ zD(a>}8O`I2_)omqxUFOuOfkLFoVa<1k4o}3w32!MK1o|M4)H@*+8`k`$Vt)kH$F*peF2?vKo44-df*ke^HK!W&cIzryagll3_W2vt@@#1xRdH_M62 zK_$iOOXKi@^fzpWc3#6KZ8^pK=18F8(0KA)BS|v+MW~L;R6XJ534Y(dK8= zeN?cUTCj+R3KJgM_|G7GHz%BoaEJbM*sI)AVO!lvLEftL`$B3br0Ud-DZ;(DPjUB z=1rsym%quCyZZJ!F__@W=XyQn9giI31iL9A{GhN>hsT%4fu=@JXtw!*1R0zVv)SUj z2;V!_E`6G%;2f@}an0GzT>pYOQe7)=oICO~!(0<%ou?=UwvFN*TKRHAo4*sqI3NDz zb{~GxFe4UB5ilk%KcWvu%wcPDD}9XTBO!P%)DfKgZyiqb+AY7)<30Li@Cr?6Rv`DH zPpF%bH|7Gxm$Z|J38R>Tp1>KjoaWNT{vhY~IP<=f&E%I?2k=6rm+qo^W}7oi&w}Y} zve(lq2*p(QcmRQ`_EWdsSozSc6=;j>DcWKpLtW<7q6bGk@U2neXts!lbR@-`F`UPx z8HIC?PW&M2yB?O${cXd0e7MRhPsxRflV3n-Ruk%5J{tV}RblF@RwT$0gqY1stpHpU zV#Qb2)uKc!Lx&5Vpvj?i=-rb|*!WmBo3s<+u@*})rY+7~ndWuwzG^G6b{itKvz#im zT$|2fHZJ2o)0*|p;B{ppT+r(Q7Eg4T5>hB7Ilk!_t{*d>#cced;_xtZjoozici)6{ z&NecPrubTWOfjSIG|v0{HO~HWD>>osCAA;=lWQ2&!du3^g}S#jkUeDr8ym0rd#j^U>(W96pr_uy+u+PLfQdO))7_*vvytYSQxE$D9I=b1t=@6yI` zThCqMK8^ZGR;lTr{mFX#!QKCOU0F60_33sGfyqtxAvx+ISVu*GwjHejrS&(;0}tW1 zhd1zlEbU>~zQK|!)AS&%MuwudZ^KA^F~fw5r)LJmIQ7@y@{fgZ?^J$~h%a;H21!Xs z{fr$ELPMrbl@Ruk13o*SiTVVWctJiY=xh!=4Z=2I)6t0CsZza-50QP&bu{%7RUP>( z!;?n8XOs4yIBEG5(~@M)&78T0n{E1=SWSJ1c8nPZ0}Hn^j1X0i&P`-xrNVh59BakD ztDr6IE?7}jw=(t33DmU1ZS<49)2$tD#OPzK6gRAEAl}nl#L<*dj9JEB*?5BnnT=T+ zQB1iH)owju=hn%j#U+c?;s#N>JnfA|w0P+iiwg)k8$ko*?ywI_$A-&$E}adH`ITwB6dK&rhbS{~_}xnIM$`gCN*#1abbE2|{IY z+pHI?>RV_aD8y`p(FhtS+m$|e-(&~rRMRLpIVuE7WJb7P?Nod%dMmzI7R@kw#e?8G z#avr%Bw4fNzFl9{c5>=%8@=tT&;sS@L^n7Sgt&kZvk@XtLTE_H-w0|uVbZq51>vVv zpV3@pdXXxB4uREO@ZEl+@P85ZxW}VZ_S+m3F&z~1XtkAH?>r08pk~h>5wutqRtPT|AJOU<#Hr5g@x0|bJYrS6=P-Z`6eD`r7T(E40laI~t@cmoq8hmI%EIKG8y)2JpLG`B+u&u~o zCO|@kWZRAhkka`u9^3H`OK|)d_iOyd4k|~)phY&)>5|JsHQiNm*AycL#M4f&1-jXSVWGG1` zrHl=dP~WxJe!o7yUw=T)$2xmj>%Oo1x<)IiG?V1^x^4XY+;-lM>aplvmN75d8;Y37 zmxVNVQ`FfE*!cp~IyF(9&HWV*pgBnnvwD-V(5nm3bKEm1t2V^bE`yEMcq( zCO08MF^Q-hKAdjj{q8PBQ!3;r%sY$AdrK;T#zc49y@<|u)Zc$jYc?Tezu>}zY#3FR zgLc-lT+L2meWbe@Ob0eXJn@6N#PsLSUUH?^CQI6KI1$X_>>Y}p8w%vZ^i%}->E#MW zZ9j6+U&A>kzXWH0Np>x&AH=-10c7@R!{BBJD^fz1ju*ew`T}1=9@nrDLt&)DKZv^i z9A-Xw%ey5m;l*PVC*1ZY)BQ#(P+Hy(`LplUgwW%aFm+fNvh_5<^UQ9-mcJ&#{NmRXb6I+)4Ir5A zk*+ehaN1$j+0zp&ya7 ztBpgAh27>Fc>TMJNcD&vp7U%!sFhg>Mb=Wyra^i<2NR52#!N-aPaS4jClx`Zoor+Z)_D!j1e*7U`#fj4#s;9La&s6{KH4;!Zl4RERXGvnz!}9hg(;| zoJHzF+w&T_ngr>cHkx2gPF$@}`DVzR>!l+2_{?KIRL)}-FWas3>%AXLxOKENBnH!n zo{%EuRq|#qc^e8L>bZPG0Lza%(*sZ1)r0NW(Hozs>P8%Bau(5@0Cx9`62%_ z*93h!-UWPBej%~YC6m|Bkp2?Ie%)WB7Kn=6RV{nJZtQQPL2v?U+|Ne!bEM*W^<961u1VweWH_I zB1X8Lhj3UKT3MNnx(sVX$9*Q^Tk%cYFt;UmZ)m>>pw^3H|3>hP@mIiaCeVR zj1|A^H2GMMp2gjEk%2{lw6i%UHNBz;#%9}_>>ZaoGM}Hf@yU;RpxqPGlqEqAeszhXZ-FEU z6H74oR=?~kcMO?7&)WD6yMHjp=MU!eAL}t?VHTim--2>%t7zn&IJzkMKz%V)gY*?m z$g4Jm?qqbFBJu9NJ^9z=v3Tj`7P`~%48MxSTVRQ_fl4HpCswA4rgA-I*8Mhq3n$7j;esIFSA2^K)z!^8T;j`=e^Zd3Lk99Ypn19manM^Q0M$b|_?xV$wDsAKEj7a7Z!|rg)mX&#W*Aj_n_H!kKJu8!HHvhxqu_P6X^lxsx zNkd&{YM~>WS78RR+@HtWvA*^%PGeO(aw;>Vm@Cq&GlO7!_Sh(%^lOywd)>z8#63Z! zea+>iZH=t>P7^1K#ntFUmV&q%v1TJ~phRDefv200vrR1An;C>7mp$PotH)z+wiDO6 z(HIy@ONw!lFf74jWM0Y+GjEa?HMjA>`||msFHnU4HQsYA6NgINA4T=4m`oYA= zgw$-r1ZL4Q<=$}>{AYSMTyl4rU=s#w~ zVv6`#%j-jqQ)HlQ^dvI5;#43R(5~X3a(grMb+p41NA18%W^O{C*KWrxiz~U1l=isi zxKDI7>N6;&m|)hgv1Lt`D&%K|sR;N@3+uaVFxO@_hDqonVJZ%i7PvM!RbS5|P5c6= zFD2K?j0M$;&9Hl)EzTzj{7q%MQ1gOyc#wS)mu%DlN7PC+8|!HlQ%NvQ;qBOX?@RLG z{Zs@~haHO7ofvLzaiIJHap((*djldy3~>;*gQiUq=0dds&RlAOi}O0+UkkS5Ve^~O zveOYb`-dlQen}tyv62d19i~vsH-d>S>CYP2ACQ+0Q4!V$tVS$9i%ZD0V_L|-zu3Z4 zJN$}jpk57pLOmh>lUlu;S`4Rt>EMNx(_m6x7PcFt!@CX9(C>*kwx1e&0TLZx{?puwb%AN4ze8O`1Dvi} z!1)eMM%Tv7K>ohf${ubuSW&)`UK?2eU5(mh6&0uTeb_%gqUE2vsR(|iJ-KHYrkuLL zXrxy4jCw+f?mS{?NUTGP@=@_nSo~aowP$s3@UF*@_b7=UJ_Y!7DwFw(9rp5HO6`eZ zqg1nbC|w&pf>}LgHtTq8hq9R?;_gxr8w#7?nVOR`rp! z{9{fVujNBp1h#?PgWbz$Y3RZkvOgnxGWWA271LIr(P83N-Kkd&YzsBVCo+b@p0h?m zj$0eQxxI>D`9UT;8}5fkH=L%Jo7(ujzA0$Bkrvxkw-GJ=YVG^xF6}FPnL@D=obFjafKw zfg`;(odYSxnP3W{+Oflp!UyOMZ{tTFD?uizce%3`UdaCpsS6~1f&sN#A-V5Ch)vr` z(iS$*Ym---4U?lCaNJf8G;Ic%79aAMzsP6vLszHsUkx{5Epw^8dPc%{5X_*mWeO%| zgQBBa8-KG~G1H0MMxS5!(kVP~Vnw(;oEp#?9-RRAhNpCrCOIB!UJu5H(Mn_;y@PK% z9?t*jhWSx1JMm2(8*tlz>-0yHOSMi!FdFwyld5{2B8fCH`!;pp#&$c%aIxo)*e&SvBm1XYCorXgzNCKpG|K zBfUC(38p^%o#IDwy~4GOjJRzM;YRP?qg1o!mExTyVrC_NK#iZBpqo((THWtG%1EiC zew`z|7GTd!*Ofhnl%Qo*_ff}bL~C=e0&$HI_@b+luI8R}jPfU#vZ)^xW2c(1&y3pm z)xjGTm6O)Wx9*?BMXo1rV7i3MV@F3@eT8pylIp4uIZm~%lXiskEXD0a?N5h997>n)*x$z5N`i3803lgr7rBLM z^OhOq)xfs2OGB@R?nK2GgYZguHN6F_rPag}%$`G=6=O=(vPbk)6-GucP`=+}0Hcpj zqZrX>riJ0beFB;9Al59RXNq_Wh^IA|Rfq5ne{a-(Oc&g*cPW(o=zyyj7p(j@0{a9@ zb?6n+Y7P<1%|s2w{l1*{m`qin{Xz>AdF>GTwr)6|G>?3wNmfM5Nsbyf=japnUSgXg zVno}V$&X_3xDS09^V|lQ61*G!oY%mw3a#)an2YEBmmVj5Z&C&@)ERksvhqE59yXe40;aIBg#AVd;f0`?0Of%PF!`SjUS84{2hSOf?;X~sm@m?5G6|;b=>e~K z6OYKViS)BmT5pcOa|@OKUB!#L&Pd@U>2N%uDpe7aUqsxLL@})CRd_RJ3y!(_mx=H7 z4TMAYVfaxE>^QPFe(FAuY@}oq^I2MrKrqJb)3SAsXUJPFsSAO*m$}28=OS-^Z)#~I zu13_^h?8EccHall+b)0QS6Z`KdpinSF5ik8=9j?nTm}5Dr~tK1J@A4--SK z?V(@6Pkl86lga$Xix)v>-4jrsZ;R81^aO13f?|xM)f5uU9uITxKfm9~pD)u88ci_r zZ5)oin7rr2;qn%9;{UXrL{ptC2mhf@=w84fx1P>M1uS!fflq8WZtqz*b9_3;&ZuFl z)u#AH*hjA6e**u((zPiim|>?wy*pTbliOd@5R3*`b17H+(57PtxB}9J5_L9eC8Z$F zc!(Ag;#NI?YoH?X%%W!QYtug7_31+hw{U~y?j*N;a1AU^;dx!7zPxz8=`1}rp9tpM zn|7qC0y8#>fW4?im>G4Sbng4M436jLg_1?mYVxvr1*;X)N6me&yalS-_0lL~X| z!zQ^{gcMWd#YVn3O(a^jilrejV?`YKHP>n7YjTVQRhPf;a#{iMEVRJAG7iFSRZC%J zkmP4mB7LO)5{&IHwE^uL)tK?68o~_2)7&cCJjK`^R$NF_HUtHyf>^T&sja5P6w#f> zZ%rmOIStvPCLB7WEj*5}#D1U2oX$}jTvIy-JYTmHevbG-S7RrAJ+;zQRBj_}#mV`q z%-ug4!i~mVoMKe2vUpBs&ROReG{ACl8sL>x@;*a*rGFZtnlkNA-* zT=C#;k? z=7k14xTXuo?ru|t+%;gV$b^?mT)6Th?}yLUnIZkMw~U$QC0estBpuit3FiH(J4Er_ zDj)evLzovf66M;MvyP{?D@A3>r_*<7`Jv?}>3@!4FIG-tj!w~n*^vk7_vVUJPje-hp?WhE8)H?Ny}vaCpQVWDHgO@dd}Wke zoQ)E#j*Fwo34nMF#cnAC^ye+CF1|-+qi$|Jj_Uo@U`oJv{QHtBKXk|nd@HXVcehvv z3|C3EIYCm>%Zp%&f1b{cCuSy=1d~c~pkr+hDH;#DDyLhwhi;wnkq%o$U9Ci`W3e=} zd~-3i&1rKughpwQn)T^G>>g;(hfR&bc|M7p?=L;jVIPsvSTXDAa&jf(f|>vFOZJPw-{m(oGzG`k)!feKU6rz#6-sl99+2qk z1d+Xo4K;D+5$$wEInPMF{vfaD2}gHsz)=M!apI$Oc;tuUTzSvUc*4gDF4TM%E;VwZ znDx@*If-DHAyXCKca_OsnrI3K8XxeRlM*;oefa%Vk@n3h(ogN$*_x<7?V79 zAB1IYft`0RK+*0}*t{YJ8~4{^yX}p{Ih72rd3!f}b1kH|fFQkWW)aMVupf$tm|CV6j8p<&(r>{=cop;ck1(s;MeIPzoZOVO3+KwY@y*an}4^e3K zNxGWL5+A10J>Io?4<0+y027WM3s=#&)T3PCo4HD{W+Rq{M9GL4 zBPvR*M4e4>WI1g`6nFm#3BAcy&|@23HSQrA*n!v@*k*FMEgkU(?Kc!tES;ni28 ziyuMQ1_={SCh!7RKLMQ^5+-|?0%rI52_G9t&Biqv-?^#>^$%8K*JyPz2j3B|SoDNq z^rfB6S%L{4IfRWVUL{`vH{Kjt zroKVk?o7rx(HeK3xrVN0i1edn6U_GZ!`NZ##>?+d)D%{zC30~O4=ZO}*@VO(G*J>S z`q}uUl7GK|jAxT>l-T+fO|_q|(8H&SU&H-wTlktOt=#)y7rwA2g6}cE6F%%G&EIsC zHc+_)GgV_fYqZEhUeQBSc=9Jz`PA8%-_o`piP2#`AIQeZob1=cP*jqIC+eZ8$b!^t z?q}=ce%eQ1$eOQwK;Sh#b6zfQvZIQ>(b^B!PWnwBPaEk@%O{wGeW7fi|6T8oVf31d6eAXhE&V#<^afW*L`K3bD^632YRiIwQ7yCC4^F$me72!W2okPcvCe3q zfhM03y$|`3s-SbvFK{Aj3M3wggb7Q709W|XVoF#*7Azho$9pC_A#UVxewD#aUQQBC zVuF47X-%84`9~>3Qd`Al%+lQe{$Uz|CkPuI97h23bOOBBE~zqEkC znuEb*q$50=s!c_GY7=jQ`GnDUvaug?MI&Ch^I3Ogb*Q^i^Kgb-xhxtR*Gg@oebNR> z<%)_*T!1#~o;rm+I6^}xZdK=OgtJOJ?b8ZT03*(={Ww;OPU|_t@;Vi2n1LJQfGW7$M^DGVAgd-QFap7G)Atx;s?Qmm}tg0G~T(kjeIZHDhBP2{Gg7FBq zVK;u;&d!S05YFv*BER?gKC>(^j1vbj#i6CL{lC$zy#wIZKN zZagOzh{Zye$}MyFa(pt#-}QoA{r*66amQbQ<&HaX@SWYDk#onSl%{Z$yJPiGs+iNHLd8C6s)L~nOo=Q4;K!T(ehm|R^0I#Z8A zG#3LoiF;tcx(X2ep-sQW;zspLoLPVpv>jYvyU{F2+&mowt2Nk+@u9EINa15V}7-$iUSQ?63zZ0+c zeu!PEafYe7d!Nld`~clDx`PtlEW&0+b#yiP5@smDbUXAwab|rdc1F6U@FFvknZK1q z11=5b^N8j;Z~X@l1u$X?mRRlyA_a6FaVgOc7<%(opuJdmwt- zi4jQ2KQBY5YaE`PX~Q}GvcV^cZ$YBD8UES67v7-16p!5(O@FjIQ|V_dfMDiKUFdCQ zVCdcDkd}}~YLq4yyF!=TcD$${PVp=S2lM;1nBwCoO%sW$5obKUY}7@j7@azKbF|o7c57xFLs`OBPd!RK;|1yOayHTPwOVVE=Snf%1HV+}_Rllh9hkHOiG1O$*VxuwdtbTt8|NYv}ZTB;pfbw3t&l%GfH?SFwM z(b<$Fz6L(IE3Td4jz>R!O>cn$2@_2)jqyVE>4@v{J~7&Y+wE%9tJ`7p=A{EKmQ=-w z{OF;D|2Kk_J&(+>M|^`M_e}WmFajTTh-W^xq`}?Dbdmr_Tou-J!_^}r;DS{XT}`@# z*-0>VcfV#8&wn7#_@FIVhrMB@*%)DOo&0xf%}MBg?QeJBfslY z=Y#FC1}% zjY?!Zt%7O?#T2ZhRFdRJoMFZDjriP%K>=c5ZQYD$Zc)W*-p~3u8EBda{Tlwlw2HrQ z)cyp|e*ejd2ai+I2I>UC)FfznrxkyZ&zUF_>JN=W^4q@Xm7N!dYYE=nH%5p@o6qt=lCs>>em@3{ulx`vY+##q90JqQE3D9fMB>+F^ZOlI!y8o znb6InBWF0VhMCatQsLe^3N$8mhRv5n1V_MhCg!^y%a6XPdyr(SFL+QO4@CYOa z3Zk4J%10xkzrlodl3%5C2b!vC`OGp&^aaSts4DYu+vUXSN!&E}AF zU@sw^sU#!UX;T9N9!9M4=LwK!Kn!tjp?&l2JT%XKbsj+|K+qHz%Iz zY?2!*siU%p5i3w$n?9q669>`WAzIM9XC`j4e9w(IwE{n@R^!5z`jC+xLszp>!n6>~ z?fx2yrwjC%h5j<3_<$Odnfa8>ZRjZP-0GN3SbOhYy3?_?yn@B&W~6j&G}2X6>{nyO+8OPb@R2g%r1e%V zYkrE-r2B0}jDaJBXBk55wU6*>Sveh7s0b;BqkC;ge26XV+p>>rm@@Gd{S~;wq2nA{ zuo+jzN*Kop?i4dmdJD8Cn9RfRiq&tmm?NWQ!qcx)xnuU`Ts3$o8*@Y8dZ*>k(v770 zt$j~B?4qNx&iN?tu#JSRGakUinuV}3Lu$m34T8r%ttMd*=^>AZ^)L~yIz0=G^ zOjxbr%-0sV-&mQjWnH8)*7dt`Y5!47m{STkWL>1`abodad_#+v0{`of^57(RS5~5a zzuh6jEdo3C%~K}TMdGWPrQEG|*N{B$7rizi(rO$C#@OnyVtoH^^3q{4A>!#l)bpq( z=io4j5k0yJo)dT2?-g)w)Vu#%O{bDK5YTiBUSAxJ>OMYFdN>E-xD<7+onbWg{~W}f z&_7A!ZaN@dn;;3}LNNA|<|?+%`!45vWrF=u5ALY2o$>4bMfqQ2B_WukV3F8^+B3v4 zo>ZU;e9P$@I*+S|f!Dj?S-m#kS#?LzL}EjIS@R;thg##|>$50ksD$w(n0<^rJFe=j zd6@R{}%(k*Ol0Ovy7P2gN92bVdwle{XvUE6Yu> z$?zB)=~95M{n>&Kj2_R;B`1cIqf049L;9>?g4z3XBzxWCsXSq`OfU{iQu^wt@sZ|6 zoG4TlQy0b3&?}#p5ZNgYl19Iz#S}l)+u%B?2o}A!$7f+XK0LBL>>srb#~pvnsrcGq zr||;CT#`Q0egwmm^kY5ND&#!~#=GS#`ZRPQ$Gv#Tiai3+LQljDy+9n3NdHE}q>(;a zelZ6cL;}BlUl*LTZVk@7{2K**3&R_IHgMbW&2YK*Q;O*_f$nT35KQ9DZtTw0m*w>< zWCA*N4#n55b=N>ejQi?kpam!Iau9%1s z+eD^kNH8i{jp#w#qngysoXqju-D|M*VM{o_WgkrDHSq3TCU|(@b&9d|r?s<}^!}`lJzl8bQH%4qqu0mt12w|SyzxYAA`Q@nd5Qa8>XXSUJ9xUs|UrXvwvO zIp(c=z@z@y#WRUwE=bSK9)dZTIgRB98_Qd3wS~~Xhx_N-Xz}-6FGuwbMUXA4hDcI4 z3Er9k1Cq``y-yA;rYzll7uvE6u?`anUSsuzDUDh})@}{qm{U7pcjOpcXe^lkt&lKD z1hZeGAIT$F>%A;rTL@yTVZ(s!Tw&WdlsAb)?h-kVWzQ6-BDSCIv$m7i_fsHBM#RVS z###eBx=&BYLaKu6$G3b|#be&1xRSTFB(j7lL+G{9mtHof3FhLXG)2FMj#L?Y zo5%1PclPraOSa+@o6ISuK-vzb5ll?fV#UPz-HP7iL|`$+gsUsw&rJ$&rd~s$0OpqA z5a@QmiIj*`fem2j5m!u)`@Yu&bH7icu-#KRnbt|hWyy19;{qFQfZqJxTb79^Z&!-5X{3KUlp^x9NE{=+QRbA z`Yby(or~-BUKvYFv&1Tgwt*%j+H1ld-!tfqjy^4SySm;2=sFhr|L%xd??j^fxgDUW zzZpFHwGdfFY{ATrO%zint>!VoWHz^FUw8FlCmz)nW}n!?jT-q~>2T7U69>xjj@3X^ zp*nbdHHMfJCGt4Zp0*;ygtB>SX5vEYF^p}+QZ!_SDJY*=0UVu%p6hJEx!S(;M|&kz zIbIP=U2`|~&By@OpVt;bwv6H4omA(XPjBOVR**s$xdp_zHSMuoA=RJ~Ef{1*U!7w3 z$)AbK@aWUJjPbVlXt;+t>>hj*dxUPlqx)~h4(XRErcT0?5lqZSJ9hc^xvb4sZD9(2 z$FyBgQ`Vlz;G8>GUp&)ORH%mn6->8t9xz>tNU6eyc@zO z;|yGt1Gc(QOu#VGR^`&DBwjQ&Grp7w+k{eD8hY|06hC*}jSkOACWA9FtgblVz3`Ae ztXErw2lX3AF{aYXM*Aw!s^65cwhoh7Z+{(OAfExvKk||831hy(f~1p<_yGQ9=cobg zs?`;wXOKmIG%-3XoP^gqe!hfQn^G8mzB7(9u)}sq##ql|6`oVGmi}m^(vN0LFulTU zvb{V7;A!QS9{94Y~m$Fsiv+l^^yvd+VIHJ#()=( zxKx}(N)17&pCKsi16_@Hr-@d_BQ=8YjpGB+0=+(vxUC*sx47Uw6W#Fs!Z1AJN;<_@ zOP@6-f;p`H-uw2=UD@WLy21|+FaDO^IpqAxNiv!t1I!M8GKogu3z(j*g!qD6(CJ(S zox)2wwh?z)p#nYTaq#D@8FuLS50Y;h;2Xz=;zO@pDdxQNk?ut>j+czQW8S!UudC4& zY-g|FHmGh#)=5L?YQp}J3wago>2Q-mz%yj2l1uqv}RNL zg7`sx&W5~zI^qRYL$A%!ueFf(g?u$*7URW5qtPq3Lon4r2Vax(u(3)9hqm*=BhS60 zm@sK)GninOl`T;Wo$$}wI#o|VQ#{zNv0Kq0`!_VCZa_mBL>}YeY;+?GxcHR_VOS6y zmGduWfbXPsko%znM&p!UtLB8dk zo)G+bHQIB_1)W?J%h5zkBJCATwYM#52Az{XAfHuI6Cgh_XJ~Dz!#~=g%B#%Z4GQ%e zkf?cw*dJ@)52@{W9U~)N{19A|9?vNR^Zj^5e^(eNAJeQS*nd8V9*=5dCY@4OiW0?a z66-cVagV&m{t_F#2C%f^Vf4-h5CxYLKWFpy);!6k*aV+U_Q1XTJkWL3!j^V;6Fbzj{5P(JTZ#o%EJj9%_ihj1@H*u>)QHkbE)Qz+d?j{5uK| zxQT>5x1J~GQWYVgy|!>RC>DOdi-6SSk0GL)CRVZ66$TpoqL^>eX>BpV%s-s$JuWX) z{^7NrU})B&JakbVT^rF3U0|+(@pEEp9FhkUZ>iwSjlW1Xo&d(#g^+S&KWJ!Z3CE`z z3i)5JgKb$jG~VPP?1~CrTxlpgE|cUuPSR>t5sY!z4)1?EBjmmF^n`_#6FAwC+st9V z5JpWi5fYB4($U2$3sv#AHO&;`&~TLq$Ctsq!6ejf-EV#wTL^oO%!eO)6mYopCz%1M z=JXilZ5tUXzn`rqOtGBFIPpW+q&c1_@!kxGUAcuCp7;2qiYO6N+%Qg0uuTo-w%vZseyM+erdXOm?mr*u(N(lS4ZEKG4d47ZxZZOZ?1?Hv`|xDu z{vtE(hqWqRa!(E|cW=VRRVo-Sxucvp%9rj1kW?2)B$%jS&%Ct$ZI>?@MxL9E-MJ<$ zO=NMj2u{%qdDp|7in;7f+&zYWirz={RLdmIi)yNf$aB zWI@bSP29FuVEdktPSWL4l_Qy8Hug~KpXjqkK3YXjc*3nyUKpc}!j@E_Ue~ix>bF)T zPOt92qmKRMEyM|ig;XgQRYlm${ok#0SrN&CI z)LTm>m>C8-id}AJ<&U#;h4ijoN;8Kw=%3;%S}uQtQuj2Yl&HIKW2y!YSlR+Z=PIDr zKs`7#`YJkhR2^p5A4Q!5I%0$2szS6~e6B<9g26-%qx~K*-2S2a;pj4TAqhy{!)h$`4Lpr(G2(1 zNk=d5Cc{B96KrdC0x>!_vG^AFCh2Tgg4y<`R534?Sg|Uv+FI z-~1b}N|l9nZta$PcHkW$0&ep)yuqlsucuEV{CbKpMyG+gU^ z1$M4+h2S;)@srrTXqojo80KS&3w$mpr#r3<38iwZlQZ>w#Nx8G^dL z0ON5b&`oVLcE4T-&7b^n=)4-nqt9IE@QlHG%VS{v#*_5g%#tw81XKPsi9NDv3iIuh zOjtG|Oc|4(nH{@wGZKw7!%p3$Exe1Z?Xb_0I&ipp0rI91Nl#WW^!eb2bAG>ukiip( zb8i{@v?he8hzH^zpJaGt-$*e_q-&#=L44H(AJ%BlM8=BLp*uCNfYbBaqYZIy8RvIo ztA3iCm`SJbNuoA(?pFt;Th2q0JvqD+%&_XIICR@v7-{Z>cOOgQY79eQ)v3|AN6RUq zahC)z7E*y&k6IykjB1=SnxWzf-eNSrJdF%=}*y78auFpi%Pt4IxI42H`D zqp%LVpHhkPC+0GuWTaO6KHUr0>*-+eBQ5@D8`ct~_f3+%_;D`oU{nXm(LT8Q{;6D7 z)_^pXJ@EdcqhRE$G>SPWVeAMd^4A*HXWcSp{ZN_U_jCu}=bs5m)~Hm981d_wV0{;g zI2~L%nM`$`xdcw6dRzSRJs3P+hE?5KVB3xz=-_e-rF`&rB%c!nUF)@BiG^5=2w8t z@dX%)Kf=5}LwU0&2l=najh}OGkMh`b71(-k0mYn^ZUGO1xih$g9Wr7KW4=%(OtSan z`}EqxZM;;etjK!_^;wU=vMC3;bkU*DP2iC$Fv)==m;U+ysu44Bna&gFuKSdCnWZVT zO?bsGoE^;v@9zMzt{W)EM!KO9!GzdWusijaGxp?8izb#VntGFzhnz=q;(Rt(M8^_>gkIN7?M?=_9N1VJ)84IsUpYmx#rh!dwDNOi( zGwi+uliT+$`(Wa1=0mJZ=tTyQPmOfrd%bZ~>TD;I_^(J}dBQ2E+WV2F$|L6^5VDQ< ztpBTk0mrk?ElP!g(??3Q~=m^YvCF#@FOWzxRf|=VbfgQk%W)5tZ z33>G+;l52eH#Z?e9uh+$kYr?3{&);*^X0++%XKi-j)qsU?;t1iJ&gU{3%~5M28!O+ z^53WG3M2b!2x-4Le#xUd(3Gc+#T$B|^u3u*Fs*wX*kk$(V@*n`9dp)$&FR~mO5s;F z`U|Xdx4-Im5YnfZ-O^<7a)McXp`W*k zM{lP8N||u+{3X-}3Yg+{(ehZ5vnH-)Ec1(c5I;!Qq_#OZ=ScCM)Ia~NcEbDT&x5#G z)0oP;hd7$lrf*es#^!rBz$SxwWMQ3w9EM&;9vR=!%{7JBWqxOfxm=9IYcq5cG1K}?J_LPx+wxaDhFN)5uvq8?qH1W*yk1Z`>Lp~1c?(xwyJO{z47$VVG$|ej?b%OjH@24> zq3DS8-2Cs_q!3I->|^hlU*q@J_$T>$#}p-!SUkov|yA?EdFMF1HAp`%M6+ z@7syXRUvSjNc!*VUU=k;OTdywiicG`^f++^Ha{@Hvfx&*V87AT%#&_`O9ZoJVWaoV zkZ@*)gG@*b8i4}7EI@(tyVD}1`}_w`ag~f;Jvjvl`iJSEFl9Vx8dsOVOHF6ozBCQ~ zR41bz2}WG=_CHAI*oLldXop*gHM014{*rEiOoAEx;DWabL^FA2GNDcA#&=G>jNsi3 zHZOqq*&QdU6q2+QFB72tLK<}$5iy9Uiburv#;Y4R7}WaS__#Rj;`AjE^{k+quy4#0Lemi@V!1B!ulrW_P z<7-``=uH&E0;zQ-y6r)gUpn$reEK8zSYm0o^a1$v{X!cnIc1sPne`s3RGvdNyoasC z5BkE_LolN-3toNy0sro5;;ZNWfNY&5PEfr`F)ySa?GwSosn;u>hmT>>SZ%?w#FQ@_ zU&Ae1I*oC7`;IhK^1y$-gmHg)3+i==(vD!nTfoIm2b)KczQOv>@Z!4#KCJl=a;wh4 zrD$`!SSED}S4eMxdV;ys>Y_M3*^{wXXbWq%9)Xnh?bx&J`*I<_Dj;J$5x{o;2L20Q z1DBi)nNL4L{0ZU#K?0tqdlKzxX&DPhBe8dCUr4i3bw zC2QtpqPJ0pyA{pIEcQ02{xZbtttw%{0)*8MJ*1dL5=QG9$@DVqAWysF$o#&eEu^CRKkVF_bMFn{6}$tRyRWg_ou3)Qo1&{!^xE7R=7)%w-ZVZX@fzoB5` zJJ1@COEfoiaIc2Mz2RD@=`tEFfg7AL-H(i-Sh#dT75^q%5Z`nc?AUb)#k`U*mIU)4 zZ?HTtN1K`WMq4Pke@&UX?;rQfdat)b_)qHnP&@VyjeBqXb)Se~njqlgD;RM1E9kwl zg^v4OV3*}F^n3pkn7``>{2m$wlm0p5lyit;g2QRq&XHj3cALoOjQT0(NjGX|s|J7a z#ZgYpLYLFo{hO-06Vm@d>#;Jh9QhdP=ly{SrijQBf55XU1V@W!LEWkf^g8(yY>3JN z&2iRnO<{qnPc+g3vCT?~aV40y2jaW~))dGq{%8y1?!V<62DNc&-tD-Gh<_lK?TlZy z(eXIZhT6zL1&?+oo=_1DVCG{-!i45QFYj0A!^BqDv;92GEQm*mKTWaC_GuKO8$mH% z1heO%NA}H6X>xr7neZ*nkZZJh&&~WhPFb@_1y_`RfUL(V*z#xv6~O$oQ^N%hNh|!! zPZ(IJ3QMx)faQwosAaAi9%Ow8P7msW*7xp+S7k~H;)FF6<3li4>kJh)hV77dbdm`- zR;hC{AAILl_3Xu!4^zWpkKpokRqTJ@0~sQF1EJ~a*tm)8q1AuEgkLvM(yZCU?=}Xt zTcnA*N9-jDOIPGNx6QHKZXsQb@j8kbNic^U8nbO550Upq=CTb`u{MVIZaCS_7{=ss^#2{;J>iq`*~<*@kKEm^~N{WouQZ| zn<*xoU`{_h0ja{wYLrULY zkbl^jdFlTGt^4c1Ek2@yj~Ek+{mQq>=rg^r{tfBcxNf1C4FqFfy1=`7yc@eqkO}K{ z`f!(SD!I)~))Z6Q+5pO2=@#%=`Vnqi)26pT*peo=x4x9Yaoyml<5Tu|vKhW?dIVtH zY;NdKSG;G!RJxi)5+;UVHqAdgV6W*CHtQ8x&E|#Nq|$V5$0R3iYsYrDC8!aOxvJrz zb3eegq$*H;)W$w;rQkmBC#1#JGU=23!Slrz`4&xEtPytrelYvF8rvRN7Gp#)YqrzX zBoItwZBjOdy=?6dnQ+3ypR4Y8n){@0$5~iNn9z-?Sj~%kdxEOrZmTw~pGiJV|GBW-d@R#Qk}%(-9{^{(hkG)-C)Qutonku0Qp{0;xp5jRGKQaLi)1>&^g_(- z*GS@;78=skB+P0gKNP7!7m+x`dlE)#K?wwnsE2+DRZQroQ1Ej8&fL>s4{h}+s*x;EmErgo-{zM%`6tKo8z zHhrhnI{tvGzD~$0GaP)MTcU%r+;IQFC*VQGT&_oBZ*1T#$>5xJ($%CB%=gY)6qhCx zvd=wr1g&>Y@_RkPIghp9lnW1O;rd>UaKWUNl= zW}$MFl@<;;)BpqQ{=$az5{g;0v>g^_ar2*jh8^;76gheaj9E7VO^NP2>sTQz0QY#pKN$XsRoQEN`QUQ2nnNCU?%ttX}#q<2G-FT@{Be5Z+D&%Cl~I7OUB zTV0Nj;F_Cg{cHx`KbH&}`K`(~4(|Awu0S!P5-8>k!Ng21P>fyGPI+&xj&SdR4JVxc zt*rM7WQXWz;7FZ%xFBz$Ml&L2$!<+NUL7i8N&IPUsPu3?w4EmsN;a}I`9c=q(Nxn z4L$0&1}-ikGwtz}Ff7m&=IC94H6PSr=Z3-fVFQUuda_@sHm)a*F}_JL3lk~k3&Gs_ zYr}q8)?V3nhK`WvQmxcGW}&pR9>#oKqlW!_>Y$>$9+o1q9Zal-o^v#C)y9{=xqX1k z)!y)h^fwI#7=jz)gC|)WgSQLg6cwdC@UhCr6mv(yG!e{YpKh#eih;8G1RWtTYMe6u z*KXE*;9BNx9*O@jtb>Hjb>RMj2$soPV9i5yEFKE|NZOxC@o-3KN`v#;+CxjU4<0L= zfaXE#neh5Z8N?0k~$;c{p;V3p%m0JGRkKqZ_Dd>DuTJ z%!!B&Y>HERWlt|1VaN7Ij9L30OmC}u%-19piYa#dPFIuMS_M6~sL|DkWxJne$AFFF z8StLn4pNf)<9R18Lqhl2=zMl}{N7D!NIsEPV?r?OBrSG+e_f?(R~;eMEs0st{UkHz z(qHDKjS3DitAm_r->9fBt>nIH|mExFRp>fD6vBB!&*UnZc;qIQd4aaGm50cgbjZU@noXa<6IQj zB<_cj-=-k%-W5MLPlH7X+2~(FCmhj3kFMsv^mw`x%<>MO6b*-4*jMjm!odEH-YMIy z(9I}&6utf*q!bX9{i825r%=T7=TvaU$~P2~*t!)auZf2V?xvtR)B$(zp9WFwo}leo zmN+(C`q8dRKbo9i42#MYM_zwr+uxH3=3Wu<&ZX`sG|&d+l>dc-qy{o<@dYBkzokE# zeSiv9BTCia<)tun(RQ$7V<0ZU670&!K``h75M?+TbG9Syv)qQRCgcEpJckm@h38Kd zNr7do#br{qYgxoRjB!VnLFOpI;xFjzZ=@LU;33}7reE5~Ea6+a8W%ays|T%ylxot5 zK^^d@nsZ6f>4!cBf}5dT2an`yG%8eQum${7pt8H+wAhMH%(*wg3=6#X@Y6Cd@l^8Zow=5al3 z@B4rAgfyX&G!TW5DYakgUNUFym}ia*ks))(m?%k-kPxLAO%nAQ_AW)GlFU((kV+Af zsDAg}`~CYo9^d{vf1IbaUTg2Y*1fL#y1qIHm^Bv!%woj+8Wk?xm%+&%`)G3;YvLuF zBi+c-hjkJkn?I0q9?vs4X?(f@|LRmM>A)&G_7S|sohSAho{E?Ob)~&vZ<;Dq`lV$s`Z1>NWRLSYirNmcJDRDa924w-igeBmn ziF$ygwYa$3A;=7q798JVf&L^6p5y|SeRN=9<8QcVk_f-gIYGRsCJp^pJVxEVBw#ip zrXs~zI<)Ds%wd%_XCXf$N!jQ@^m|^F*!6G2Y;W{UZO1%96p=f$)xzfXzd|oAUw-)R zd>+T5A>4QW0#Ef5A;@_u6g*X?Z}b^q(!3%B%pSySJ!~l5qZueWHD8-kQkg0V z+Tu>;E?gzyPirm*e?!2kFDU6jQ-RM1lvK&AUM7WNDdV+L!tysAY#^b zeUmls>MYqhS8ZV zC081WOThl@H_4WH8_DWV+vQfHTEH~!FBG0^1XqzR-M--}hi zzfl7wV=1Wj!?W<{pA#_uzcPp&J5LzRjaXqc>4>@JJ}E1GqL=h7E@*DFy~K5e7diGI zQr@=dCpdIzhw5*Q;I-&0l-Jfn;?x$%(EkDss9*QEa~(dGeI|bnw2;efslfgT1J9zf zuxNh~d_Oct!1%`t7zJX&Pd~{#JoZ*rJU*U=&wEN1QZLeQwNzer9d|SnL`<~;w;rYq zu(r=nq0@`U92<}ZXZpS-`6o1>REGCDt)W26A|S4BK6oaHmtOS=0wy0Ze_HO}?KXSA zlPA7xY~PkJvD4g1O~G4v)SK_%x}_cJtee25z8RXQquh%94x6vxM;kGfJJO&p_7eD1 zsK9rf3+p)a1F&si9bYc(;zJao9v6N*d*> ztDC_sQpBwO@EzI?G(h3XW}%^s$CTyXf#3@j#D8o%={6)9YBhsFWkv!#%Vc5S_mu)h zdQ-r>LChG3Q)93FOm&Wp*XFE;_H%w*?oP%PC@CCjaaZ#{OxDLA0>)eA8?^kv4HaTo zLn#ajeM_o;sX&iQk??qGAOvks0WFY1^ePe4J6XVdM9hM@cg8-kZFTM;*X9P_JDIf+ z+{j(~-|`&n75x7(IdMOMzgshS)C6`d%>w4nN(BUDKOtUk+Q{fFk+5rC5UdTn4GUY+ z;i1*JSop02KIasRAO~~0Ui%Xh8xFcWX0a;D|hiQv!5is|+HUjzl zU3hNB|CA2iQ!~*CiG=R$K@fL53x0B`FtB)wfYDA9Fl~rY^2;9EGuWA_sMhAT z)+tF-v&WO_5pU(LL0IGb-=rB#{e}5n4Y11qA5#pkH$Y2}WmsRUiKrrXl>d;J+AE;9 zAOKFrv*77-6V5q!2$&hS1dQ5ktV4%+jm=rQh&lURn@bOWCi@aLoVXm6%XL?C-;lZQl)?DtRTwZa2m*VdmhJ0JnCmG1HY?Kw zj4oo7(y!eeqPvTks;t8;7&=rwW5jS`x;ISD*E;#pG>0}qqL+xtm{|v=J}vN3vkD$d zN}+UM70L1I1{Y66LCn4YxU(u7KK;D`k=|>B(e%D8V2lxyyfrV=BG8}l?V`giNl=wH zof=NOMoyD2R;d@B8~zO)tNdFSjhEGDnBbPyMT84%a^m82)=xcwWTV zw_wp24bSu_}2A znvo8-ZJL(swxupP1UIwF6VP^2f?GmW{Mk|e#Q!#psDeBfkKZBOa%|r73a+_pgZGmj zu<~&xEkniqj$v1yccyNxdz2d z0Qy4n7`}MlaazPAUdBwxt-pmm^o;g$$i@A0mtls${fUFh*i$gGDHs0JkB9Y}#CO`~ zI|7CxCMcjP%lA(P6W>*bE7H-DzsUa~Nqsdz;x^}_fN^+?R{HIDnyzd>ZAT4MYqWvS z#7ZcLd<`4i^q}RuAw-5;2fyfGIAD7ZBA&&=3WEj0XuLB8j4NX9Wp|UFn7}a(sybZm zfHCqHmH84T=A@*$4@OVmXbha|VRRtYq7h>dh04h2Ht={?0oj^wL1SW1I5?{ZjC_;| zkB0?;afTc|JctJ0;+X;_K1;yNMa+hSgQZ<`@)>!HHmAO4vV3_#nnZ1SvLwyAM!?iX z*P-$3A299l1+|;iFn`k@Xuewk9JZP4InWnYJ~4*<9+7acMzcV z7hI=Rz=Z4?urIZO^M(V!r}Qo~dIZ9q=eJ>jYBX%TDQ=)_6#`~GVj7yaOY_^xnEGeh z+zL8g9^pSl5;Fdy#APTpk*nYt2QaezR#KY_p~|YwX@v&?GS8ZY?K(R!+-h3 z4%}wcLU|^xxbBUx`fwGLg|vg|kvEWOgK-Dumf#*?2^Y_2!TG9_u=#HaY^{g~C0lU= zb&wTCvkx(o)}NL>KJk*7l&sB#84Z(PEh}LxhAWfmP3V~PZzs6ce!`Bg4%ijbC|r6q z59|P5FOU#l1w#yMK-tn7%*zz8t0EXiY)*vBE25#~*cf36G;#vw7-CGb!lfVVUNO(Y zwYk4ug)*h9evY2Wej|JEVg;?@2QsZcJ1+!$vTDw;^I-#5S?o>jc

tDjYZ zwzm@H&9mI9Pz>AcE9CrB39gx)!qxZp%D3PdXAIXg`om%SY%n`{67B`WLCgLGDE(Iy z__v6o2}ew)EK0hh^BI%jrOiEiwN7T2)FxY;(jakyN{|~W)0|}=0Ol%DUO^lsuYg$- zlqj!$cs}4YZ2WBub<1tRIsF0rl%9ap8L_ZrUjjHcep9zFMuOlG(Q8M&dERJT}Jpq%17>_yErT5MiGt$}G+^oIEGNT7u(jlIo;4 z@OY34H8}YmJW+}2eHM2*E8f82{>s!U?8Y3~9i!9|k6DIdIbO zqFlz-5!F=#>(%!*&>K6B>$*V-lJ={vI?y`{zFJz%rHh_(%+|dRzS&Vd++~>wr z34irHBSMu1#8knI11gl4UGw&aaz_>Fg0ZjthwHO7KAYLlNu%J&%~B{V^Me_$&w<99 zIjqG8FBU)lN=^mBXr3d+>1V0bK2pXk8K})w^)Q#hZY#MWa*@Qq=@}GEM4!j#x3H{0 zg$CSdLG8dxyo*+*8CH)V7ySi?Z>eXEep^BD&lj+1`e~Rr_dKlsuZq2OuTsD~DHJeO zh*{k7So+aI%Ji~EIghoUGc9`PT(V5c@J<$XgMMQEYNdcloPl>XmCvCu^CyJIu+XFa z5BuHSnDgH-7G|S{aQO3381E7XjSc#oOQ;sdkLK({0aJ&VCj)DwSBtWk2bS7g@ugz9 zmx+(;sZX5DOF09oys(~{N_QAj2AgDKJrzdVPf5-0oss)Sx`RPd5JWYU!e^-xja~K~>JAoyL;OiN z(J@j)1c0+7?ysCU=PpUC}4V(3K*>nJmQZ2M^=?1V-`=u z)7sf}(rabEB!1p*@~uNHAotHS2q`QQ-f5#Zd_!L-OzjDA1AqFJe94YhxOn$dOzy+N z^Ihl+_aPtJal2@LyilG>unvHKcOMHF1H?>xHAOb|b^)_y8h$-ZG9)wq8%qupC&<1^ z-jS!K-Gx2^(~lic7TW~jX&kIvX%3|iqsh?&?cA ziKKNg3NNsQgirsQc3Y2nV+fkXwZ8(!M#Kz5OsdgX*{aN6%nsB*)$4@HEALJrlbYAc zQyzaI18wVxfd&gcb$^AEblZY7NYB?7MC3jz{}5xe{5rk;H)Q=*rvogWf)#2y0+V8i z?*4WG^G^J2oDfs>8w)AUDiWR5+8o>VR35yxLPC`-}pXqixZ>Y4E7$DKyWX zPk*g4p_!`P>2CX{@W`BOsVEvttKnex<2+=qzYeP(ZGwU`J?VQL9lCQ{DeSp5 zh^}2;L9F|I5muU|__A4unE5srWkmZWIbRhL_! z^Bp%(IGQ@GC`4z06S~B!4~-{-4h6!aM;de%zG7cJy$AJo9cbCQE|51sZ2Zp`F{=@i z_;8yn{o-KB;!Rk#vr{GJ7t~CnFbDMl&n$`h^Hjz9 znjH$asrR95cNSWIB*T)&N|Y}R+1(F^w1xT57R5pZ{x841X@{nvR`lJkDp-I{zD)H@ z`gG)HIIL&|9y2muSOU8c6Q@60Rv*<*(r-QPI=q%nmU>vo{)}f*7F#6E;1DqI~3hScA&_hx!>fvondCcKl0doj3 zDG_?I;hN@>F6c7i&)7_#mjY(Fry#o<(CzcfVVgx40h1Sc)vY2X6fr|Wb!2xhTS@}VQ4h`bV=dCPNYLp00;X_vA>?4E>L-0|s#Ee8db&kG zgg!cuqP^j_o0I5{Nm&03djlI={qaW86CMueLkB)oz~lv@rO_R6pB8}_xNag-HR~_g zp{&gfn%A4{X1j=Ku^lhbS(*!0UZt>j*DdIBwF}ihje?lxk$7^$i+r;@=+$o;m9MRZ zzDGyHwUyn$Z}Uv(>VE}n<4!>ecV1WmAtELoG4}r3WvZBl^H^A)naO=kwWV4l7u@KS$u8cepT`qvCHPLySey zQCa93OG$977AG~~Tp+nuZunDF$20SVn!3hnuik}Ul zx`)D{Hs=@XIL4eyxZRU$C@*01haLkPiwgo~y@>O+E(U8e;fK zzZD1Z(h&ow@g zjn?qA;szV%S;zL8`jWN1v4_1lrV_?jR0*={%0lJBj zLZ!E`aYm_ti4nKzjfi0vUvn;*Vk9ANG`T+YCx})22I8bWpYXM(l&hlS%r0TV91p;hi+luOJ*=h@+QlBh&Y&iF-{B-J5@ z+-HgTr1cc`P~#Do|81sEGp6U02#h4%U_|n9@*waWnWCZz z_w?>Ubl@ccqahwVx+122Yniikp_62HxF+{CW2D5oXDYFn`9{e4PE2cq+4c>DZ~VWT z`KbO6}eMl87TVkiVr#Vw^DtFbos6w>^Nq6XgPCu{fHMh%p>DfoZSZCu!KH z$=xd-ruetj7%~i%6gedzp+_(>c2bO>#@xC~B@2jYV9 zZSF# zac46HF^Ma`J3DHemMqHFT?GB+s-u502N? zf=c~U*k3i6-qw8pxwKrs91t-}5mS6t-FfiXgOcrcG`T3rA$HMpM2qzCliji8+vI|-kRlA)iBy%(@2_a%V45=BN%$h;qBi(^bPhLRL{CAU@XKV z?pnmCKPb%lRlQBp|Dh(QvD8veXzRR|b8m=&PxDDgRYf?US zvF*)UXw%Gvr18bDp|LCFT@;6xpNDOIhCvOx9qbbe;luNSs{=Z}0Rk#~Oz$EZRP zx6CLP7F-C>#0!>~B1To2I&y zk98Y9CR*~`PoMoSMGbnM!_q@#S32YEOd63qmOb%Fi{&@BHsTTpLQMF{9ZbWenUcuy zTAaLRUkEiB=^NmE(xIv5a`xr?6eH5)Ic(_=>cjQl8 zqfYtQ1Gi(J1dH(Slmh6s7P}?UWhCj|BX-FT6Kj~agp zm<1vx3NcZtQl?F%zr+xCHfPUnm!}OdWanKtr0|&%3$EEe!722;VAjYd$wpWffU6T0 z^3mXA$;O|oXWJl7w`D4%)}lv5*caG+bSSmc8_50pZ>NCq5MMSo5OdZeh8Z(LM{+wE zZF3B_DHgjfVh_~rS0wrd!QzWgp$&ydyjf$}^cS%B=L10!pZjMA?3nS6HC}Jd4aGyE zX+I6x8SomGoHnHc^NqM~CeH+nlDGsi5aar6H={N48M79Z_icF=?DR8p*@fer6h?oS z<6a;UT`pgO>)cNe@wgmY74Y3=ksySk#`s0B5_vQ0`8XF$Ow6gr&3mAD+>NIG^O)V0 z>my+Hix>_uA3KIJx2BwDI)7?$16}eJMqMRrVB=tgMY{!zJhmU3n9-;6%tzSuyF#eh z3_iXSj#HnsFnul71~wt zAvOs-(VFG$z9&FObfd2xg~|W((iEPXMDZ=~6ftNm%QVcm=j@Kv!GwHQHBhQeGri<`6st^5I^$u?48q&X7 z5oDIWD)7(E8*wz1h!pYTEn_KLZLSj9e6+cc+kzf7Ek%4~Sh!a-KcbU}+ z;-sKM9P|s;1PhfQGGw_Xpe+w^9(fY#(~anf9=~DBtKM|)&M>0)T0_8?h@+`R%&exAO)04+`Ey%{$6S2LU|?-PKpjq=0w%-PK212^t0Ksw0Z9+XXGhe}` zBnvLJxWT6QG4Sx~VVbjiB(+dG3*W+h`1waP%Ysr0Af+#YMWL$xo2e)-b#U-%t+zv>9nE=3g6=;F`6&)(%eyJjfG=I? zC)Jza&{I6H2Z`52rikhF<|%W9{UN)ig`LIiI?kp23l!4HHWK z2pA9JY$2r1%2FRfDrP|3EDuPSZcg2Ne#2D1pU~<#i0-RcAWYh8aWwr9V`_VeQSMWw{L^?l-82l=n%UfpSKI9Z#>)(|*UY3aZg?Qjc_E;q_Xv*Y zI@0~kPhi*Qbnxg@qLc6oiz`6MP8^LrVpi)ebskhyDVzRSi!*GgP{!{CuAjdQulA>7JL5Cx?LC}s?5Kbxsn;Rz$wjbL6OXvF zMT{e29v>Yh3pKth+k0J$d%ZJ>&30c1>%-C84(~g84DUpq5#0)&E=shlBU9-2j5?hI zMe#jp5wWGKBCdg|@j#kZ^c3_@UV~EWqoBTpArD`#ATo)Y@2!v-@_241d209AiHbr!OBs$5|{txT`AD z$7(79Mklud0&d&~mD}p{^;!IqewYrsrMh(Kq4&`LRXoI=yaX{%a|Fy%anj}^rlxMZ z?A}Q8vA>^ca!ITUENcrTqhIC|J1P2eovMNW`CY*?C9*f}*>KYAU8`YqS3Ke_d<^M( z-#|&PHE?OiIWT^`8J4(jhXnz5peQ$6z=Vq{Z6#ttRHCIV@6R}oIHAd{J2nfR8O2!Pjhf`w!kCoUhqb|BQpaR&mhp zM=QG%75(Njx^fO3uh~R&!1%ESufOrHLoB8oK+G_$a%atmP0WPbycvDI^TtzBa%g%z z;X5Q<-M)ZZY#fFMwZrCrQBA!08dRSD1_6spAYUa8ejdC43nq5sE>u}@r<5(Z5m$b( z)BAsbn5(e@X0BM}@JGzKF~6M)mDd{I-1k4(IU0t%^~}y~f;y%w!d=PpBDpG^`hQZ1yX*4lTuN^ezh+L$Ul2f|v&b zemUQ@$zfjTYH(>jO7ahZDzJCMZ<6)#wSd{tv=Y2N-iGJ%6Jh;}SwhW*$7J4Wf?sSA z=CbFop$>o9whtd!?ZA`l-Lx`z_TjLA884O}E+J-h&Ozr1;h&i$dFouF^qsp@RsHhE`jF4ig9?P4~kTdjs&olBu0T39Jazq9f+KhA24Vfytx^wfwJSXU#L)Sb6d)c!S8ERQfJX_~QceQs|7(;)8CQV_## zYm#0((M$4SmO8h@Wi(sNo+CB}I|XN0H{UPt^_-Nfu^bLzwQ5khTu$zGPoEKV+$weYs8A37ob@3;G0R{? z9O|L=9D_xF4203V7PlO^h?#Kyv@GV7x#U+5b?!uyM6Mb8pJK148*#Xm2U(xKLe=2s zf?LAupfAMuS`*>*0xqNgG>Q*6$_>O+KU(T`pf6MnYrgFafhxye29^ z%)!EF*@V4D5_ctaZe^)0ar>RG*s3rkZiU&HfcYKtmbZ~Ge>_pxDgp0sc>#L~T-aRD z8P%U2#nUsti#eDSNx$X$3A>uXqwc^rPV6j}i<9;eG2a>@WY4LVMCH30msJ|Z=$iN| z_B8Zo`0_)@@)lS)$r`q{&4!wpHlSzfBHXZtY-izHFKcRqhNV2_L&`#W%ut8g`Rt%- z!*k%LTdFXc2jX*6jhNn5r(|gv4b0QeYMipS6c)e#4IbP5u&*Xe z@PwS-9dih0snWD#Sy1}7KP@Vf!DI^+>b}ni!allyspEH&YIFypR!ap;lZa_R%#5GA zWc9-fm;p^{oJaa!a&cOyqU?&L!fr0UjZxYgg7-4sXYYXx7Up&0a`08DMolyCK+C88 zbn3NI=w`TuoX_1%9IKUJPF{b-p!*4MEa{+t874lSEr^*G5F`uNxy8KgtIpXN`6;TN z_$iiskt)i6-htotxGC}}1skg}i0W}ia3Z%XSEqcsLSFuGYC09)dkZH~^hbtMzMqJ4 zm@b(SfC`n)bpqzF_}nOEV$;$}Us>~)R7QWfI#>3xFN~%~6qfA^6?~PWc)2p=J-PyF z&_ZXe6uqIJ!P^*Y(43h9mPS43%X2rOf9yo+AxnT|T~+9hAAP7(*geoKHlX|)+ERQA z=pd#}{eqOVCNNttI&8`~Y=iF%!CNpN#p<`I@cA{ij$mn<&-!ljXTcS(Q2SudXV8-b zSQ%?fJM&ZF#mP=cX9_@9SA(`EIneiYc~F!pVi*x)gcy&TkxqHmx0%*dbM z4O3~Y0`tJPh+ofJ;%{S)n9k#;9edP2Vm@hVaJMawu|e09NO@2nHso^>XwOljs6#=Y zPCVwm%Ldaa524GKE;MaJBAhPoLZeKsz@EOQH11J4WIr^Zo}Wh14Ob&!2A3fGHVNWN z8;F<{f%35l170#~w`p*C$D-uD7Wzvjrr8LXZG$yvmSF+3sAHe>rd<5Y>5oEoR|d;-=+wd^&*BrOh=}w^MX&mnB9h&oKDb40<*`G)vHPrZDuL(>Z3Mw!blgd z@_MM=UJT*G^PoquA>|WeUcUDw(T%o>9%mmz<>Lcjv__e3Fc?K2dHhz$D$gqTm8L8H zHj@y;-C>=NIkquYi!`}UU0#um_md?(6rGC2=BaS{f)3?#aYNAC!Mg|(%kU)qPnD5? znQ$1`%VpQunuB*>weLJw;?fC~-<)V{$`f|ft1B#z*(_paBWCq$b2R+a?`hA4lXUx5eVSz!3m@;^W4otx=Tg^)!F6sN z^c$r~ubBchoMgs5TUjq)ti&a-7%?mFE@Mv2Y-L8?*W|*rjuD*!gA~dho(hAx(a=6w ziSl)U@JFo>;ECQtHJtExs%$<3TP}WQ9n9^xfiXewsA38fsA$k@G0ybnZhNkDXNQ2H z;%~DCF%{)UnGe0cFsth|IdeO6BJcE5T=?Os2zLt-?$)wGiUs*7-(1c+T(&7b3ucY$ zOFywcFAU(UQxaephNQag#)g=kBdEWFC3pN=xq$g!RedvJQhfXwH>0P_a&0Xx;@<)} znLbAkCV0{ zOP8G3{8r&{q8o|77*8h5=!=r;Y(Z+p>jikvKcPj(jsFudI3BP(K(8_m?)GM+KdRTA6SK%+P8)`}onm5u%vP8=NHb&wtt^zTZ zzW11W!P8|6IyJaM8dZusy)Nw4#|pCJ!VWN6?FkNwn_%)?oBqUNN!B1#s@R=|kKqB3 zv8NDjL>vKarU|pY-Qo9$T9}orO%E3Bg8$sa>s5t#TFXbw#kZ*pGv=hM0gqAbEBY&J zzdcthvHU~IFrP5Z_yRa6U56fJUFb$j6&m#*MKEjRV-IZK6iNCHY#{m=O?CUFJ6OG` zhAS1yH2x)~$Za|%Ea)HNX{`(~L-kXcU*9rh|1Qwr#_EkDFE=Q$g&hp=x41d(X<&LO z5e!qi31`pdf)r?*oDHi7X2Q;XSIK*0OW@sk+V zM_`S!KYW<^8!ol_!XVRX2uv!5^&AJU!oLVBt*>|}{D_!OS{s~)3{I78JB$0Yjxsj> zK@91U(;cF&)T4dgQ*a${4c^7-(RViJ$uTAwoFYqvbcGrF&%^m8IZ)SON`w#fF6Rp%}y=d$dwd9cCU6zaNt#^~KLsQVrX zsqO|evRTB;|5*mE-*RDCuQAkn!vtzF8@p8qRZ+uh0(0-^#b_VgQRW~>58|M z_PX&ACPl}>hvS%A5V8tVw@rmE_d*2Beet(Z%feUZp&Hq0OXsXSH#P3<^1~!`f(@M3 zb;QIZ)T-lX664~*vu`h||4ECstV;s>OXU#K=RTOJ4Wc_@ZK)HUb;ecghO~z=NL4-u zjo$;I-9%KT{7=iFiGJi9S&6)n1ond^H-P6U5 zJ@o7`G=CP|;QEM5U@&4z_r8&;ejUp6a8Tt=YF#Ij%nlQcB|FIK2Ur;_L4TB;@o>1T zH&qVRq2}1mqciBUfVq|S2a@mC!yWx5HoVh{JHB0qYsk-IgCAp0;dimnr6GQ#MRcvrQ zMeN#Tgg4UURYM*}jtFudzO&eFlaG+M#;>%n>jre@D=qqIWe00>d?>ehp*1&cbU9nU zB?pF-iAUTLaXaXWn86v^GL0+enc0ylT*KODinm)PlbKf>2=95%r!G#JItzL#m4MwG z4xZLeg);YVP;x34Ji3|F1D_1(?i7x7^w;H%VFu+|%L}Z_E*8Qk{y&(xh*_ICQ?~AU z9Fu%Pg)7plRoo04MO+4J6J9dHV-}k90@iUAxvv!4vS=1Jx}?Fs#k9RZjB^>}oOzl|4S z7Byo{V`SL^JS-d?*OyG;bLMlnCje;co{R@05NjN)} z#zdIV=P5nm%^6Q(`*Kz+Vg?TukWN;`5EA|bT~EHsY~w_o5BE#Wn`K9 zD$@O`2`sn23gNAy4DNT$a-oIE_09L3-xzOZs}`&GCWC3@Rsi#3~I z#4PDzDBs)Wfg*nuZp`_N`%P? z<}~rRR^dG&13c6_V8WHX5RnlABe^x;{p%FSd#OCcy$AiQ_X)}-&Zk8xJD|_; zX|V1e^za^wSLP4C3z$lA2}C2t{7I)Qc3Qm5td}a+IOYxcQ$C!XIXYFLQj!j*cVYQq z5lTgV--EQ!(@;4q3;1G+P1F^rNYJ4_@BW2PkK@RwxxXdXm${(Pc7uHCj2jrDS|niJ zi%TF0F?UP;$R3Y>A}d~{%Bjh1B)LmM6w${=vOK2UT#fSEL6t4pf?1=RLn&C6Y0~hQ zmtlMLYxwB>5IXhGQB75Idgaz>NWCWk&E{fw7W+ZK{1iuX7crmbB*{3%BU#@ZRnB~f zHT-h_k4!oJOBl_Zb7%)}?D1_KG6qERx!hdV~rcB5{xFfbnA z3w=$l!C~FU@avTtIP9B3jqXpO4%nc%!5iNm_@^U2H_s6><)|<7^-_&=npBN*^0tMq z7|QUnJEoH0E!0hOl#D#g!Mz$<=%OK@&iEJbs$7q{YF~y&d#-@*;S`v(suMDb#=)|= z47CYzqAD$kaA$<5=z1Y8=qkiq*tn7@zdT-AWTwtZd<)pkw+vuzLr*peHR?y#=}@bI z7)haD1>vLa!{%d8p}(;aJ>U=tR{kaMV0I0h8>mV@R?mRb(=BM0GoIF-je?|M2ZYfi zi3j#N#613@&N#Xg=PtX{xv{sC6;91=WQEQjMOsoC9AD9u@;21GlZEc|Lg?922IKnm zqIT8MV9mzB>gY7c&sL#YQ#ZrZs;+dWac?@z;xOElcnFxkBIXBT()@g!Jxgnx&q>uW zz($u1UJyVIg~=2FxRAeC>e8&5JkT+&gAlJ0e2+bb+j~vve7r-O_+=LvQZtAd;;KhG z4bH%6o3HT6L4&@yb4O9LXP$79zAIun5VQX6!?C~YdNOl=sB;rvEK{U4mJyws;R42_ zPM7kr2mEDm`06rL;+I04jTsFYmk8&uTmIRubL=YDc9@pu0o^M8z}g&L>R43BRt~wq z@=Ksu{B5+PN=j;Js?K-cJ26jsYH;?B&tQV}HWK6OC{zdME$c=@@Vbug$ag*R3`$-V z!``(fv~A%vknF$5t{tq!b^9k3!igTJ%<4gZp0uVbJmsCiI1lNVh*V4GOq77 zGR7Fr8M7FBuvFlP^fJ#jv>^AOBL-wAADa|cx`#f9j zvMdPpCNz=P%{G)7HjEnQj^KVi6?Haa#OKBgF|6-aCRo{z>9E(}esV3uSMph+WVVx0 z=@AS$dzu6-2j6_*G7fW#?>!LYJZg5H5bpk!?Nd33`=Aj5je0te`@)tkAAnVkBs*@; zy0^k;mWdb}#1vl+V@7QEW1O)&3oPYi@x~c)+SufzHuYa{`jh{EsU*C;;jW9hkmFqh z!9NB;>VtH)s0D@s6_+UC}v_1W?9`71%ofa@dMa(e7e9lW_%(8Yfb+#H@ zOl>TAHvfpiphP06b+d%<5toIU&8j*j>N>mv?t5p$$MP`vI{7(iA3Tf={hZJCJDvbK z5!T?4Igona8AwkRUSz%2CI~C-ocP-~A?DkpY^Lwo$&3#!0q?PGlCA$e$YPF@x8dkK+f6Iu@9a8~gE#5{gM9k)VY9fE(*0S zL)eek4imkGOcL7I4HEy!gb!#A$oEO}U(bOT`vKjOPVTO@f(1nq(%MlBcdlDQ!XslE zT-$@r*|vo29ot*Lw2E7f)rk3V@-yQX?<7-QrOqk2s!P+Ima?0>M3b%O-jmQi`jC^5 zF60sTJZJ{*&3A=>4ZRg*WPE-+@bWz0`JZ~%nR-4ij-!*8Lhy4xi5ybk!f_7VCBPHO4U!kQK#Y^!vQGt~Yv6m~R2 zk2ul2*IvVk`-5Obuqn-0sY&}*9s55_p7>7Ng_!jpelQ7iM z#At9gu-fztjb<`2yCV|Xt@Wv=iJG7nh_%TFuf>@#>C7phz0Sh?<8^R4Yc6D+>_Kb4 zCqN^PX!7zt0;XL&Nk<@N)F4ad!%q0rZs`-~>?d(dDHLnKB=RE||q{~oT zZ9uQI;niJZnh+Pl%SUfLLFvJd5;%R@gsLyQ27x-iz_kXA(f#}&*h(fW=pYdjkC=7m z2FPk%y2@A1QRQ-bDY2h+tbm99U&-PWlp!p|ERXJ&ATQpCK7Oq(V0bxClz{@>dfPx{ z%qSYRtS7add>3k3D}kgd$Qm*RvTTwCOqPgAL(Ghs1+po!=Q7W4DqN*3IK4Xec{4VmN&{V%Meem#(xBg|PP7pM^;q>G}mG{LrPxURALlSDA6$ zt(CA}lw+&ilfiw(T>*1Vd^{Twb3JgH%yNH_)5uNA+|Ge1;qrcd5WW!= zkr-BU`@IpplsA~Jo2 zQ|2CT>&9;K`5}o_S0b*r9}9}EVIO9~NB`G?skT|G8}tlm1~2@gP8^7tgpyIz+NywU z((1+aDc9u!dfs3YS6+ZNMyz!X6-Uz*FG2b#Cmf%&Ej#u}za+%GbTnmXxh1 z0*CA>F#gg5f+`cipx+fCV558JrPsnq$FSU)6#iJPi3wu--KilJD%~;$55Ih)nL)Lh(y~SfT#P` z2{oGo6I#)_?GCn+I?`ihlj-FBH4=~Y8x>WLcPLgz4JJ|VyrJG?iGWcSF&2m^?QJeM z&$i7{>!FPD(K&3^v>L@Qjmz>xJl6yq`T$gMfvh*33hUzr!qy$v2=4&nur(cYmO0Yf z8sq7N8xk@j%|a1((?}6AbQ1|w_JA{r)#7Nx?~NTlnxSLl&9Wlt@}bIHzkm8FYWq%Q z%SxRTi9f2<+r zKN!Q&X}-{bg<}3KU@dM3M|!eRv=T|tjuMdoh9p7>CbNV*sb78L%avE(u6WHa^gsMx=IJ)b=nDUF;V>^ z3hJRJ?efl={(f!&v;IsVEwQtR#WZtx*XKNJnourahKiUeh+*^@`GNDg@=0fvxep=7 zNSoI&cG~AN3OBPX@ZQ@7t^X;*giQnn_BDon6RaTSmMXQYxd^6*y3!3ddJDT4gY)rp z*e*-DEAJR>syq)NH<|@ZS8)lrAtrOlX!-jDM&A3LGB^CjZW0lGkUd{HN70N$6keG! zyX_xv`u})3^LVPd_x*D?=DElaGA2ox66c(CuQX4RqEbnkY4p%MNQzXFqzp|68A>XJ zbN1dONhK+Tiqc$?G>L}a+IxR~Uw`$_^Sobc?RC~(`(D?5UE}wGPmLc4vUUO6v=nkC z3Fh?*@TguLTxfR$7caXBbF(7h%Sd-vk(dI{WBESm0sL!iKEZ@%*vpFhEtP%hlxJER zcB2G3j=mnBMirB=pc~f2TRl7nCX-8(A69$|)_~LG^)~YmyuADZ5~bQ$+r<-}bq@u< zXLI3I=|w8cEE|R{k;Ci~*vIbz%LwK*Z6zzy+$pmeD`18hIKUwNBSa59h-Oj-AL?7pJj#e^8O)8>+It1m@-_E|IOxO}LW%Nj>LW$0 zwBs#GpYaI1@25h*zcLs+gMT)*JSLi89Ozcj?7ZsMjB zn;KDVU*S|kY-5a>UmLLMhp5>Hp{!>bxn z#|>u_L37F^Sa-M^@b`x>=XWu>+Te}N>?UK%e?Lr8>fk1AC@<|jPB4~hABpYk+N5X1 zip+!+=E%~01@!ujqS?_rd!&iktZ&x4yZ6d%Fo+-qGamF2+frv5xc3vw0csHG)v z?x7ZDzt-41g4$L0AUm=Vwg#Hu;MR2baCayy-gq4poZf)ybAXg4TU_dGiG^~zKvQon zH<}6jXbK3XMs1qdTY0+l#ZN^h@7NaFkW^^nTvX_Q6IVcfsSfTvLqTy2@!+(5z&HE- zGsCqB84%nSj|#LSkk4%+tQma*-XHIV?F!$asN9*F+uvHo{%-8~B~U^z(q-dBw{nf7 zf82%4=L8Y`D_9*KjJnGeA)UtSVq?;f^g*r@*v#U(ISufAo&^pxISWe1oao~E&2*Tz z8n&Am1@-xI_zt;eU+Y~)*DA-*EGCfO1sH;Px52wCbVWw_uH`~TKWHtADoRHI1}c>O zYf{p_t&J;4pd<-l)x`<}-z@SQiTG|1k-=53 zLn%jRpcS1vWLd5&!9MsQhheQ*SUFFaJ&}|yeaiJlnJi-HkXR$;>Y{YWI5HgW9&yF9 z+lOF{Kf27_t_%({n#a5&7)42#SUqx}`27hX6Z0q!6=|%I^k~nJO(bq&agOJ}c~K>> zHJdVz5Rykm^=T~XRgf6aTBhQ}& zx(P z4>ls_-iheTwhStfShtQzbO5td!v-wRh5gM1oyUp~)hWmxg zpUP(_?0vax!TpyKo%aXP!(Ad!dq{ySj1=)n&4!Jwj$JMRpO0=xD{?=YViH6t&xwQa zYQNFsVNTer-2v}eFo-%ag;zg>@xL1-@*`Sd|5$9$eqXekoP~X)UFd539cokmP&BdM zZd7%{2vU8dP&z{i3o710K+{!tx5f%iAMir+&)dQE6V|9NG6k+zC_>OBN1S+QFnQ%o zKuV(r0lU)v_x98wn5DNH#f~Ct(FboK^LAnqr8xOI^)^ZaO=MD#;!ACa+J6l$4p6~t z(^BijE3oaT3D<)4;j2CDk1iSdn;{{>2Ii8=?cY!h99YUH zm9dkS$?wpP1Y>;Unb_1XUi!94k+D5~Ok!oypSE0l0M#Fr5V_lU&ND^xxF&89{szb3 z3-IvAHrQ6V5F&?;#{sKKz^(ZieEUMaRdoz;40&lMB$6b?I=-8zf;R*lMKJ#@yDuKR zla_{GP-G6x&ZkNaYtVDw9Y(&3kAksW3{2j27IvT2#+sYtaH|4QKV%mIo5Ox%ojN!$ zwovHu7)D-DftC~<>^VaY8=bX*uf4n>Aj2C1dJ)X#HMhlgH9Dlijfza_>g^KqdsejV z$wpMBNd$bCGDxgz7975(i;X5LVAgAht=YuMmB60T0!lq12#NNk!^GJyQFB{=Y_jk> z%+?)+vtm;)J86iYw5bF$R;^qdY@sZBXQjxz*gKPUxuuV0pC^T4^0gK<G$?m>XfrW!5pTJ$M_S> z`14pCwBHQCx6UYI@6GvOOVSD~w@RVR*$CU;5#xouM3OYnU4aqKJVW>Fo&%ElQDCn^Ok_Imk}QIg;1X`k z31C<)N66d%-hkruarlVlxTn%OWG~kHYO?3K3IfpUjG2sLg==V%| zUwNqX-D3e$+WbdiRx}E(Ebj*`_OBrL(p?C1%!CCdrg;5$HQfE~9Iy`lEN1CfF)j<4 zgjY|w0?)1dASwL`^k@dcy>4sxec=g**~_oA9RxGI?Uppk*rWW+HUV=pya^@m`-1*x zy+Uf?&!MH?J)+>s=E@IF^VM;Pc`g@K$$m)>Ah)o^#t4uIDq+aWY*2P{)L z1_5pSsdEI6i6xk&3W?I^gDX5gc?if3Z4SqlX~U4m4-l*9Di$?xHJjUSEU{6S23A^- z&Bcha^|TA86>$&wIm&C@l_*d7EvpxIBg-@aY~6GL$_{97OJEs4X^8|AkmMxIdbB|F zUQWOq*`P;)>ZhQe=m@b8;+f+?$4lbTmw7nwbiXW~Mhp{FYqk)Dn@ms98& z-NZF5IsLH4n^UxKlwuYXTfFDW4_?Gh-$hpo>!&}Z75*AC=dX9t^V)N1AHN*%Fy!w& zAM==Of(h{+AoW|WD^{+RXKvY@p}kJbL63}EB%Y&5h+|$0F=R+1(MNne&6&szT5>*t z-cuP&-)Vpkjy1)@*D5h>w>_Ed11uTYq&Kt`M8hK28g4W<_)}*Q!Hh8Vk+unki=SPV zXOeIIG7m7C($TLMg`kHIkRD0G3?IJ(-rc*8*pB=LhpWI$9gm&IO~%i( zK1n*mW2su_Bh-~xSCqEQ3556danEKvzXX~HX7D^i*>PP%aZIH=6Ma&F{ygIwwIu$z zENmSGQReM%+B*&1iSva5xslLia)v9WsO4UQ3m$;KDtX~|s{p-RjHu>ip46Iy;YdZz z2}Tl`B6$zU1@I@Ec7oY^d8o|UKTg!wF3)(2-ct25C(~m!{V2hwa%d-7jnj*gQ22T` z@OiHd6ALmB>pt4M=K>6FbikX|I^t`ICg86TfPSMHXu(NS7~dNRwOb1~j2n;XAef?r z5wfqB!^UrahBP=50Wl%5HKT0o}d)_ z@1kE>9-xdDT?00oh^^VM6{ta@m4R9J4ZUwu#9FdUh#z2#PcoKx=O}A%k8nrN){D`3 zeJl9pvmSORzT-yY&Yx`L$VvB5+%TEb>q@EdECI94-51r}ilQgJ*g<9Vm4L71FTio~ z5Po_Ti1%oN-2ekl;J?M|1e~Wx7opjP50ZsxY+NA+Kq>s?41>?9jpJJzf5Ib=!XrN8dF?S4P<*kNkBnhkKXfhn! ztc*XX=#YEp3wVyAI{y7T6=rX$faf)lP=8LI+d3!lJ9K}7nd@vJt2cF#$>#}}h$}Bq zgwGy&e(wfOGGglI zSuk;a0%do458T|&zX&$+7&C&I|5Q)5=kzSut=V*w&LOsD z(;iBk;7E_hzGzLXW^o8Sd%r@?6hk~};yJu|{YX6CFaip0rlNO7(_y_T|01}+pVRCJ z=6qk9)U0v7>>^fRzOSUg)aEZLo+jWVBl=CsSTEo_P!&~BR#Zr=!W-c1b8Vbjeh?1G zRe`We2X8WQ$9iM);ED$YS0(Q`wgbH!)w*+lbh*KEYR!M8YRuii8nI;6nV58Db0 zqr>oAg{64Jj8%}G$=^nuDd!x=d_7Kc#Wk5Z<1bwlajR#(v zh)aK+fGJ9u+_MSiF#!a#cypQ9{lzNjElnX~Ds!S2$KOTG&2Knm3R~r{OsBZ~n_v@C z8an$JZlsyvfP!>zIz5XBWTGJHlmb35V?ONYu)?wNM!2Zoa`>3f>pGoz%o2jxz3ZTu z9;`1t<}YLvMwZd_kLSYiL`6EIpcqz~_s5nYG;FbX1I}aWxYCe~gjj!eoq;9iI?=i( zchKJ$1CoQg7otXJ;w1x>@y02|(h_Z2LN;hQSN_?oA($((+C)2jOUi?f37Mr)qv_S* zS!kg_0p(kG5nN35v2!|2yazu*)ZhE0M(_Y;yt2k&JI}(q>q2^9#2kA1M-BX~FBCr2 z>)_VEO4wvjK0SGQIL%^~^O#Kp<0$I%bc%2;8+(_?5>hK<$u3D~nS&n{Y(Y#K%lqM4 zl?vD^>jG!6yp&cb^YElz4x7D4QdUyzhCMRIFfX@V^k zlVIWB4*Hjc6(i8T0)y|_016p_?_L~)-yHK`5_0*PO%3mPe}G_;OU%U=%zH!^yGYIE z@DG&yHWgv1!1KfDBT)ENo+}NpEm*9ar+r#2xy?|=ORjB%1=>GoJlu)7-c1_++?-&& zqbH6e6Y69kVhq&2a-$LPm}G*PbY;3YY32y=iXI^&Oc{s%=#EBNu}QM3No%0Dx($Mf z`G0X`A6Vu$LBr5$u#Ncuv;Omh6;(BKx10qtYHuE_yp2gDuLLhc*4WtDjFHZ}$YJdH zpn%f^Gx5zH@z&V!Vi$oDv%jeXm8?yX?9fhZMFOHPS# z8%zA@&Jt79*if!FD)m?_unSt%R~~;D{uF*hQ=k{J3w+9Vqv4@n zq*Ft<($G5tdr0aVgq}=Df}6^JkeM&w_)uGXFIkL?x-5YmjU&IHYX~MF^r!faN1tci z1tGKIPy@A4Lyp#P9)y|<(^2%){zPa|0{5;c;UDquIAu!BTr*D2BX~I!hTS$me=W-3 zM9p9l_UMQ|)av7u*&c{Ju(KEi9@9WD%T51@lb@!P-%J!Tt%`AygAW4f6$Kus#-s-I z-_Vcj0L7fnCgi_P$i8|R(hr+L(b7T`7~u%zyEM>yt!g;`#~n7V zYc@?ITDY1`t3Tis#CzD|nFHL`9E=aNtKjA7r~Xf8GmU>XZwThlA2~_G*8-_IsY9Rq zK#QN=3!*=SC!v}ZPB3eT2Y7ms8*}pEq0~xZLP*on<;$TkV*hBEa(XF#ltH49q%Gh# zzyt;t4Z+^q6mU+Gc)F&y{5HkJ;bx1bZL|Qp_6AFnt z2$zp-=lXBlCTL-Qhrf^)dI6$tlAx0p=}>)J54vpv;YCU(IOLCn=s%`-$3b%D&a#9K z5`Dm8mhiuuUV^Ex?-IxL)00ItD>7bdvMJFFC)z@;3h9(gk{@{ruI$y}3^NS= zo`)Z^Ww30^MKFt-LOtE}6790Q42Ry51dRMaIFNL>3^{F%lZ;Pc7PFF{G)0<>CcafX zL4ByqA(pfooK~efHRY(2Iw_nfLtJ4Y(c7MciXuI(1&b9~_`ahcjyVsjhAf5P!|5<8 zx&#Kl(jj)e!*D%KL(#++@G56Ahl%7zqeU*K!HEa3oA$aT4Tqs9{-30({NWz;V~cKx^fF zIALMMVV?5O#*kn%2Q-%Ti|r?y{aJzWk5HyJHf;ckdWrJPy13+WR+jLLq{g39Cx=o>S9er;tjopL?ZuO0dq2%VY7|}s4iLpyMFO!=(YT4Fu@ehD3BUVJ6*nd zw}7cg_J^SefnUij#3shDsq(CxN7vPoE2cE~o`a0Y=iCRo%?52O)pNu%g7VO`qVdSp zY$*KRX97#l&4H~w0&WSMybS+1vmd7TCD-@XTu`gx^@%~%Qh_mFES z8~x21lXo3gfnu}p*t)=H=l3vXoEF}{M?#0LN~Cvp>(k3NQoRC(UB6rgcM$ zX+K;ZO(LEuJ-|L2Cms_>Fpu2ar3*`PMU`#xj9TbCszap+ z?TQ(V)ONR!s%vvZe(8B7mjW^{a}7YQT5#5I@0Wbn@>j9^|5 zKOv2p(O*0^S)Msm)1R(e>4e^28;9)A--ibL1gsY>Bqi^!uwhd>ygC;Qm0!L=t9Ln^ zpJ$0TZ1TdVlwQykqlPdpVdl()AJ^&AYZrt3SAOeU#ZTHcg1JypEp?x3EnXcb&x}e^ zrseK0mE0L&#Fd8F3RI1!4Y|%HVF5ErAUEBb^C0%Ex&}{3>$O#^FP^jS2;FKX$9VU4 z(Od2oYkl1xBe4vX(N~SL~5m@ z*p7;gk3dL3EWB%d%GGSxs(PcP2w!TOg(t11DYG-j=sxvRl+&8QsQ$epENSJ7DWhfF z`zC>4J|_&2*}Jug+M?u{V`m1_hq`Z3>l(I}ZwaadwO?&8DCY!Pd9Ruj(WT5iM`HZ!jTDS2KYI=d-UAFFkyP|ucly_v0Lr*s z3IWyRyYk;Du4&2jtTOb}Tt%#FFKho1xZfU!luPir&lYg_I7U4qMxzheWV7*hgb_b! zZZy03y1;pYnZ3tT))Tr`+V+r??Vjh!X3z)dt=kt_aLOsqz;*0=$SVOy|1 z^(b-z|KC=|*zcMXuG?q}zcxCe>7A}9=eaeEALC859Bmxte-|s)2xihB57~e3?@CAg zk!QZjN1$`f`{?vnp_E?NHO@%WNAeTdRfvc%NfUxxHMp9M_m*_HovDtmp0VOiF%7#4 zu^7$P*F!vE5zI&bj0BQ!AlkixcC;&E5eSm9scTy{0^X^~?a=Re%p-#Fn_wb)x_FVSJVn5~>yeiY z|1pRjxl);Concv@+r%-s@FwjV1o|bBECPnB+4v?N0DJFVcy!Sf`@7}gc3pRzR=NPr z=4_A{HIcfTfi{Qn;}5sb3FiHdH&ToE^|GK}0_L2V3e5VPfb>Rba+vLbN;qoFIjB}3 zfeuNz;GBLB&i&HHYEJv%4nw>U9WC&$uM_aAlxz}6Qw_RR`EXNpG)Obw1G_`N=10R` zxBEDyNo~RdWxM?q7+v3GAdbH)k+c$*5hAjPuvWow=7pT2au_Xx$)?ZY<{CZRvLX&5 zonE4S25+Fd#U1xAJO~jj7hnrX_uKAR2O)>8xzS*L349}%!=;IypDU28e;uige|ir} z+b=-(F`(J@xQZxM>_vK{?3dI*+}E2Vu;~>^#v&i_zxIRPF>e$*uo1|42U_1L!}ydb zcu&kItbXkdxVRZ6W&!icH^ye|XKz4ER;;PA48KfzpZUIDmK# zscj?o1u4~BblA8(hS<|A0WP1&MEx2XA=7O$B=6{=@>cD^bM9=$>#egumzWH*llGIJ zG!=$ieJ^MdKhu36y?s`ZakiKN9mg5;B3zYIruu@8Pw=od#7(IfSdFX}sFqJ61M+E++!YlNS zo&g{oYf4*YlDp_zI=C!C241gQISrJjdK0{LGRGzUsgR{%2~$-rz|}G(>|f#!8(eKj zB=SJq*t-y1GmmhiN#tK^0}19*R-w4o)K~gzosh|#w1+mk90YAI`_T;#F2Ui?dboQn z1pzfL!L$7i6c;zb=rT)e@b46Czi$b{%3J`QRK{L@Yryn^IW|$z$DZzCXwI3Fh|HPX zNB$*kOEAIBhT=WzGkz%zy>=L zHNN+SQfk))U0SJH50`qxfe+Ha0Y~KV(J%3|oY`3N)aB&5_|c3Y7y}$CI$FQE+(}J| zsnlqsjvD8o_P9*SbJ9hameG$Z4gGNLgdM&Q;XFBpAN*;(;Hqx;kzrbh0 z21uQyhp*%a@yXuMmHML{qJ;gBOP8xcz1_tkV5Jx2-f~1iMSYvv33$taZb>YX@Ot>yb>;7IqDj ziaoys#u7~GdOPu+KhdJUT+N0xZay2R zgV$6?Lgc`|^z?Km#?hAqaOjiceYgm}HMYj_|0GORX&;CAUzNj~VB~}g#O3jyMe6=a z%+QDbq4~QGAk?c%EpgcnzQXswVj6D!;%YWp$4DF!Nmm#p9uN8Jo9S_>gPFJ|MR0w% zHwc|2IM8Dd&e=Yg@i~5-!#v}oD(4W)n~Cw_m>HVlIm?uoRfVsR^0?oUysZypa=M<- z@Pl}$5tV)37m_2b+QK=GwT4xIM!Nze%Hrq%sgUXG$$}^~7f5_L9tYRh;p%gr=y4|| za+r5KCYWGOT|F;;EmISZ3sqt?9?@vg>Ory(UIK}sfCwpWC4w_hFkDsc|7tdG-~i0o zdIaq@NToV2=F_YF)8O`~ArL)l0$x_>h%cM2p;tM(aSOVDPsChBFfNVtVsopvBDsZ1 zOs<*``me~OLNDBtur(XDF(!od>6RxMYj%9i#$o6bkn6NWpP%nWV|MJP?x~R|w_~P| z)ixQQJv0oP&A^oQt|$((m;c>tAQ)e!SFEQMEwY}Z#4Nt9g%6ErvA9FW0t?4W(9|lvW>d>A z=tzS3xJFeXH(FK}Hju2e@4B*VD??f`HUZ@}#Ua=IhR|Mj1x`E^V%A?kub_l;=P9c6 zM^C{Ks%C4TsFh`)lI#I(g~RcxoPL;@>4Baxe9h*6ds-a9L@ZO4jFu`&Ka++s1;t5{ zn^}u!H*-JaV_b}q>hw7S+LTMmm<`)vyNMn?Gk|x|sVHxp6CA(-R579&LgYt7*fx9o zbchC?aBCRamT3!eJ-@wSj@+Idp)ao<{cJ1Kde4t#|k_8O4= zEFTmOsbZ>vB>N4z1X9wOUsP1a)odg-UO3`t8%(U718;uY72~yp9{4#GX{_oG)~*iRN8!Oa>e$%p7isyq2#TIQkWgU{ z?_Oo&h+cJko5YL8oE!)5Rt&~#w{?SKxd*`%Vlo)H?R=PUF2Rh*QlYatd1c0 zy%ly&eg?BMSAbq_6E|sLJf@gnRD}P;k=JZx2Q5k8TJbU})5U_OB5opM;W^k+aRl1K zPr#8bZ5%OEfCJMmfI+7WSeJNrnM@X3s|qoXWH9QW7~IBN;zf=(;pydHP(5fDCWDc4 z=i_&!1hZ_WKq7P;D_c{c$Q*O(pshyf(B*%GAUIb8!OLPo{%{+aTPSk_tVf?KFE7k5T3^)dVvlr$|ix3t3EvBC|dwfWGp! zSoXyCBWkCbAS#zQDwASLA#t-l%J4=rQKzp%Z^R||Z^ABEmyrqm?A7q5ZOM?YrGvGr z9bwzPZjiI}!gA!#iO1A4SXpf~gLv=Tt)q zqc!pU=M!*0FXD0cI1Se7{Q{FS$w(K=fyos9`^J+`V17j~#uq-Z{J_ z2J;vSt~&u+f%5evU0oB?;h^F`uA7MUvnd(h2-LMQFn(-^=RPBPfv9R=v`+#>!fL(# zT|x{0ID*KQ*V*{-m`;LuqVQHae@&v4dM02luMttirycfhGU8N2EQYNPRy;Gq^ZLl6 zWu;aj#QUCzld?a%`2^df%JdI;vruU6@5 zw<*$^O#()9U@$DOc#gsZn!sijcQ1bcUf(l7D6qtZVdMhrVjlQgwm|?nRB6vO!sByC zVbA?KB-OVM1x=X_CORYG@()iClcS^@`8&lg0YQbF+{xl9>34OeJjzzUw7KtuKNdmA z@k4(IzR?b;Hyfdy(C94K%=7l?rtJvH5hsx=&Qr z<9OfbDOx{C<}jE zd@-aSR~icY{+7dxkypoe5(ne6saNR{WF~0QUD|KuQF=UVgyxxib?_07F(8=yXYtZa zx1sF$33=xFj8&4jwj3n7bd+=F;dC|zC*XCc1zxGIgDHFl;wE))lhzZZjW?G&VjbK^ z@8})QocA?mw9DG)AaXYyv*9c^X)E}*=OBV<^2?N}k5m`skyetL(dp9BK~0k34{}gy z;$yJCPeL|H&j5XhSm(zp;b77g8NB{8c(zF)K1v0jakIvLq-L|$2{GB(j?6!oZd(3f zCVcED;xIdSj6K2lZ!eUd8|EWwk;pT-AQjq?tuD*PowP>@GW;37x&KY0_qQJ@$jGH zaQ(V0`qoEPW~sV7^E)_-zL~!d1`xw~cBSp%&jN^GJ}Q2d<{OL@VGVi4EMOq*?`K8@ zHhh%So+lp~;qqei?GODgolsu#l}m9BE`Pt)WUB|sLnY{QP;?sklY%{jph}P@g*4N z*uk<7y}so=WY7=VMiA-V6qN6C#;UDZ+SO_L0 zQb%1n1sipklI%|(G(~SB>Ud=i6Xq0BEg0Gl zk2D|5onkf*&BfX8Msoj-5N(9MQob(W!H;GO!OSZY$vV0XWgb#_ruey+w5x6peMhT_ zVsmlrn}0)%rV+@w%;T(%J1jgvH%1x9Jxc=FA9)=3%Yyq~Uw^X_=XKqNI|f*!$dozVnio$M?dc-%|2^`|_u^hZ9bluV#66+Wd{^~38*d0ZA83AOpBp#QlQ zM1z|ELtd)lAH-H-if=Eh+h&Njs0L#FzqasVA1NJ$h|tnoOW~LvU$bfBG4TX5vddPM zl^P?ysxi-vS-#qJ}r4%2`o*MkZ97KXc`~CUZgF~W(Z!r|=V5g=#-1gh*4GRz>#u`j^J9n@XM))? zwDaHDC_rco^^5L)*ni(FOxA;HkvW#Y?v%cT~Zh0Ln-PWsN)8L;7=4IMV782+2l zAG6<{Y9Z}lYE&;QSXt`O=XTK-1`rwv$;{D&tZbEy@imxyD&bu9#V$bV!?iL z-}c6h(i~Gp4K=pJb`1wWFi#DST1i5K>=w}9XZNGoC1A)un|B1$sA?wKe|%SYpB*up zd8|))Kfa8<-)W!((~F=ySs&+(kwLN2CkS3~pDU*9kqzd|v!-5-rBz2U^uY@n*#E>H zc-W(bb!Mnz#Z`*Tl#fmL-v366_9G}s*JBW10@&PPWbcaXhhvGy7E1bE|jaf7HABPFx zNAsItRG3$y#k12z`?r%1_Mdl=^^ACAT{Dz2ZX$UcLRHLGIqI6fgV&5k*id_ut9Aa> zje+e2|L9E_&dk?0Bee!@RV6r*f)9%b1PYaVJEGK$0${jpU@9|vB#kP;w5QH zOp1e>#56t|Rd>yy+Gp&BjD~K=AaSn6F2A@66x;8)`I{Uh{F({DB%7@1u_I%&qyln? zuR!T!XKZ%F5{p(kG4+QVxzRZCdzucx_?3M|uJ z{dyG&y|sXvuwu1@DbC_-bJ&%})@(jdPl1gKd1W~Zf`-|m0NqHW(vnIonVkVo*A51c z|3rAF8PN=kn@(9&MRGNpyZmSz38p5H5j${hp;FYgSBYtUJz8R0^NCW5-jA4^7?ics7*dHp3hOVhOz{mTfO(#v2VDjZ z=-K|^P%&5qZC-m7l24C>aEqaM(Lw`kFLXmu53PZnv{?Qu;6*StuNuT=3gu*I&I-$LP`=}=K-g#RV{15K?3|Azs72?P<0TVS2I{7$BHQax!X3p9`-4LAD8 zxFZ z!;{W5NZp~2+0lgX3p#{g&Nki>2lq8gy^af+|8z7clLk53rSBoiBaX1CN{1nY?8fZX z_kcV(oN>Gm{PRn=&nWdv2a!vxAvmnR58tOc!sr@pyr}&VB(y9(knW=ujP;szUf#Z45UW9UilTU^Xs~7Z0DWCcF7ck#UVopjZCqiH682 zL+|M45THjY=E75)YwyKzd<#~?S|VEBKtaNlS@16?7V3iJ@pw0)wihVl5q>8ic*J%1 zUdbOhhVw6iSc0i9OcP0SHDqs-6`6R=3fjf}AnFc#fdUv(bUauK0r_d1&Sp=95@%)- zH=_m~rO|LXBN1E@?!$Z|eH`Nv4T@ARyglGW8l1zRt(FfB`o?1t2}Y|*7GZ*5n@3v-S@ zb!#ikT}{k2lC2#)LRwvE0I4PxT6__E_=jqeLBYpKFd+?gt4S7@Q zV9UBwaM*MpR~ib)&xhWx_aTgU5hkg)V72?x@$83Rz;1UMe65ti`)N5y)%iJ+&%V!L zuJT8YY=Y4{*d?86Gfp~dxdL;b_7J5%m-r4^SwW>+2gF?=onF^7xSEY-H8BSy#T4&L zk05SXB}{4;;pL<~ewN*BnD%=DSlL%YlmBoCzzt~Jva1|Mzlb~86cJ47{4S|Q@VWB$ zs-#u^p9?&BnSkC6?B>F@j4$4U1|s9#S7yPP1J@nS1y6Fn#yZ2!Af0*BcAMg3!53jH zak-die*!`z`{8{1CNTch!eM~Nlo5>FOGdi-)Z1$X6#^!$y9G7cK19MTpHN&m>48#h zfT*?{7?NO(-BxRI0vJTK!d@w9171sN)02t$43$Rt<`1Ro^bBNu*D1-fpySZiU%)Ns zOFX8EU=l_oNDX^Wc;-e67`e*>&=b{i)c-kg?!8Uo4|{ky4_mW&zeEeasXj{<`Acrn zmgV%vt)v0t-uVpr#eZMuQ|JV}V*eaEWz}M^nfr+w%?}<^M=+t!cS_f*Z4e!pFJMl7 zks<9pGm)c&ytXo1q0;Ozu-*^lX_nY&mL`|O?%DT-TLNk!I{4VT0XVee3mvR9l=*a8 zo!PjwhL(D4fyzF9LI2}1O$75MWS`W^;i2dy5-`HOXQ^e2iY3Cba1>V7LX>q)VCj_z z_ZtlGr#VVE??MtM?Pa}&4vsLuuMQgGmw%L)>3|rYOL;Ut}8Z5L?V*$S0oK5^-B zfs2OXx7Zo4@%~BApX|yw^tWSH?R!EmQdtN?6Zw^<&Hp?*2jQ=c%;Hac_mN_>gFm?>CWSDOe4Zi2D#8Fc@^}SD_7{yo)6T{A)~?6kuP-J z;3rM)I%&k5q$CT!qc1ifU(&}Xsn9EWb*OD+!-7h?AW1Vd^puY=6WQTYj^EyuBD*Y#D>9$6G+`IZs$lu8!CR{l6OzJA#QDDw63X zE|scH7cdJ(AC@#X&ZkX%G4+9brLnPYK}j#UhO&2LG;GZ#;;S6?eV+yC%y7I_FaR4U z4u&V=9ngXi?Df!9tUhQeXlTh}7So>}jWfYKUg0M5ua`O()q$y7UeXLw5fKq~Qq_DZXS!2SnF8}>E0HJXTGghyda zy*{Qkk+#xfCjd_{ftut{NLJ619Vs0R6xqGmNgH0sVSEUtrp!V%EXi4RSVw`eJYNsR zEip0`Vxq-jY<|k&ErmId(OC|@KBpnR@D50(t6<}XBjE4;1ngZNLhRcloPR_eznXIn zGB+hbX6hMOw_b_E*yVGW0D{Rjtdj=bb&!1sP+-){S3+8;GJKg{M%5m^3U~LBOJX8` zc|=^{D;E`WHJfokYPkJzA{^EI0;x@Mc$4{b+%CBShTl@)!bXyC8ZZ+!%JI)8uziWfwd)+!{xS*Fq|B_G2f_mdC6im>UrtqB`w2(mG8==H&1W zcv~xkRqxekRybyqP7>tFB}%;C1JL_KLqkM6JnPfKZ1!re>mmrOI13l(r?5~qL6kgs z7A}gOgjJ%l;iumK4)ftGH=0cZb0zeQI45|u)P02_lT^A3eP2)x+VUzFFi`{( zI_ZSCYlN~CRVgx`w%JmT*6)QNZ)=*>s&5{rgo}%B5Vh)4aNf;;fBh4fcC$YYOg{}$ z?^5vh=zwnKB}~vfi{9OH$1OWN@z>D1Xc8%ov6H5l!C?*%%%!Sn;_+8^mz9&!P`vUO zN-g*dy4%&sjfVAy4jEemA0E7b&PL*$qVfb{$jLvB_}#r*nFIfwDuZcGe_-CC&*)Bw z1zy&lSnBRs1g~RxM`aZrlT0w?T6rS*@mEBQpOD#n=M4Sv<1v&vtAMh!EQMi@Rd8{} zEiQri!;zbym(>DiT8%Ml%CM|C5xxIcEYSL6?`k;jt?RI)}htTZ9^1-iNL#EqeUk$2SgzQ@qh zCkH-P$Sv+?F~1YQXW%7Fl%r>vEX>Q zIQz1YX|6ku+U_Pu)c&oOg@>$%#Ig!tFP5Bx6mU>>_J74KeME$)>GncM?vk~qJE;xeyZ@rbK$&}GR&2;Nl>TZp$k zTOIWFxNbBT5*MEvb=J5QA-1 zXc<)t79}JwfJm)aMVHFleng6W3E2)D2x)I-qu`+oh_rgqO;>ANKH3PE4T(fuay-U` ze|suck&gUITHLkPLfo`f$UN8AMbjNe(%pk?QDjdCQoNxBdY7wVd!zvSFMbB`|Ef5h z&7k6XWD{uyr~IcOr`fgec8CCyAKPNpn*R9qwkzB*g#F#@<}q3Xv);N+{5CaQWI2bl zV5z5}8=EZYu*bttv_OZmI__Rr37f|gsrBCHU{A!93F?mU@Ca{p-1lQNJ{tN8^c~E> z!DSF``K^VAtUdI980{Qx(hLdaKvT0=|Gs~@3aN5vt)7o41w&f-{w>Mn&;_6vJs;TW zAR8UVO060SD&X%_a;b8BC$y$0OOaRL8OYd}0C77?VWW)@7YCEPwO0&;XkUfI zBUfSc`T0nNmV;ToFTlva60Y1c#Ws;75c-r3?A)itErC7!XdDP8TfR|zD`dO$keraw z>t2q28;+!h>mKK`SAUQW6^l~1G)f7#8+ULRHo2S)MLo7=GqoyY3K~MPi_EVHpW@lz!`V(w56$}7SPrRzLx;zb(~cilk+fer0$@m@HU7P)6EaEqqK6u^^$he*T5#1=lK=EmnkG=A^S5}PNPAO_}&MQS6%7x zgJ7z+8#+S=;U@p1;B-$5cShzy-sM-||KtTXX(9iQsyFe=;rsvp+gC!8B&md?lTH znVEB)^IRSe9%D~1qmJ#hd|?fj6n z)!!6@j7&ZZS$+Y`)<1@j8^rv~F9>FBQN~+U@4*`5K)Crv$YCgcvspzj^AyL6wCgsB zE-fL6u3ArKQsrnc-kpIwY=1)7#d7e_AZK;n-l=WPH^^ z4v(Al0QL{=fs6fK;2yIYLQVWR%v?U2%>-lW5Fk3G_euCqMvg6OQ=tP+X+ibIG%lLp zHRYVGTT_P$4(RUW7A@Je0<^CcLgX1WYoAe?;dC$z7iVOJn= zF8x{r)?di_Ye?fpA|3w0$Q%4CrSY!PYcOY96d3>I^8)ca<}krr`ROXUa%F>6P?#(` zaCjmbsjC4yjvPcThTmbm_6Lw5`h#{cYPjvvFV1yw=9N#dKcyH7itE5Ltp|kTz0f5(-UcgnCvZOO&6TClG`9eRxCWj~mSySY z@$A#SA*^m#JJXo^9Ny=Ia~KC66HG8lE+>VfLskk3`^Xh{p+9}|;vlqP?>S^)*~Td< zmpI;nl6%BjoD{tz>O77wTcC4L8Jzpw0LrVHKs-y1T{vSrdvA^=oA>(%bLE#9^5git zKt7KNCzu+YV&UM^Zh|X?GVB+d2wHm4d6fO|30i-ynd`GT8gvv&#=nO3n^K@r_5`E` zv_e>X3B){9!cFOl_;}0*rhStNyQGuoLr-QH>R}9+UwFVpW657};|b<+nz`tL=!(GL zp$yxo)5c^p1XETTF393v9oL+c)<6`l279`jNbrbjom_GiBn?^8Vn_$s4iyMMvWTr3{)-k_pTPRn@v7Fj< z{oyKDH%Jz43LJ@^-C~%&Uxv%4m8ZQ0cFr_B@t`68F=#lIJ8BI5ci%*MlH60OzTX4F zrM7U0P4ZuJ+=Repi44R+5p#qnoqDXZQ`Vu$f}#OKBvpt;s|px!@^!#MHjhkSxrrmZe6 zymCSCdYug0lD~#&yWvGglvz-g#Oq!%9{1qCG-Tp54%{F1qJ<-}P*~ho@RQ4j%2`Wr zaxe6Q!Jm;4 z(M^@8^XRC^a1!BxiGEnC(TlV>e&iOdlfSV4BABKVmSXE(ERuGRVX24K=z;zw=GqfE zD)~(wtQgTmEW_48e2g!IUsw;*1CK!Juy5ev@(fBZ&%$Z9rEzk{1^lAE5hmp>gQ-R* z!05vbSas$Phgr;H`UxiL`3!N`&R9`DS+t%mZN#eYXB49K#fL+3iC<(ZmsOuKD--C* zs}L3(&S4~;UQ?8a2ITG@@L79}NE_Z3Imj76Hs z&Z!e^+9SiJKN!cb^A9#!pyu3(%i{r1;5#-6U@gkqs56DKSWKBWY{!6Pmm5y zLYHpF)7DnGpzZsWoHU=p(w;(2>iADmE;qf}lO03kjV591EvmRC+8A#|rLZW?8A5FX zNWD4~v?j}Pm{t7GnhwG2EAJFNI9o09ej~$9U5MezyuGN(!4o2y0!{4qgwV;PPvEjHeYqMT#aKaUdN`$6tldw~4jboR8q^W58i_`Jc531f%-; zKhdryVWNF%vh1(oD7g3fD6C7$;xLjVq-4g!anO5EG0p)Cl`2Sn+X3l!qao&27o5<_ zfw}pA;M>l_aHB#OPnu(bkNB5?&sRQYvx1MtoM4_&SJK0>kf_l?mOc933rzeXq3urt z9Zm895{%?Vu>QX)kfa|Zd4aGE#2=RoVqPWUKmNqo_ugRQ&EBB{ZUd8X^A5lz+Gjz$ zubO+)rt=s}f+^B*wp@B236pNhlCjd~Xj?=pV)XlHiGJD&?{CmnM!dd<)^M1%st*uo z+XbETo`NCK99mM_3eqpWfJ25A1S=22dxVp4#(gIkdODrMOyw~)1T#)?ys*$X)vBpU zmfcx5j`^o=H#F0F+^MO9q( z;U=6rErOI)GWdn5Iixl4B|LxroVJu;G=9elquWgcz6Nq^*tT5e(0V(tQK+FEClx|i zeLJ`uBL1tZTEHTaM7O0Hc1B9!em60wH5lQp3>kdbO$CR~y9{4W2E#eis?Nn2;3yc+LY|1tY?Ukcuf-B`LqbuA0;|=H!3*UoJ`BNAjzkF zcqW4-d)gsJ8Atb$Gxer6aF{Ux3jQU)gAQ5jSnP$oM)D)S|2qyk5{&)ENg}5Dp}^w0 z9Q$s@cvKfij8VU>q$O6B0b75OqU1+d|NA?4VK=@|1H~ugaPYD$*jAN8B6EX5sRZej zgWOt#aOT$_{16$z%|8BQvz33L_Y#b)_5xx1-86x2tQ@Yep8*ICrK}}C6gYDP#@Wu)gD0F|v zE!rA>7dS>RlM7#4spXdloSwCPFJczKqMULLbDY28dJ>FTsf}Pwccb9$ zb2;{JqBLslR3kZo8-kKSHQ-hG54_C2aR%uUbsm+24X~w22^(K5B6gJ9Kxg_@w8&Hz zsN5#%gpmBAmTBQoBRg1O#=mI`_#=le!5kHA6?hu`6cnV%vC{JU>3U^5H12w^NK%lL zXx@8#>wwNJJ+NkaC8WM>f+fdQa6c-8S@zyU93uctx-cI6sy3sTt_b)?1ey%hmEhL% zXfB$Qd^PGO!L-aX5sW_9BN+Ttj%_(wN?$VQr%e0~P+l7vpkT8!mT~_HUTuAV2CBh! zeJg}?sN(vd_ps@G2s~D5MjL83!K@A+nU$WmsJq_3>JjP`f2vy%H9 zOIdzvf~oqlxIXj`%-<)4txppfmfEjec2Lsfw^fA<$;=u+xn*8px*`=VT(SsWP0oem zgC0mP^r~YQ z+jr&2lw-pUi~*gO zL0H3xyAh0eCWkw{df~ss|37A?a}8XWybyk_JtyA&J`M$zuA}3|B|yM{DvqUPK-A8c z@TT%zLq!B5HF}Lezi1elU6W%+?^i`v@M{Wfut4i&zJLVdnA!)M-jIPMjsGv2l1DXg zX7YUa?EG8&^^PODTs?gN_l8eTIA1JFNnAj<21+zOesN05e>=D;V z)Yq_R!Il9-@Dwk*=qC29z z(&yW@Q}lh50%38-)cBaoHpr#Aeh_!S@35~G%{`85AR)6ffA7OnWzd} z>Xeal_Dv2G&dY+zWRXPIvQL)M%eAOA)w1mBg$IbPKr}V9dKx8BfcaP^gH>9{ctY&} zgk^lhUa`$DAOxR&J9ext}`fna~R752`bh<^Cq zx;RlB%rtQ03dw7F$aHZRxQr_2eh5Okl(E9tYEYcn0(7V%tUYi9USu0WZekL+WlQ4; zBMze=GA2y+7b&+l90n20U&A?8_M0bDJBX9)-Jn!DS!x~Cvo1p{ne>tv(*$>RL(juM zVEnC&!zeG|G2I#6@D!WF*o&mHIO;!mO^hAtw0gj}Vj^;{;yY8qc{{{~1oLp*y7ZCR zrj&;kF{%3{q6IEjsbbf3u_XNlE>I_q{N~JqV6kd&2d7LBKp|ggL`T zQj;3_XpHkY%tnIIUX(2i8aIuSC87-5&KQZm$xfwizIw@FI?aD^n0opLxC9r2WBgZ; zU#-YRWA|Jh`={>*57*l;GW$Fzli9=49SzWC9z`9yE8?PY;W4`iMm4HLIM-|j;guiUK~pvKoF?DBy2uF7SMwKdkjV z2PIVxz*40S-f0X%+f80^m>~sRGzSSrdGsrxw%bhVGm!-ywt5^@oBL0o)gB8-slzA>RvDO$&pPKC-p4TG!`lBiR}zBt^QesD+iW5Yjz^Hym*{^vQUO*{_=TKr&A z$6Xje1(5%c%(sus&>4e88kc5L{hmbrLvahe{*H#Y#r~Q|GVdudNRM!q!aYaZz*eIGJkI_Gi8@a+ z`Mt^Sl*0>S0wBpC0B(?O)}o=8!RX!-c;5bmdSVdIVU`wim@tAFHPuX%a(_DILuv#I zI@i*DF&<*i_#MKqgceAi^O*?Ilfk8hpEKeoCcYY?_a`vg6-~_jY2Ki^?IpypJ}~6aW!M|8!VZ~V$6@Sw3`;P7{r8Hp7;`G| zq#RqQJ5gM@-jVVgy-FZ45HxOh3m@0Z;=?A5aQN#R2!8z!auu53H0cfeFkgx_^Buyf zRbPP3`ftIb;VxLNy9Ufh9X4gO3M+}`7LUm#nCJ_hB4vkZ6m?pTt=_6n&n|wDZqxHf zq`tlY(#NGj-4R)Q-?bKU|7Ah)q<%63`VuUsJ_8G7Rd)A?A?#Y&dvML+H^lvU0@UC0 z;COHt+gua^eks>oDjqf5&L0zvmY1%zF;= ziC{EJVno&7r%}@3a;*R0^Yl^+D{8OfZ*j1rFW3yMgODl2rF1tjdE7|EGj9BYSoc+6 zXt5chu7ok(>#s61ZSx^u#c=%2={3y1<^@~ImoVOYJUGm&4;-eIVBX6yBERResdjQH zjE~qs8{2Ckm5+U5^XH2oe1#fZZIH$@N0dV55aPdP_7CJD)nK;V7@)R_#I||SmJ5$$ zL%~{YEb1$ULuApQBa~9TRlp5jtg7TNodly8lq2%m2UP7_63s_X@ttXA=wIj{`s7wk zFq*(1$qRj0`Yi-sdItOd^?{b)HF7xLjy~sxit1*)rK;@+=Gqv%tF8f_s9b>-jY-I{ zVF-u0S;b-c2xjxcJke=|1(ag599!XbTab}39ev2@6qlt)p&Z`_ND_^`N*+uZNaQdT zLle=~@1>|PCm!WH{z3oEeg(^C7~quoJ@825Iz;{_2lnoFxz97Pn!_k$lV@`>PxSPX z169;Z?5XVJMeR=iq0_y(bee+{8iPo(P?M*?Et{Jo?CCh7!zEoG0phv5xZ4BsJ;4yJFkERVY2qfOcQ5 z3Kuo95p_xiFD=Lf%it#*Ch=So8v3FQy=s1h_83TkHW@SvIXew2?IQYj4Hp5$%EFk^ z5Dr807;S=)zgj5L?AtDW5 zP=(r2vYeT)q;IfBI~OK~QTX#8E&R;R7oPkM#V5k9W65`OpMTQ~31*lc56QyQH z44p3Qr_FzxqRP^_bVsWLgew4uU&#=|Afos1Is|;S{R2Y}7qHP;3b*grU{fZ z;MDoJ;=B%4%{v9U0YaFS$~RnQ^PlGwg4uhpMYP|*g*v-io^6XeNgHd96A0E1qa6o@ z5WnJJ_)#l^9m$|&@}oQOiS%?@kZi_bvPFgj`oQG94n!fY6_gYlaK`@O`1G7b&?x^` z(D6zdB+=ONo6T&3iD+pQx$N0ZskurNm0ghMEOmO7<7&bBK}2PgsE>wBki+-SJO%57 z+c0J>@xXcb3J#mbft7-`!DK4qaCYE7|9Hze{7J~I|!JJeXoJtCg5?N3S>%UMhT!vjSIh&a|;j)IoSRuX% zZQE;rd*1OHT_gCjz#4){)iD=+w;WBqSt8Gh%D+S5Yd=O~nKqJ)%6D#g3J-y#AY!9A z{j{s5q}if92Z9aK;nL@Gpq4fizarfbp0}6b{xlPe`*b16ax1QUKa-2bj6d0IC79oL zZwbc@{UPXIK$CFGR(B?>I}-GvC!(LY4s z;zArI&uiY>@R*|n)4iu%SbXEK;BuTCTe|WfT|Ui%88=-S)LW}T<**Q>&nR(=Ch1a@ z{!EOWl331_9bTG>pS|urI-#l!^*8reiJl zSkx4;4#wN)fKGZhHQ#e0M*7*@cY}G%MS@8`G*fisTZok%xp=tLDx>Gyl^BD)cag+2 z$iVw0JPTFDyA+7NZ9g%s>(;>a4J_Bo(K&20WE>xfX9VnGRQ(+2_j7*H88dD(Pg-YT zj6cyjiLLbKp^Yfof#f(XvpI}McRcKJj3h;^ z5x9Ls27GcTgv7`5p=y>qPB7?aHkn*!ruM}%1=2&Pdmi^Ryi_E;a*4_AdBr7eZU^d+2L@gNFSs zf+wV}O`+us^S#EJS+y#QNr_p4$7%601~iX(MKDZx%bYruMA2?yDelpojn?lK&`%<+ zqZtf2Z59_VR`e)JhCR3HAToNqlS+DTh#m$ga+o4k1Ke}kk%MX&8rs>096zRlhb&1= z+&4vgw>*axL4eZC44_s?9sI*jqZz~O@%T$g9L9l9rqmP6jziC_T=P>!W;bM5le|0V zkt#yVEkmiON5pq^Z!vhvD#ASrMQ}(b#vv3hO zhbqA0(_=yFc^x|F^%b?Hra-*q7l>IT5J>x^!GaPSWL2jJLBB@9%2C@%EpRce-V?+{ zlfq{?{zw)rbb`RS-$%5WIL3TD5r?jo7o!RzXG(egU@UPcyO^R1SLEh!p2gK4rNHY~ zGC5CwhYi}7#lbm=up)K`S7n!+avqmO~t3$JSq}Ns}8|!7xKW_a5^kbItD3Dj?lWy9%MEp!TwX7uyyoe`glzgM38*7 zd&^v$ci$Fw{2;<+Cl_JoQ~cet@iq4fs1VFf-AjV%9lD}o(lS!*dI!1b8KR3{z6iRB zlZB)Wu5;sA$X$@aS-E(^{mmCP&XVQzte$*-&X60=Z;HTGBo$ z8NNvFPk`p-eQ><_E)~9=g?*b=LHL-_v=J#1f0a#z;WOvpg8Kq)(H`=jr!K*mS6K^#5(XMQ{N_IH{dwk8Tjh5={Qw=A&1H0F-8QFv{Ynu?8KlK(n1+_?t$yfapKwL z0!u`v^haRdiy35~JeKqfv~r2AWM?vFS`i0!LDG25MQiHml9!;gQyuRM)yI#$i5=`* zQu13n6Mu2O!C^G`7uteg{-s{DdU**8M?E9m59ZhC&D%)>%mE{M-yKbyyp`seCTtWi%A9dDOZ#B$S;O0j|}LEiG|&R#$meB zy@Rft?oSsV(8gXtWYZ_|pk59&P+vsM1b4pzZRu$SqnY zzi8_TMk!KWWW7-+oVP}negE?nx~MWzFwMf6cBRIW83G1;YlPsXU(I1GKjlGya{@>| zRKb3;ROs64S13WW5}qqi$3fQzASbGu{7}q-^wz^%G!ywQPv0?ir-{c)e!Wh2i@ zFq-_caVMBz+w?^H53Ll6vq}H|p?cc7Vli4hwVzCZkHQ8oVjygO4xFA^!A0Xm^aR`O zqu{uM0(Mv-V7r6lSjFu+*zJ}!{v;O(;W33^I#ACJ{O+wZyo>eKRwkwZE6Y-~-dAq?LJ^J7v4hs$w!oLDn2!@V)E;3#C#By`DESniWjd}FI5B=7fM@#BA zzZN@lo%fGll!7D)sq*6!=+N%qSoQ`yx9YJLGOw8-XXfDb_f7Dn`=?>@rsq)Vz%qd+ zM{}3~{@DZ)%&5BWqS_nxtx|@{u|dTa%my<(c;H(lmUt6M<_IJ$BUyUI5a5*y!6)iK za1q0wVML|>UnLXqWHqz-ErmxnPr!Pcz2URnOHls1n#oMB;9dcWU$h4VB`Wd~t`Id+(8TRVkdF_7>9fvcOoO5r!qH(HpmX5@=98W@ zN^P5iU799fA2%;}r%8kBqp|4S6(5?s0a7viqD2$TEjvT;(?9nGkEY16leE9l%Ilm! zadVN#xoaY{!VQ$`_yIJf3L!d*SnQCgVx!(SDCOixIGEcac2==NSr<*PlaUs_s^t#> zqh3L|^j5U&zQp^C7_0D@6oOej%1k_V!B0Vgi5y$sb%D+!C53dgYZOVQph)KnGJ2t-=x<9>@lc*Oc(xKol%EM7;#hhh7;&vOM| zBcKUpq_04HcZLZ`>dLXpO&R)dRSax;@`2iF{uQ-8yoW4?w?ce=K3LkOaW#T)@HNni;azwoRVgl7bN_aPyX*1R53L)9?5c1q;1cuvYLqOs`@{37S6L2_4(%ll< z>R9<{u&XqTJ2-i5orv{cqp9N^Z|2pGGi+e?vgMua``FJpk`FE|5|oi`m#A*pw*3o+xex z?Q$}irx8qwFX{AzyK^|qPkx8)AQ)`sExs*mrJ57Tp0;=;bjCSBO20d@{4Wmd%~FUN z5Rn5V*+Gw}AQ(183TNr1KwGsB98I~5$Lzm~_y1JHmvI!drsP4-nQZ7t8wRN|{8>Pe zkEVxU6yS)sPX8Y@afdAXaK&_3wBHl#Lp7m?H1^kjNreJKVtPWFUtKQTgt+Ns{xg*Z z?MXo}N4Osk);o^BzvzckYj(k@=nB|LZg0EBo`D5Ae8Z&|fANreL%QvTnTUTU${<%w zS$0rIH~0j_qLIE;C|Bk=Cz$b>Z2E1p3ZQ;U0O;4r;nPd=K&2-J?rSf@=biWA^w%Tt zW*r;QZww|^t4KJSI0Mu+KjIec1z*TlBbdD(yF@dIKFvPT53P{W1j?rtFvEw}qp;Zw zSnn0Vh`B@X%)mnK?)mYYB95O%(h`9z%(y^QVTcrqj>;FH<$TeRE;8|zTL>iqHqbpH zki!Uhj26MXi}De5)^t&fi42R)9>T;Evdpe;2f^_~7MFgQFRhOE`@iKWXkH)0^iE7FIRT6ZIBm^o_wX_X?nLR2Y2A9fj@3d;!ZfP2lt>9SoN)fbtcQ z41BuGq&@7XTmIX?3~jE1|3ipt1eRdzyC2u`YmX!z4nZL+7(a@3JvPX(hHdqVMbuB!G$grhey32X2Otw_Ql8F_y)2&doN&_D)KMtF% zZQ1mAdDi^EFUCZB7TfpvHCVpnCsu5Ej5EPJFfJ2DcVTMQwjQRlBT`(qc?z>ye-Ai@ zeFkf#Vp8P#3f@hw5V>zHbo#bHx#|bdPHcrwpU9Yx6M(MeOg1Z_oJpBRGqGp&*y{!D zaK!Ex7tK;0bC_UqFGmPnMw?RK7Iib<8`q%Q(^2Q+#&!|bX^ROGQ7;b${Jop=>WFgG_m0NeOt2dD{$=XdXu)2UZsA#nAS4k1I{fH0D7~Bk3y+2(htV@o z{@P(6$qu@xks7ri7K*+9qQ#y?)Jyr<;8tV^yZmOMhdU8g-eAOGj`PRCV1lXeE)o1X zJ(xP(_=hnbI}XLHtU>qPe7NkO*P0ASD>sCSa0W@i4s_8}5t1j1z{{~6;%>cxTbozF z7uOPMX!a~HaGMBotBsJH_f-7*5TA$M#ACtl}+b zjtr2QbrIlt1JDX2RtRtIqM<&@T%s#E>L*ND@EQ^}?EuHZH)Sys z-u8#doGd`n0vE81(iM+CDvR6V6GeZq1M3Q%eABSUicA91XXFE!O{KfSZXpkQDjr;M?HJ3Fb$t8s)U@ z2DR7ZFH_p=&A4CqgT|j#VV)JJV#oGS2v`{oS)>ysdHF*!wm?L+Pe;RN8zmg;SqHy& z{D$hPmRU)~3GrDst2=`*w~3WN6X$zYrs1;wOKeTdFTqT%HVi->ts#IjrPH_aP6 zoqYvgvWDYKb-raJp2xHij9&5l^zgz%RBuZcbEPkpwag&7-;f>=Ow&v)GvZr zYCTG1UA&MQ_N|+V+%lN?(_qhRbPi;$E*gndj6yj~ymK8Svr#bfz)O%|>|PJX;&Oi| zi~9l<)%)?HOFQwusS|MSWjFNrWdI~ZS#XOM`9J>~f=N0->~b&YQ*LU#%<>~X;^c|m z%)Q5(8TsX-v9|pqFfdK!hA%8f#d0(3ox(_%A3g+YX9l53Ei1uzmpy*-ZXu4Gi}1UB zHel|S4Wr}vxitsAeN-uz3}5{97k%hbCI$IECi3(@G)QS26T4~|GuKKFr;`(Y=JOXY z;bA%WxWy5>J>tYnFuN_(ad=*-Amgk64xTl}8t;iGyT&{`({l@)v3U!6?tC-sVBP{r zonSQL>xD`sH3D|kKW3~~81y)3(0f`>Fyj9VvC8Tg@R-9w@P$(7jE;x4STfD37X`n+ zYhdG}4^U@L0NR#60F6ny_=UX#e)%p0dTYl(^0s2`8a0x~=n#xl$ZyLDaxVo-jr*CZ zuQ!2S^_Py=rp!#WHNs)T;=y1o+4x08r0S8tO+`rFv@ztljoRSLVJWC(nGzoj1 zhyx2Uie+F?2oxE|31GWyFPPU5!31oS zV?ygq8!0$Enw}{P~HD;~)?EtnE1N6|f&u#O(ss-B00|`ZqWn z5e8T5)N$_?EA|T!s=K^W8IP_s!TnS9@HhVvQ0?E!tU1LeQ#|;#YfFN;e{r|fP*($i z;P3#$u6fIx9g{dV@sgI=$1&LI;?^PdaFuyeBkPb5ECy$CVw^h02}ffJlS5cH(o8 zxi|pf2d02MQN7&pllXz=yD)OoOz@m@w)o8LzhFT0KHIaGFk5!WaF~%iW*x!wS#A(D zPrEE^zcj#vW;fF|PQLV7+mT2;@&+s<)u}ME53pjaki*PxmBAOA8jyASInXV-!FVt$ z#Jx!qaguN@md@{h-39KH&Wv}044XGJc>|=j@d}rY1oN}%oT$Y$Qs}dJfU$Ywf`mPY zezT~XGFMmt3n!jM_47YLXF(eL8TA}44N}0ZPWMn+>MY1J+(6IYdLEe>48_t(7Uc0u z*bTKx7!))NA*-J3Hey$N^MI;L&=L|4(@^vkGB`#Biq6=o|!?X!7cpS0AnxcuL?h=Pz<~VY=JOi3mHc^sj zN_fmMg4r7~RHWfLQ~2&jKXWK554EoJMit|{QSI$+6#3i>Ne;Izu4G>$Bfpbh48n

&^+`4ln5JO zW^yHDL@43&zp4Qlt1;J3-2fTJf%{q0;W3c}vu7Y%IJQP)HMymaS+O9V%FlTt963K1 zMgI&01M;7~cqE4d3gaQOJ`P+*>tc!Yq+|I_@LBT>?MoBVp$8K{^$o@nU)Ymn@U`HjayE_iN zKE=W7L;CnnA-OD)LYU{XJYd4Zh_S;CF#A;iJFZLN47=;}O%}n3$~3J`6pa?YE+{@v0n+}u0eRW)jseYbP3eI{)R&Ruk^v2+wt85eQwdr`Dvm` zg3%h6XVtuJlb~%(FVnv{L4f4^k<38`*|)vm3~LX)QO6Tvq9DLH3Ldsh!S=&RDq?C3 z{L7TbsRyKR#14B%pKumjQeHxC`~)WC^a0#$ZOdV<^0QHm1k)g1Bq+W$PoVswhcSJA z5S-hLt?V9+LlQy2o;#)R?wls}`xFiJ7o*_^Wr35|kqXF`I2f2b7?(=-!U&N9RG?81 zdy<9QZ#9@HBb{)DngNHI&Cjs66HG$)e8HNXj)K2FJ&ax4MAUfvg4mlLj=TagIWyrG zA4lO5l~|CR)0WrF;F^;%Pb9-@q6B-^PXwM5&53o(IPjeACyKg~NB?=~ipQ&&a~Osn zF7G0k9aWx!%qP19GdJ}x%;(MYm#ZJqL*Fqd*fpCIp#7GrgB@?h!-S8qa5i){wy@3w ziIXhtJ`_6=>2SlJGnvu_P4wPWPsZ7?ikZHBA^vQ@r-q_F@5qssBuHj}{H};+GJ+MINi}ehTrS=B&=`UkrU$mQ9_#j4jGuf_FOb z&&H0&XcA07&NV@H-wT0Qwug!QK83pMzZzv#22lok-;rxm7L30#1j`)1NxY)GV1x%j zW(&a}G6yK)FL`oq3Vgn3%bHpc1;&~lW@7m=cJ^R0(|wZ9s<-f?i+Tj}cEdfvYOM;v zndWY$Xw^KVd_fIHe;q}&byN`l?w1gCRtm2g;|hkQ3qe{WjU}Ba>jMfPZ_Y?OsVE8F zi)>gA+h(Ts3eCLRX2Ax{2COAE`a+^%z^XPOjmyoV?GVx z`|KnR^OMI+Czusy-U#rkkyO~zZbm`z4U$(K1_}lVR6VKNbPgs9^yx9&E0aQOaww{_ zyb6+D4wr%VaHCfRJ9J!!*u|fj!0;A&^Rs)D?a~v>vE>*$t4-lB1}R+k10tAbYuW@G z?Wak(zV!R#v3 z>c6BvGB?riMOV@lqx>j&1e?KpiPCg#5|)+ zAQ3a^yq^qdL+3-$oiOCtG7jm@QUimZNw7Jt8Lp0%!aLTThw7=})b(o=n7uHB1i$I1 z-^cyS4!Enn^Aq#00W^{;7!adv7|pu(mr}|uQ53m(rBpa zN|dADje3leAlL6ZBGhrj{ngQpOj$nXNa+z;gFQI5;au zte*4_j2pu^+iIKpBf;TdKB_4Bha@c{respW`XLQl>bFDce((S5CYGFPf=vu@O%t!( z-Na88lNmy(lc8Iv)@M1?v}@hW@=|ShKvF+XY(9&3kCNdo>_v9w;H+&2SFY*9?04ip zCM_cc_vP{Nz<4+#w*i(M4F|{7MDLa$_S<=3yS>`DyqW)z9uv#GX&wY)-r`P;I@U~m z@ablb$Bshm!5G-zWkN|hx@2Ai0^7bC(Dpmqf3L8 zu>l(ZH>*#A?g$#}>u!U^@jxP)kpRp84#vx7+<-F*Ht=Ix0to!8MUrSP*)79$XMVsv zWxh)_D3ZhY5zNBl+o_trQm8V$n@PNp#3rpPM{dVPP#;eY!ZNDlzn^^>B*}ZPsvvNz z34kx0I{s{>j?*SIfn$&!E*QuLHI-mIdr=RZTS_BI8;}(FGmGFbK?GAjdq7a} zND4Vj?_tdDr7)=r$1~zbw`i_83HftfLlW(W6~%W!;vT1d<{2?O(ZuK8y?`&XiT=|u zvgwppfXt~=*z4DEsGK20FW&G2%o@BVWEjB=inwYOk=ag7n%K)&FjnmMtmRB&_h$My zF`rGpcbyY9Tk-Ncmm1Q(mkym3X)x7iG=6IT2|f(I3az52L{h>Y6gE*+hyRv85i?ldFW=5AMR=*8P}%NaWdi^5Ge!%1rN1r;`O+xogxJe$i41=0ldec(d_y z%3bLnb7x{9Lu=PEaX-d0cB}NTi%RJRvQTINH|&vRHeSQqcPv#-PR2ln zSR5&o6_QSf6c{#UA`T;i{}(JCp_vF`Wc+ zaG}4b@aTGKr-?NC#(xc+^19F}O6vuE-bo)D@3=s^QHnt_f>j@p&bebtayB7bhT|0* zm$Lh-71--to3Vj*CH(b$1B-expgcyF^;x-y!#F?Yc7Z;ES?rN43ea6az1$_uzWVl* zF8Urxd%gCfhix8=Z#pjJWI@$qKXLX{>R}Dw-M$Sv&-H=LSj2AGU&ef%a|BO_ZHE^v z$*|*8G-wqRF;y^|!&vcennFHNQQTc4QuA0!)m)Wk8yi%a#X9O@`tftIWZ2JUm=dVh zl|YHq2e1rC;Up%?RK~%~L2qD-?Qk~I`T)}xb{3mj48VscaWH&#Af(mpWX3NT#9`cd z%us^SlT{VBge{{k-IQim)e4v;BSxSK#b8S1dMr3wUPFiLOF=Rl zvzRukLUaO%+Y*s%E&3ya+TN6NeKxj>Vxj(3CnTiYEW+D_yB_yGH&px4n3Tf7?lBmpu z&~M*;*YA7R>YrAt*V_B+bIv}`en0OwJGk`-TGcoZW#wgp?flJlvbhS0b2>xn!mN zQ5LlvItpJikFr<0heE7@3hTb+3-~zQr)LD>{u>9AL#$YtvR3^o6X-n^B0bij_?>s5 zczgpK^799&_0z#K<1WRFkX##Uf*Ja3rYQYtDpRU1&A0zK&njMx2Khm^*e%Jbv;rkA z4RLpfj8rC(cC0uQUZXXe-%GQZm<0^X{k9B+Zb^sD0dnZYUq2A}35b6BD#dh5Ff$2e z_WBtjmu1CFWvvuHD(8&I==oJh$%td$#;Za2>PxKa+zw!C?|{*&nDoLQ0xLv_zay0Oz3t-YiS@bpOC|a-Th+_Xc1lxr}kndAfaPT|Ex~I6&x99Tn z6tj+CNF$4A6eGjF7%j!ewkWVc9*ZGu_#?JtZX%Q@C%|AGIpR5Z8{%gM!X6S(S2ME^ z9=-7cbCC_n@XACfD`z0tiL$VJ%22dUb{cdEkKcA3SxYf1&QXjf!7R5o6+M2fz$yj* z!yk&|*@tpbY`5HgC?-iUb*Tx&J3tZH{VaxyDu+q#({N<>l&Dm$#KF@W>gdI|YskCR z4yo?yU{{yRpk2O$z_Za2HW-^ADe{|thGO;-O!w(z;oa(iY)5cE4whd6se|@%9`gF& zMSM?OLsOvd%OHx$_c{zZ!~!&WR?i}XOU=wuBF&DDd7joWOil~nKn-i%aFy*mCHN>2zm~et|w@wy# zzN=%3|NX^zTe@M_#$YT=iUF_PM5KH#3%b>`D8}V?82q(2MB=OnarWx9)y(#{b~dWSiq^&y>cH|fSD$WKy5EE zFqN@D^{(X9FyJi~_|kt5E6QV-(|kl1^F%!Ptfv zGg_l#nFSyI;5(+H@YtsZ@q!D{Ag*$V!|P+}#-ReDqVx4V1Eb_7A=B5y5a6H?ZV67o z&fXI6vtPxg4sK&3=6z%niT|K0n4>mzFUb;+U~&j%ZP)aAUNaT zl_4-Qm^8&0lNPMe4|L#Jz(A@(C4EOzLa-??BOg1s-^0FkZ9N7&jW9 zzz*-mp}Bp_D5hP4DJB@>o0kOTdhX1T_)a`SCIjzv8;ViNM6jRy0xHTla3Vt2+HKdt zDEvI!O`k@x2VO&3TnRk+SOYtVJ+;G7Io_x*hoHP$y1r z>>#}9tSSU;`v7S>L@vI*Ucn{ZbkA7nFn2><4gdL_RF;eh8PpyYM$Rv}4bAHTX%+4F1oC(dcW`Zi)$% zVCo2_WV^FKLv0M>sNIg2JY58$%X>KgB0Jh1XR28UV)d=igTV9W2WxPo(}x8ZF?>ima|W=Oj$fMSd!*X9Sod??8g9GRuVbT+o(SCdyl zeu(>Rq+h{A6q8S<)dgU64#R_j->g*pIo3r$4v+OXcrpDUFw#LFtsW2Kl~j1qQx%+~ zK0#zL`3j!6Wg_ay4WgKB63lOcIjhhq*m+!!k-Fc8tpiuXkOT4TM~@4P(vwc&4u1m@ zG~(fmUJ^T`QoU0GM1f2 zV5Lz25ehG$DIy5^=AVJ+eJ5>(K3ocFM2}-V=qq#HT@RV5tf81Ul822F!Tfhvi&3nf z$BenshMhM$uq(?PAo@bHaMT83%G7iP{`)cu_y#hX*~8d*|5PBGd~2S%Oj4LGlFSaz zTky8H#CAoj1B7NxCnt$z%($4rsQJNMiuodWbPgk!!qAb-+NFD$MR(fp;;_4{_UHt- zb4Q0$Y?dW?9T`wPcRF-wJYzrh>}Cavm5A94DGh!62I?VuVB-%CI?=J)ODvrrWi>z& zoMGOdl10b=%%GUP3G}|vC74fAP2XPF#MdAm(M_(X1Oh1x`#+1kE^dZAfh(D5eMgJA$Br zeGR*7a$!vCIl9Yf@AN}1p2R396 z1B=5D#rR700s?|L;|xrW#d~I3T03SVZ*p-qGXQNkBv|P+3K?~Is9g$JWL$%Ht%_*<(HqcTN-9wc zwa_8+C|J2I12s5^KoOoW4n;z`fwGW1Y#a#Y@TwyMAEkPxiSNL!-2<@HNNe1g)Wo%Z z8Hr@T`&TOhoNv%`?%>WT>{y@B+R#k$JX$+F`(}F>oeryLZ zsFxzY>Ug>YTnR?&&G*}Vm!B||(!cTOZfidNZZNKYql=FQ=p%I|hMJr@-A>k~m*AnVWic znm{~h_a&JB2xi47dr`~4D8^z>H?G8wg!4sCxNW&NzFTOCip!HIMw}#TagrPu6O2^@ z=_4d{frr=svW{C1!Cg3t`~(w_+JYNUHQ5(Tn;coYw9)kY=AHx-L@9e+ZQ|KR)(qD^wZmU$ z+90dsOyWQ)B>igN!N?*X>KU?4AD;;;-Hp+n;Xc@A3*gPKcOvCcBM=x!q58M`p)BGH zcX)#%7EjuE$!JayjOp*s!f&$|F*=^T*zrD1!whCkkYyWSTQ~q(Uir z*4VksfyQ1OCBF$aJ$%K@?!3XpZJSE#(DsMRAXJU`I}tfgMC~i8v+3jwkzXj{iw?>0 z@`GKG%D)C;bgGP=_!hztK@T4LPg3P5jG^~U7Qq-VydWIChGi05`tT9+&D`Veah$L2 zL9Tn23G&5Z&^GEG%Qv51|lC4`v<7@&X zKbPevZd^=9V}6Wc@(E_XH!nQ6c@lFtu@6r;@f_!cEaj9MRA@=nId~}vJ|We?z0aZN zZ8miuHSFI4cajF87us|A*4+0vq%;f#y&ZzQF5U;F=mW6A`2+TzJ(FS7b0`(%tI3G!6gpvV1PMR+^nje%5C<4-A{;aL4*zAELw^r(_HWST z11&@F)4j3iul)$3@yH_xJJ>PgC?1nPiejpw=x81g%ox>?qRE~Un5_geEp`@OyyG-0 zqp!@0#Id3oG}~XXUWe1+@YHf_ciV<*@jHdStszISIoH55 zMF-x6@8XQAs_9A-Nk&scFkK&55wSvLVuJecEa&lfg2Eg2!L~rwHzp9OHwB(JhrE=9Cvb32-j z<}JYt30Ww5Vdlb2v+Kjp1~`kt{TVQgT*q2RO@)-Yr%V>O8o^IiDRGMsU>Xe z9aDI2>&m&h3fVc!0#Q=vPw0909;&;h5+MeF+oDtSDUc*tY4rr-ufIt2X`(+fs;L*B zouDt+LM)3+KjyIfnqd$-LXK@DPNOQRcff1&IoNt$8twk#%|5uH3_3ZrOgWwg2e0fv zDbgb7^y!72!Wm?{g1|lHD8-D6qoZjdnCwz}QTW0$%x9loe8uEEqc-X?_;{aU#eOzJ z-jd*%g$=;X3FUkkS7YUud4Uu?A1X>@&n#H?{;ES)qJg4uV~Nfb2X7gMD77q^)9vPJ%R@T2xB zJLJiHII(Uy93aig;wp#Z{$SE@p+?RPf*`=w7Ld6qa*4@6|I}8a_(XtdPnFT&=N-YB7rpxtC>APW-x24mvG4V|amZ#jrA7V63L`F6HLYN);!nQoz|*3HgwoxH1ODSs z){QLiREUMD%!w%4yBU0=is1FvK30RTW>(}s<8JH<7R9aVhwPU=u<5@&XpV9w#W;o2 zNpmBZh7b>C_~>LN>`)utz3LZ!H#HdV7!U#pze}KYc?s!3GeLF#E!w zISTDhgZRF4@Y73xR6^c^Hql5wO_fLYI&MP4$S?T6mNU5Mu@Hv|RCtvGM31YmkYY@a z($V-4jOesb(0MqB2|GxPV$xEu$UT@nbZZ1HblJG_VDiTVdFdq6)C4y-+%|*_=_D@lCTmYi7U7;hhoAdqX{LLxj&Z+Eax6(v`T(qg-NsV zjA3KBj6Kb)Ono(^S#Ypyj~ui`e!;UZ^X+QCI)gqXn{f8YC^(qHR{X#l>>|z>s_Xwcj zn2(!%M)d*P__2a5)!o4jS!9W@NKzm+mS9Q3o-;Bi& zaB{w2fAeBEryzjA*Df>OL^87dgruG}L9zrM5zO6=D8@gjj7iq~g_|n$nROO*5U?zO zb07T|tfbCCz!m{*!Ln2s$Ii1*2i@G8;P&=AJR)DzRRPDLb(W0n(c?>@lA8(n&%Bsr z)lz7{w4Lb ztJc%e%)$<6Q(i|g;l*TM(3lTvK8I1v=))A#PcRQnmNUOjTCfLf zTd-yKB!1TWN9+b;EP73vUxvBwfG^BJu-RGyvcI=OkPAtNyHWsKSE--~-@$0Q9_CiQH(;Bl$3fztU&v!DVwsY6~A=`!O*z~ z7m;=mkDWfy)^(DWhGu8`fyL)6$hIwnzURY`$E<4*ysHV+TURP=NM#Q6-HhLk6~LoQFsqN3zb3TRO%kl)PsHNWxSt$*=U z5`U1S8j4K@nNkf@np`=oNs&X1#aYAKBpt=%*g^lWG@v<>mzLI1a72L&T4{VUlmNPK(d;^?PmqWJ72k_A! zmGs)&mfW5z2*&r@K+#K^T&BdT4_A$P1YPH?*^$?$V%0_gtwW2&u&##f5WoB;xMvVa zRl^CGZ*7Ezcd&eUs~rExlz0;9&V*mZ@+i^37+I-5#~{>DmmuQ)2kxuMXSxKwN-z-wQ=BCm>Y=3R zb>Im|8I#ELkh7Y+rl;Ua{tH*G0a7f&*l6OZwz0U7yYuK0yO}wQfV}^Et(#f7{@E}) zKZ$)gr<5+}wUXD`34%e}R)|`5q%pg$Nb$?B<>S*ttbD6{BUkOc7^DOlg4zLfRL+yI zJ)NY;w*Y@(HhakmV3}zkSI|+xzQQr6pj`uvEEojMaWlasr;P2Nc8X%^B%?_tm?brS zBB|mlOwKDQK7Js1G8btBXVNB0@iqjhg{=bLoCc_yTMlWXQ^DxdA4qB3z`pg?fi20= zjMU5-ptCd>ZL1%MWHaZ$TeF2Q*JB2lMTOF0N||Idmk6fIGEDT?4>Qj1rTEqSF>ckI zP_P`g)i%6t1n3#oGFjhRK}GK#h@C9Na-PDzRMz9X8mM*~GR(bsFnsPNRBrYSPKCsR z%$Lm&Ho*>7drYU8X31#s2*!6)sA&4%*NkzK6u)BqKrV-*U2E?bit^hvp!(WcHZS`x zxc(~v`_|*IRC@rLxBWdkNOcH&*cB#NTuUZ)pBp;tb{Cw@iXpGw6?W`i0E$}7;kCe zbz2fr8`{TQx;7go-=6@_3rNgCt_XIj9RabK$wf%J!6yqlGU~ zw9QAXv-$D!AZ)y%N}^tg694roxW4*5_%6JKA`<4I<^h3l`bGtu-B`z}R}aAU$0c5> zizS#^f|>JnzesAxSQfISc==8td)`16vIdO?^^9}i*b@d!iz=-^?bY&v)RW{hinx#F z@Ard)0orslF9z&Eb9Wqv+d6?H)60qTnfiq7ClOZS(S-Wam-H8c89a&+H60tn))-6i zI|>2Snx5tww}-F^3RzGScnp@!9!4><4R*rV$C^l6nZ)nu#KH^PGoZcUCi1*J1}(@- z7QBjl1{cz-U`<92wEfpYC(Y+Siupw_k#+Bd8f~N4Xp4XNs=FMjnw5a3job$D#B9!r z1ki@{YNF_f+aMlI*d|?6>q{bDcU^|!mp_;&b69@ z%>L~t+wvmC+?8O46U?gGxy**gLS|`i7p|TV2UBvBvBmdzaFnm0rJ;w9%xD*$+lv^O z;yDQ!g*AeErU-oX)1m47`r99ZKXE#%hl?&f%mF=}!7%Q}N@V>hf?{$dOF)lcK0cbn zEVQ}EvPwd56Q)oAKC2YrdZZr9G~bG?e|?M=>nHWbRup zxG*@JnH1lF!wqiW^14UdM&FU(JLoAS3?lOP7(>+N5(~xCL*TlNIjWa>LUxz;p?|ar z8re(29W58}zL%tUCVn6vcxXAV`eG1Dd5-94gc8g=f|+$jUeG-zm>Kh}9S{2Rfy|}EQQ3y6syE?ICqSg0gZhChwshfe-7la@2~{yz1N&Sq-}=Ajr63L5HE^Z zO)!N;;ewHhyBL}NHf-`#4O~h?xK}B0jN|$`u-`*^Z7g2GpmG^Dpza#0t6U0c;pDvF zc?A@mNQEC2=ZN2(KA-<)3D%yN!_A5MiWMH(qv5TRZ_n!z%qD`FB;6uVd$f(&^}P*C z{XP#@`wf_NRXVrZ;5#HZ5PyLonZVm!WOpa1vvqz)!SwS@P$$~8O9^|yW$qC;cv=y^ zEV;;@4oP9RufEA$)Nnz2o=YlF3nY`an_w)fO_|4;dl;S1ZTQ09bZ~f*!%E-QyoyyDJYU@SULmh?h#$IeGO!bT%c;|VUU0PiIW}tm`zA8VN(qbaWylS zp~&1rbkat9(@FCsn2Jd=n2Ov$1_rg`22mCpcYO$ORVG|pVi#mRONWMmjzuG z7x5t670k*$9Srshv#1Ag{bEnBY;A&Yqt8O=2`iy(@_fjMQeiwJ z)Y0mZlH2pVY5eL@%Z-Ux4Q@`7fF#26k}C#%LbcK%#%HI30x(ZBKZZ(TU#mi+WQXd7&DKXV!Z**+FYg{ z#E#p-z}a~_6lV|@(&tB@Mu7wh|Hy>ML^+hJ@RRi~Z-#mE@?hj!FRHVN+^&iK8(jv{ zzLL&j_nj0|Krpq7%$W&>1K4@4ojBN7lheyS#p#DwV>RLe7oT|qf?kG!s~LHW678Vr zy#!EqybP_&l+eJybav){_3&@5BDzq~NlQb4XYye4qj*S{y-T+of3{N$PcW+6yaYkr z((FT*-`Mi0FaPHFbgVe^J=d+PgL<}xLh-LNu&IaGvIRvFJ0sG_Ox$^nwyL1%tL5RK z{bNwuF%~6}295D<2`FpNIVOAPFSeC{Qb%nY ziE|-`#p0TcS4}ode=q{2s?C8qnYZv){{s3vNC~Ac`w8=2R&kmeE4XKt`V^BT!MrD! zzfm@#zWvvk`-gk5UwZ=1bNqzg80^9OJjbJWr;`+;l|<^Enqsajyp2j?an=fMYWoycJZZl?=x7=UrZ{q;sQln*#-96&7fc4cf89hp zJ~tGve{PAi&m}^!+)bDo^%rV_3n0FP7-!iLQBnvA)7U2sabY*X%ZS*xS?p)?+|&>ST>dMH^wfaVvB4Vr=L4V<{&^HeR)lTk(D+?#r;DO-sHNx1i?SPuhQ@U4D-ogk6Fil}6}8 zMmN_#u7bO5d;sm5PLwLMKEqkNec=CUf@p?p2p!F4H;R#aLXyj0bPD(NyD)>*{^4C| zmqA%^JU2F6hZa-v%E(?>QwV8a8X#-#Ei$S{bTo@BjgfNucdXc+jhz-cq6r03XysOA z)HjlR={*R<|Fz%8;%g%QcN$%ua5Yj3*~;pUjCH%3N2T0QE9*FiD!0eB1NE;`K|g={pOV z$48--V@vtl8Y+DIi0$a!K{>Rfxeac;ISW^d2l84Y=2OhhwRF-938wjanJ{oU3GD$X z{+G>gT;R8ri+SzFX`L8_hQ;j$E1fbZ7*E{!CKB0bpjBa^Sax_TgpI zg3uDPp{P=L9~8WO;Mv_jIBU8Db95cWSP)F({%)bwys6AiHz|I=`!U$~pcJ=c-(Ari zA|E}HVMbL${&`Q~)Y)88*8U6~;R`_S;SW%ipU6M`nvElx!cbL^HaeqP2#rVFAgV48 zPhM+INApU8u_lQc zX#hVxMQ}GR0_m(ye7;8oJ4MH$lEN`4ch@CyY%~(CuGYch@BO7qpja|#GYLk)9Ymex zbC?oWDW2C@fP+?kWUrl{%8F|?4!50I@u8R8`*P^{kp=Jjeu1^iMOJLtdXDV3mF<@jx$9Y(tU_4;3jU{rs)^sK&rc(m zf4G=6*dVFdJXuLGE(EjWxTEN*=rHqkycAz8D<|^b7Yk#8_OWPy4(KJ+Gd&|n_IgYi z?Tzv&>4lHw>saR>8W3wN&0cPi zEEWA%dYUor|A!6k=rfboXM#)9QL3}4?zUiEo4(Luinted@Gog3Re79!wn-j3{q8ds zMmDg@e;HEyiNT!+WP@{Nz`*tyM8p(8F@_S1C&9$vMWVt5dCXXHdpg;gGy8{KfRsh4 z?7X8&u;pk3TXF0c$n3fUoXbg2yf_dQIz3|Zm&yQhA&%Mf3Bgn3gw7t#gPa-#^v7{9 zoHm;Sn~pE0m=sq!X?qD~&LC&eF}q4;2J;UW8w*4pX z+^#n<$&dQ+#T_5H*Ds5pQuier+dLj*TgE`SqZCsAECQdXa407+I{_-LFz=)ZH0o}r zn9;`_(a*3L7sV&*SdXJJqNHd&b&Ml*uaDoX6*&vEb9KfFT=*RgTja=IM^H4qK z0;{eRPL5WO(WIr?1|hg#ChZC~#E9(90Lj$n0VW1aAEW)8*Sm zhc&Kp-(UyD%y*%fc!GIsxmwisYB2j$sviqKsKSvYAz=URgCOs70+d9Zgw)lFsN{$c ze3t~k<&5E|WDyU}lMjQ|F&jFX#y7Lks?4vfy81tu_vAif6B^6@cwR~|Y0eaLj$q_- zr;Bp4)!3#nefUzT3-XSg!TGOP!sZ2Lfak$8Al*+qh$DqC?Aak|m|-{I2`pX|3$JDe z!sk)ZD2pA2K25yDnK9bP=e-^D@uWS*0rM=$XCv2_ynP zN*;gyAxngOxghS7?!G+))f5OJ{zd>SS}+xltbelCUXwc zWRSXT0bAc#3_@>-naPx;6q7?R-&6W+yqyNHXWM%4iyg-3O-U%;d+G~o<0AqCzYCC= zFoG@taWSQQ>lkFUm&CZPDuYd%b4B-NTOu2`(I6Bd97p`Strjl!z5GF~)bdz9; z2}Y|oN1#&L!Ys_{#^;T?QFuoq)?X0>Gr!)2l7E+BLzynBTPcJ(e3ZKLh*KBERgNR= zw{Xd%)9|ctzUa)tQu5i=2%iI|fa-x|Xw^4~oM(dr9Zea*82A`6Pn*k`R_MYpq|r4W z#p3)e+o1UGLufR=0p_HyN^G8G?-c__Bh8SE?r+dm5<%OgD3ND?FC_c?;6mm0a=j&u z(A%G0mbngtw6O^ zU8ly)Iw})U#=K^b`Fb0s51$05S{^bE=j%D9##S_YLoHklA4Ec*79i{AlA2BRLW+4s zFpJkrWcpkZ7{#ldcyC4m4t{+GzkU`D20%o~gYUxplg21v$Q5WzN`OW8rl0~MW)@?% zI$s7qRU^3FwwLkW(!%)sm?C=XT)>Ie5F<^2q-L{f5yjLI%(5>!jC9FS=FZvb_LqV#hXBSqs2!`N?Zzl1kt^3S1@Vc8Sk99=))W;K zWYX?cai^Eq9N4S;4n!h3G_3nOky&f=acwntsDB-x?#oAoeME8Qy_%e*=^@Hj#GWiI;#1Im3~OxC`}*2BXjX zQ^+x!%}Zz{McxLjKglGRJ#pN3UU)wx2K49 zUm6Bp6))%#7fOrVl_KbC^#^He_|*2AdNPiHLbI_*N-H`u-=}$haJK{JQI`k-{$SN!)yN>eLB} znI*wk5lrl@9ZctfFeX&172AEVfL?wDoLQ>Q*=VTEnGV83~z56FshAnNi}3LM6LSCe7<6h8ik=0Gf^^W0)nZ27|7TJCo?zg zTJiH=wJcL9f|D7RT*Zklh+xw}ugeM^MCG!)#|ZYvPEt%cPypft=9imK!1<4PFfoIe z)Qz7D==^kel3vQ#It)k0CvKvctrCnK!A$3lFk^EuGw(<%-qhg2PEvgiwO#*l?yCPF z?{pG0_?yF)5shriYG3y1%t4^E=qB}tE+r1}!!AC6-G^nE7eD7iN*4FsAQX@x7O47{#^qu*%bm>noF?A0E}(=J21^Flf*zq@^LT zVTOxV8$7>w5c1}Hg@3oy{*{PL_%eD7^wuqc2%{S`(CG)`4eu-D(aPRf2p;#3qU3s3 zplwl)VR@jW&~C1SMs8~;Gt^I$HQUmLh0nKe7yt2KXSIaex=RUJWdxI#_DYaz zI0s(_?}dW=a1hIRLaxXlxJbW18flvx2aChRXW(%$ z^|{TljfI9?pP~80PT19}3U61BL(Zj>uwK$N?rg?oiZPLl<`ltntRF3EQ~Se|_5HzK znezOt$8!9-EB-k3i=@*_Y^R&rIRJ^{5Z$Mh(c5$F;*n^Z|1r2U@)yiyv(cb~=4j}s z2$p5+@Zhu8nauIGL{jAUNiv!gg4uO*nJ6ixig_8(jT4M_+iv&?g7ZC<~9_p5P|yh zY4!~pCp)kg88dFU-aqiIVL!= z7mq(1%4TnL#&WA;@SXFPNTxoGez311ZP&#MiE#P-9oUqT4MjeN=%b$-)3mgT**7cz z`GYFb87qM83P)jtj1GJDf<2wITXu8_a0FA6Zz?h$c9hBf(ub9-Y(a&cfF0Hz$3NLA zsK+W396#O%uh3q|Xt)Du8}5Qw;IGDxMaNo650u|t?6q(<^6;nvh1O~q@AVn>1h2%^ znpd#++T58(F%Jml&;FOf3tjBW z+<`2oa+)5eM*NAZ&g%2JJ3it04Z3JkQVO`_wnJErJZk8EhVem7UW_S~U}^|Pk98Lc zj_zhYRQ|)8P7+7Hry_27h#_8CWh>L5Q4dtN6| zfnURqMNpIq6GJ*lET0N0ijd_QdzNC{B$&72(af7;F4p4j` z&99m{hhmmW9yav^v!i>7u;{Nnv;Bb--*V$Rb`4g+V}l0aIHHK0osK9*{1nJCXJ!QA($C& zXN#uzSTp@=$fe60h`$Sl!L#;_qIC~R&F21h#+P_IRmN4*vYl>F6Yca8OGX0gRax_q z7O?P#C(?bakEYn3ha`6$Xq1`?x|wwhSs1#Up16K&O$d8 zk}k1j)}TA^F~uyDENBCQneuL#C}M{{<2Ff}|888(uImnkBMwIF-S~-Er;9`Rp{SqO>CrZ&-L@^N}EbBbyMAmBTo)9lcEdF z;9Yiztu_qv847Jf+u`@^yYz%zoQ{3&wJPMA9oJq0<>{pz&G}*(&a2r_NL5E}z;;G1ii6V=o?! z${JBa=UZk9(Whb0J1n!^1J2jKX0<~vf_m5$*h4g(UK>iO?_k_01=KV54$Q9hhpWa@ z(N~pdv@Ssl4NJ_2NSl%9nXrN#D=HQ|UtUNtHzgQnf_V+B$oF0&Gfz{BSI;qHZ?<1z z74mmOmfi(w%_4SG7N^R4{TD@@EGkw#1z(Lgn5txpCQXb(TN|~|3g#;4GHU3cNjS@S z&jXF6q>4y>!zGjEMliyzTH(qa^~@UkfB5Dd7CNngn{h-7WY%7VG|QV*10}}P1w_Eg z1FFczuMTWNE`n)RH;f~lvXhUfpv1a;kmWxVz1}9x{%7q0H=N4oXckK_TL@<7wMD|0 zci%93W&82or$bO&_-UMyy&BxBZjx78A(SgC(b3pAL_(4FP-Kw*8`|=2!+q~sHavSc zdawTmA_XJBZJ#z8=KP6OR1Jm}3&|1QUJ1sFU^C3+ zeA75^ml45}k%Q2tiKP&c91HKlMxdJbKH7rSocAB|c$_q{mm&xHYp1iPp6j9CN1NEH zPE9m1Dx6MQkz_&p5lnVyxwUwqf;63iG@gOik(f{o!_nvOk@Q>7SjNp%g@ zK`z_>((=QDSu*UxsB-x3Lo#!orLr@2DWihG24<$-cr-s{6~!b;Frfsqd(l0?#TUmI zhu&_yVHF9hTa}G{Pi+LRqzY=PZ9>9MXC{`wJ^2I(nWKl|3p>Ddp9ub~K5<)baR&J7 zMZ)vVC9GqM66$c8z&$+%fbe-EgnncBl&^ zxe!GUVZOFH61SE11fK`B>xRhpIf1s*7Z!Qu{mi0ox zXX6QsWAJah!`KSX3?GI=dgf3+o0995aLjHf5(fo{b)6ggOpwjrdWbMDfpCS1a3lUZ zgf9Ppx9rNsKW5*=wWeBp)Q)i|+DnIyrdCqu$|jf*8_WgMPiQj^q|nt*49h13mvVVF zqoD2`$y=RM1)W(c$m-xt;`NjSsl^6pW_BG+Jyr(4n+}3ca}(72>GQK*bzt7G6Aw)! zMu=JC&_1k4F%KohltS^O^>*5R=VX~Ka>9O3WeQVL_=nS5q6G0o;G(2b4Tr)9(uOi| zv)`JnLs7)U_pmeUE`-G#0rLK920*3m~qr(OnzI?feJE8kyLJ95KP4P^MbvpcLWJcJD#a+1JgZ^3G<6qv+5^)LP;xWD%U#; zW;P>W#n=i~Ju(cec2&~RXvRiC%Y)7E?bZu?;Qxp^^SBfEs`JM0MYfe@F#QgJkG1f%Nr-S&F^Tib|F-B|DVUHbdmPP(s2fib=K4UA?L!IVgA zXjoK4TS%7B&5ROpjwexkn;t^!@-r~fbp=d(u1uq|<6$})1dd6|=tRvhbZqf!VTT?d z7VmoqCZt1=s;H5tJb!iL*%mpp_s(e$dHfY)wWOC=7-6soG!p!5Tq6Ah4`QKjEw2(3 zV;ShUw;GP?$r^efhRlT1gIghF4xyDT41<#{X{ z4uYYu1RBh%Xg*ThGm?eO`LE!_okuX|#5|}yAtxL?{&zd|kbH~QeGC>bE5y-g5=`W8 zQz~TB9%_$r56(XImww+JMq-b?vV3?wA56pLjD@?uW|92P;ov{i66{t>Kq0k(nA0<$ z{%j9e&;0>guKXvU5~plNlZvC!m*xRDvBOi6bkEx z$Y9rr3Mk?~5>I8n78EunLnH-z_-^1C@3D6Sb4zs04fu+eBYWO1(wKFsd zo~(#Q9>l6eiu@Ufn~gESEb*B{<>{QKMy&mYH>_5~6R!<|&2vX%X_A3wXMY~t9!CiN z0({aE?`NagcMozlw?kccIaDRxhV;cT@MP@{%4bO$`mM7NwJh3+qHeAeFrUOimj%Hr zcQ&Htv|gj~h|Z>O=wv*3jT$U04ZtTzT}IRW4D`015W|EGt_n39^QYvBZ~kWp_ihI1 z#r05>avx$US3;X^I6A!07&-rPLB{Gcg)f4B;tzoh!91TDYOC0MiyFQ82j(`K;h)($ zxJHx0L$35kY3ojdicbb)5a(pxFr#hK4Z*dS4?;UDeH60DfA7wz1@F@9@O-itsv|zQ zF2mhX?|}ZoXq?1nGm~J#pMTH0rIALx_(-zw4p?ypIhOe5z1?`;Ms>vZ6c(-{h77xj z?Mi7DktYy!%JF>2JNF&#M987Vq)N3l_$@5-V_?SH2G}tmh_)`$L%;w2oW?(!Msd=d z31+fYu0+W%ntHal7w>rf2(Rwigp(r9;puAH$SCRzJ!ln6DSW3r9`jNwzWkt4 z!;-UfH>BhgfcrO6O(z1SoD)AFsyza(EiQ&&IS1srX*~MAfH?Y^4F|Vq;vaRbQoxvt zn9T&!cc?=$g8%~-ob}i!dvL;Q2wL*En_k-gINo+3 z8uQQQx`>G&n8~+yOWKOGsnO|DT!%SLe+)Rx_BCMEHFOx_b)70iI-+u^4NSQ*!8Rx5 zMJ{L>{Dn;+V>#=PUYs#-G71`*0i!mWqUgBgv|CCmE*mJ8AI6B!CV^n)mBdMwn+~8> zevsns*0!=OePfu7!}C}^o{CpOW*An%&cUtV9`-Nh{7Q0Snk<)RX2|iQ2^ODCD#6@7og-1TSEa@qOOvj({@B%UAL|l-f$gs@ zi$>1eOoAM$A+@I&A_^V|a-I(m1tl||LR{_yu1c;RZ~1!wMJ`E)o22(MKemWn{`&)V zU1uO*T*R&OGQo__dntK8U!Izaz5& zBzi<;1iSj$Qc%i>runcf-X*?Mt`r=HG=NfTK0UH_7RW0uX6cqibeMb!%G+cOe(Cne z)!r4KN)DoTUJ4U-XgLv6LNGNELl~>0gQ>U|q%`C-nqHpxmcDX;W%=HyN)k_1x2R5# zS_P^X3mA2a)AU^LA@H}*kyg_l2C4IpA}{s^btz;MYFaZKmzInJ{g>*(E^t76HkAaE zdq|gQ+G|BMNXc+XTA|eCo^E=-^CFf{!E$lkLc3jk3$rJ`0KRe?q}vF*2XXW50ia`L zNzZveyzXWmLte+%vwL10LgiD}l5(mgeETXZV77?QrjB4XtE(}k^3Ifji43>mk_uY} zGho=86Rc!^KPZbhOWT#aBhrx?l847a^^PV$`7h~H25PWo(Qw+IGX;mjH1w`uD%)>M z2)dw{hEumqBpnm&Le1ueh-oI6`;5)q@`VXK_P9dQUDOb^pqrt4vwIirC;X39|IC*aBh<|Su zi<8z#F#YD4F~g?srIL=xa6bCw?2XA%uwdy)mK$pT&4B};T#f7i!B33;TfTWB*3R~wtu{!vZVEn!T(@#B;s;iaZ zWG3q1L(yvR_3eAM=Fdi0_{ksm4-XIDhk~)0=b;8zzc?OdI=F+w$zSjw_AnavB?mB!aL^i`SPY{u^la9qKGW(LVwCHgeaGq;4- z^ZSSzaHA54QS&Yob0HRa-OND8HAYc;uB}2x+Q#6>u?h6=q2xP>{B=wdFggUY{){U(@d^I=>3F3_vq1Z~FWp`um;1(Czj z(e>w%x|av5(XtCEMxJ5qFP(;11+i~UYl?swMlk!<4rLlm5~$XDvfLCln_A!?j{}3o zv3xugAHSQX@*Vi{L)u)D%T9IyKDN5Fcg3%maC5gJZgUYRuY070VF=|#~u7P!(7OXDsQX+H~F7}cQ^lR@-&*DxBVOJJaq>GZMK5O z99fhz{w&%%(wfd5H4oY9w6iu-G!bnidZvtM$x73exMyflPLE}|JF(wbf879l zX@)Ap``MJMRzo2X^Ya=gzk+P&eDDGI7A(88Y)F@T0`m@8pu2ZYqKUEH^x{bq(6>=b z@g+$ej7lAV_$A5ixEAvtiD4 z$(xo4TeD(W?q8lSmQAEwJsrbasT&^a4>WP zGQOmW)7}Sx!4Eq~=G@qaQ%FE}{1XAAB|e)K1T#4Jp=9YaJ==6Q8C3-s>lfa<fX zZuL*$EFd#gSOV7wCLl|fS#c_y@t-Zr&00E|m1#G^_0u{To6T)tWAPCzN?y=Wm&X7a zBL%fuw`lkG&xPWB%CXI8yO$mN>R=UVxTvNJ*5}iS<6G$^b#bU@S*0yMX~8xECWl~R z=4&yrIma1lwJb-HE+jLHU$Q4Fma;*UIzTg}6)cz+^x(z`klZQ(4Yn+m@T18QG35l4I_mwk#1Cj(rM=(-VroVX?L1np`tewwxxnWzhKDr*$;X8485Jo_63T`$g~8MV^Ff_4;N&w7H1m%l8LskzF0oGr)6 zFP;R+fr0r7L%*{TFa9CTQ*Xgjm*#`F3aiAD8!=G#>{F2ztCs2jiNoYAV7FLc?+ z5`TN*L9DZoflPx!Vnka4-SWi{pLh<2O;$wa{!Pq7lX<9Vxd}=izZqVhJq|B3ub}DU z!-OReFHTxF!G!!%m&nD%GV?U#xgp)lAXXW}vur6mt5K1JGmzM+9hp#gy9_kLYhd=c z*Ra#~J_Oyq0MFf2ka`(I@98`R)0FRlldA{FCf)}#v-4<6le6$_!bHp;g8926d|LjG zjm(j)@|@krG88r=7rys@!G_DLB0fXXv^`I__q>=;4SwH9t0~cQ#5}zMb*~>l|9nfj zZL}rq=~e`dq4UvdT`%OgF#|2hloFl|wiMnQh37KM zqV7k~Sy@8jU;CifVFdd6WHV~7uoE!a;*nz{!E8}To4PmPYyO86f@#=-KTNX)>%v^Y z=e8~2KA0B05HMDjWng2{D!iUPNd?f6`yHaslhBPzySH}KC zqj3{QV@@!O%QYl@Qitx%DN^7P-|xk%H@U!#NvGIn$vViVn=~vDYZiVqp;o0}n%xdf zu~m@wz66&08nb6U-()pz>7a_TcBtQb54f~@uq@ase^)SHw{zdc3zNTW5@1>nnBCh zZCmw^Cy8+C{8~ubLWJ=FxNO}2C z$n>&1(gRKJ$T!c(O3+L-;mo3Cxg!;W(Vo*&p{>~%opu6n=-;0k^z5gAaS_jHiwS1V zs1ixuM{Vkwts>WOw}p*%_JxV?i1Bg#4H>G3q58k?!f1E_jGz8@FfO?O^b-!69F4h- zyf1i;zYQ|;(}K-UCZYtUiB>F;=jIPl;`q@F70&{z31)=qbIGHh)>PF>Mb2%M2|J_5 z4y1_SQq!>t(g!+1=HgzVX-Q^oE~#_=fWDmvA#dRfxa! z7b0>?p{_U+th9bYQ5GqjxJ~Ul+#s33(&ah^I5}fW3kO!v1W5Y z{3!G%nEJ9_$;KDks8i{RoTq&_TXJV4B;7G(iyp6s))QCh>nT#GExZ_12Hb?5@C&4( z8|manb0BEu9Cm@40lm$^4+S}-&>PVL$(thAlB!e$dlFaxK`G9{x! zsQmk6r7eEV?p9L;$Ij(!9A^S?pLWxCuF44N2ZP|NpeFSjyt!0*w}l~meb&YFFZHEe zxV=cWNsX4Lcc28<|M0jiqu^kQCCxt@pae`9!9+W$G704|RA7rD7rT20>!0?CUa3Es zRaa93^{amLz(_fC;|wPVV0`})z2<>r!RpvaV-3Bx%7CaNLs8MSY4m~SgJ@9cWn8n> z6dI2W7BJIk0TWL!+foKIvRpFdprpjLC&=Rsv@B%IvtxNVPwVF-df+?-)IFCG?xd@6 zABnBZr9+OWK)@VFx-)nfbl;CdstM<4^dK0W*wunJIaolLrJR7l;-sA-n7kzund!$=Z(nU>bP@`i`>&1-* zy}Dz_`?(Sf$tPN<4ayu}vpIiJ3-OZ{FD`+L1ml=Gmyu*&rdD|?anm0eV1um}>GQ5( zEN`0=X52?lou-PKu4Y5sm{e#R-3K!-^n;mU1Hr=ihHzlYY>q?6b_c_!GlA%Zb`QR2 zl!4AOBIcR63)~_YE#1w`0-GDukkd-s5A7{DJLwpG?@ciq=D!RQV%7!bn92n6q&tdewaiX&ELU_;Ul6WNt;1q+0PM^1C$XNlU?26#$K9tlg&7n3ZCz;!SL+^P+#>m@ZCj>Wk_p$!10S9w`31^ z!*H0rfPBk*J%)S_Rl&=#%h0l=jd*9PGu^V?*PTux#amV>F|;~}@bjmrar2eAce~Ca|F7v-p?fygd`cSppWTAT z)f&jK?XnOfx<2(Yxn!vY73Y)SIsYm|?%jc=)^A6WgRzh}*B8mI8-q)u-oqc#NXsvQ z5b^h>mS9e78qR3KL8?AdnLD>Y9W3mg<134%uuXSwlG~0fm^VQarMX=a5}0{cs~c}W zf#106aBSm9SQxz)eLlAidEC#1<P!r*%PO3OSH*lLM( zR~!cyCl6vsE00$Uutl3b%@Z(>#|y9LCxSUL#6&VTx5#z`!K~xlz;~c7=ihLjk_nW6 zY0iB()K22U3NL`+?DN2ycSB}cv)~Us=0FzBjv0igUqews_FrKB0m{lq!;uy15Zxel ztZXtDFy9GA_m_nvVPw!Wn>WgwRsJDtv_1`gty)dBB@zdo@eklm5eeHOU()=Z7Mk@9 zK3r=AAEF@$IK2^WCvQR7nKLTA`d=p>B7AQhf3_npAD`2Ev5CySovZPer zLXy;`%vI=i}j z-km4qMHLJ>Fa&uRUj(-l3CJw}3Nqw6LNhK2G(N_`ji=toa!DS}`I`wbW1?Ysfd!lJ z%?g#P{uEYP`xpVEO)x*M7&Gq_^_V3+%G}LuPI&*O1pK+bDHDV%AgKEpNRJpKJR81v zAOD^Y5_%(GPT9SJ(Z@HTb*}ncdvP}1m1V(pxL(8VSB#MQq7(sx#L*ZMj8^(WMs1ZV zBi*gcO}^!eKW(nUP4OQkg%`+8$F$clo_Kc$JW3PpZ}``f58LWBO9HbUuOO>>21%!x z%{|y6jW;KxVBaYpz`mC;?1N?b)LrKUX3(hEe80#r^qX|EkS$H> zqBt6Nf^qN;XKXyRNugVrTl{?rtEP7or`{-_d?vO-;f3FTUdRJq<*<(%3$^!>=sfb- zG&eW^0^eC8FYQ3Ew|T`J7`N&5yii1&>I)e8al*6lA{dL)k<63WVQjdC zGPmkiFSF}n9Ik8+qa0&8A#d$J;PlIA|80}tVEtfFGC4@|M|C-qo$#P&D)K0>gl(aP z^q32c^xvvXI(pF;`rnl!C@r%>IC3l(e+YaDW`AiEv%k)i9YipDbbhldWS3*hx*?2P zU^lsUmPQBdBs5>>DpE0o+T}+{dv*mB{q~3BAx@}&ct0@NUqk!dctXE%&7_AP|3bgZ z2|poSPTWT?y{+!^BNB+}eZBBfLaZ0kt#f+o%PPoBA z)iFW^s;%lVXusM9LuH-O%(f7^W<)bxqR7$l2XE20WqRmw*-S$cuVMO(PL<|Ex{_ZZSYY=H-U zbCLE-JNkbzo@kx1Xw|~yXws-KR53qQz~qW6Es9_^qX_0p_H_38c4h8r><3!vMHf5g z^klYN>n}{wmq+#;04eWMfzOa^o$m-u>W^V!_kWP!ZI4VYY@_{yf>6Z)eH3c20;Vt4 z1nc?1sG>Pfzoi&?1d0Lqpdm@u6|2~BMPx3*qG;&RpN80yx!S}_t zg1Hi z-_gfrZ%A6w#8Q>=XqJ~e;?;Hm$M1tc*UtOpPAQ?&($Gl*T8+qm>=-G1?Fx>QO?Aa%E8- zsnR;C5IeoOjZm)h91Nz^K{fe4Reg6Fw2v~Z$M_To$-4_TtOi14$6{z`Jb-!z)(X$& zkGMm#1XFOqC$A|(mGwES%31p%(PD})J0ka7br@GsP91ovyF z;KKcpka0_zI*{&0hbKR$*PqgX?IcfP(@$4)$#0@Cnor^`P)0DHf(P0zkZxlddQ`cU z)>~n7c`vLFv%=B-TIjKdG-~=?AoxR9Km83A20w(8P1>A`(9j%8xh$H=`kN+EHw$L7 z?}raYr(fBj=SlA9{=i6~o;FH+Z>kB#i92qaHzl934(`Xvztsf)OLZ_|?p(amQxC=W z>jN3-hv0GZ4RIj-3FRKYNwKR%kR_Zr&>ugPZ)Vw$74+?Z7G~|wHkfXrhsGsuL>s)s zqx%0n+`cB5k#pYI?o&9(|Mlvh5D|@nQqiJM1U4=~WA|g!nPvAV8{@ z+!nS&;L02bJd;j+{~*h(DJZ4Atfx?Zt6E@`mo@5)azeKIP6^LurC5agKrrJhp4cv& zx|yjB?9cTp%f#1bl!Cq2Xk1Ke2_k&EA%5yJ`0(xx_^$1SwvD~esoDv>X&BrGkHgnT zyW=D4uMpSxGxWwmH^3`G1!XM>%@4mVY6n@d{P3Az`Y)SdYd*!2(QP7_EqQqD=0rG9 z4EUF^K5|R=2yXjc!}`5%LFL?MP$>Tmd?>2BK`FGNmw4v#8caF|TX5*R1e1$qgl+MzIiM{}oyo~y>yrpn{WPYg`A7$+#YA{M+9YBs#xl*jZ= z;6HKQf!tBcJc18ck7JWnxUmuv7^L@vUSqiqbl;l7&FNB{$No#0e?6_la<^P9DR=iP zl*9*Ym6%>u<1SWy#mVkjfZe~cyr{1`3WJU8C&3&zQPKvXYyJusD~X3oLD_x`cO+Va zo3L>PGTyuvo=4fkU(+qrc<;g7`kr0^V=aE-su4_G=_p3^)cL8=ztp%Tk@+}qKoMx4 zlED$bI-z=8DwH4U5+=>g_dOV|{sYxpiXhF4Tt+@0$_1*EeDGx(Q11R9aDKQEUT<(^ zttRSmBi<=;{AfbO4|Y9*F$;2M78e}0mG&CIwFj-niOZ{qR&yHWuUAJd-UikCyCE(2 zHPrQxnzZUKC@(oFd=U)z_6Lu-Cc#;AccC0N3dUV7fSqo7Y<5W-p4`wTjOHg2_B11c zkw3MYxscJ1>T4RnO$wD^Z6CH0CFFG6>YlV&Gi#uCg>ivXs0t~=$lQk}ax zZ5DlfUo&W(vc$VJUBKkv3%We77XmG7p);7+=bY|>rBl?QXyXJ>Yi(mBFXO0RE&rjr z7cAMUyQiSYTgCK-gSRRDMVi7&>nExotO=(5ix+cl)^X}pi8}Xuh8(Q(A{Q!ZV=-?I z%vU+qO(gzY`-lpksO`G%wSnFVPB5Cu^3!5cIyLA)vPV+l)7d(=i`2t#qr2We<+jH1Wnkz9gK(t<_Iv&tuY zAm*8uX>W&5^z=(<^w>ga&^$gDmCbZuwS0D=?W4=+Lmq07r2f>s;GIKktAH8LXCO2KW0zbHz0J6qs*uhv6T35HxN8|dV5?RvgN&KOC z;aE+kG^pz-{=XJ1_3UhPPwO_|wi#&W+&kDnW&t|;upao)DEu4K&z~1t3fRL)`Fg$^XVmtGpdTI(NaIYY}biNQz^}mA?|L@GcE=aj! zjKG}1ng!3N>D*`(mcTo4v+*OCbN5=9ON-ztdn8_G3oQ^oD#bq{mp)mPF`21Iv)f}A+ zy|pngWN&{o+cyVx+QbPeRih=Rg-$R1GhryA@ha+Q&OmuKF%Y>*9i@HCq5o`s18-Wz zu811(02N0tlN#cgn-8^Vhl5(2fwKd8cA*R#mff?Bh)4sQtR#poRYTp6?+Sfu&i6|p zXnU?u7r5D{j50Q?L>KynBijxS+9`Af+CFJ9$T3f$Si4VH0^3Ikn@tMAtgtj^st(K3 zf0t=-duw&U_F*)B9&(OyW3Ce^&joN@sE&-5n^$XD4aA;8jDsGpxZ<7YG<}3C0%;N1r_hK+bv-^!o#8XIQC( zCVezQJm!Honi~Y8yjoTAg1bg_Kh)&DO2X(}OLaNNO(dIWpG4@2*iIrtc>zpa;8n1R zdMX?_GVT|`#x74tQ6oCF8w1e3Yoxwru8G!l#xc8&jzU3KO$5vb5p$Pd9POXvbD{ne z6|Bh_Wwx?%=T$kQ&K%lkKI!!GtAzfG1__hK7w>~E*FxgnPeR-~@{NGR{2C}N)IoAY zD6?$)TR3}C3SaCtMEgmeJ3ktC@o-y6FxiUhB#EBJ)R{S&+`#c8n0DD`Si|u#?X#&I zY(i?`+mpd)aa^9udsb=OGg5C)aIz)ipUEjRL&<`x`trR1wNoJc07QdYEToAWWLwg(3)i z)(md*+rjT81Mk07!O$QUo^4d-=KB1yeWyItHsL=@JYC5I1^-MJMiU}_Mm;B(RLkoU zr?SFn6H7F>M^Bft`z)T}&0fc8UJUE`>;p`1&_cY<#;vrBSnIZc75UB4agc!Ot7c$| z!@+FXWDb2@f~U3|!S^QA0_Lh%wre05#dDt}#SiyOz$wqc67N zW0z0R)ls!z)%gir`xMdauG_%h6!KeVFZ&Vv-0#7H(_i4+c>_qg?aB@Rd=E?S`GDt) z)#ZL1S%?DXgoKIMMC9?IRnk%sbOsJ?YfsCAb6or5Ny_aH;6x;KUy zqBk~qbeM@HXRG-byQ#d#e&=MkPaeC`xkF<4;ksCd?jx873Ew3XmMvp4$7^uC^Y768 zLa*TrM+wE3hN>feK*pm4nCr7gkR{AC*bE9Ynjmd*1{j|ofEr;GyH;9?D>6yMJDFs> z{L^`CGxQkp@0%lxCR^O0m0prv^m4g``FxPEo~FU=sV}6njW^?!&t%yQ&v#(-krWe$ zID^~^C$I>e2^M7ru-ND=@cEwZyR^`puS?j{FFx#&5jSloMf)%#$?b`@cOr>E5L-!t z#4iF(f*G;lyhJiHfjQ!(!C5|&qrd*Q0NWhQVBK6v3f7=s5Vt`QR@38QuC+EKLnU4P z;I&YPexg4Noi{(o)-H%*mJHCQSa(<3{Oju}pRq~kUc9L5Y!NYo2}b>PyyT2V8WVU% zgA4v}l#ZRLfVp}1*tY&3!65f1tPU@sch4LHTfazw((7CFY^hhE^7st2O*2I$6Hc=x z51-P0t1Iac$$c6(HP9A;$;f=Z=%v~zVvGqU&Fiql%<2l$_gRB8yVZ}{yk;!Bv_~8B z6{zy1KVa+8T>5T>1xzXIqme>B&Br0u%bfx3kuy;AgDdPQ-S>2#7N!TLVOn)jGreMA zBKng4R5)_Dir+UD1OxpKOP2o2V0y`sqegKMZE@6J;`w7RuHNto+^oIwRFaeS|~qDE?sJuBMqrzthvW$dh_Ef`s{;zT50e{S~5EU9dp_$U}8m#4Z)bG zhD!2gUuN{MCa3W{oVvJGo6dPf0)ek7r2*@OMJx)2$Fjw7-m!xxd@MOoN^Y5=59sD z6Wi#rg4u}LI}B}Ic!x3{IF|m&`J=77UJK{6gW~JyNigcqJR}unVa&}IZSLKaXxQ*2 z6wK(QB7Nhwx~!$q|{J!?rkCzPK|=_ z|1x2E!frIKx>XpBi-_4wFtd|f^5=LhW^(oqdntU~W1H&Jb_7oewXC?c+g$gM9HDXNM+g>fQgC&Bz_ z^0Xb1Zp{2r*WvEJQvi+H$6)^512^sIfy@jNeMk}(JqAC8p#9GUIZt`UGa^B_2M67sB0ZgJZ=-SM{y)NPl+C>-V9@jwd{U}_|Gr5(*Z_WJIiUA^E|NDo z3(oG+=t{>oP+fTof*1F}y-*z#FxyzbJQ54UsRVOosgA_XJ1*~8ye@Y(Fo<3E^#N^j zBA9L3^_NJjiB#m(Q=uz@$Ea+52MS+4g8TQo@T+G%iK&$3kLw(NT$eGsP8{PNL2XzH z?XjB?o{hTrvv!$a;^)LkhL@&I`&y>U?Q{sj+rGEZ5vF@tt2uoTR7`qqNN!Yb?K6n6 zs0LR01Mr$#1F|fFeS%nLb1m#GH3{W5Ho*2XX>fS=ZkVKKkJ-I5h0%Nycj!!lc`@{{ z#N~vgZAO8*!) z%S%++qaP$T>>e}~H9^GMT2MQ|cj&i4qH_aucHM_rf228|f?wGGj3G+(*#wiH^+zv` z4TW#Fv^du{Zv@PCQ2}It> zYH2MzpZ*wl&yKH;_}^G02{(jUBgdc*KmO1Siu&BV6|x*ZnsyOW zNif6xpGiFY^r)v_bvfta6x+0ub78Q;W5!CE7?|{u_Uo#40mB~$c}&Kc^HAuKMuf7; z+(hROc(&dwl(ems*6TkL9U8csHY@py?Yq7Uqd6?9ALROFplHq(aQhMrje(DFeM}-w{^yF`&!Op4 z`pZxv(xA=DPT=ViGX;#JSmJwB3ktiN7|s(cLd3moC5>Z-LS{+T3bJA9g+{PoVG*X2iepBubwZ!EJ1&?N19U;=y&7Ha+kax^0B@oO%6#z+{0=?^-+lK4OzqHoT57x!bjc*ri?kKt zM?)~$`04@^UKxzsrmw@HyR|`o#}47W*(BBlWa`LS;Ph8X;m}y>`w%@&eY7(h6QTh( zvde8(bf^fuQGAa_$*?NO?6@Of)ZZ1-*Dff)>|K$xse6CeJn0xJQ!ix_io%i0{&YNT zvp(2gTrFUn#U;>>VDMfI=9O~_b=*vko4sxzyMF6Kx-IV-Q)aFKmjhVZeezGRPON|r zKQaZ(&E?w?HT+E}Di_5{x@F(jcqa|O&(v2v?JFmo%0 zGfuu~)LutD?&FarcGu@C^z89N*`*r>L0L;P?PK~&(5IPRAUUjq+u)OqjG(g-_pw|w z(^wTP#1*@lZ5#pD?SaGu%Mlgm|mW<=;461jv9+y0zAAaWCL6^O2 zW-bSkYrD_p5U}DG)Q6H!sG(PdAhbtE=YY4|9H=qbDO5S^HeW^|6VqsveH6)Fc!w_* zYoXyI#5SM*#2*4vf>F$x$sFj)qVQ2YZd7|Hn5UNQa<8+7d`_|S3Sw&)i*(GPJmTJF#NVX1#-rk$f+s=6)H5*-iqPq_PPoz(~jwdMLNKbW}W!8Hj!X- zyX}~&u53#6mL9iys{{S^w~6h~h5gyI-#H}3?*^o0^+Kvy5tK~4D9A_oK51T-@T_wn ziXRhuO(NfLeDHbQ+xC0JEo2IB-1bmHX(ls@Mq`abI>on{n^ z4n5nAr^%T>@b5dqXdJ|AB71^qO6ri*?7u>7c(2C|pDYKfcPz!uRb8xA=shsiy9*g3 zd&$i@2R`ZP!mlTvO~m`EpZzV5&aBvs;%d*J%Z1&vZD16dUcVoY*Ytq;c2@y&*jOm0 zxDm`p)l5l0<9JH`qaLSrD+cx$ci<)QvaDMjBZLN-_Wb~>JuJl7TmWm*x5lSqrx=mm zC|i=#>Me`hoZ?VY^fB5${5Tq*HVV7nosV{%b3y#GStQnMRuGKF`I7wmKHk*iK0R*2 zXFoVUb1+HCK2JG5Dj*@Kqy;zTe)&ufWpKHxE#tHoVs36gHaT6R+3febuJ4%oS1xAod?=cfN?dQI=Ukha_7=jDj?> zpl8NX;&wd}MRLc{ycHW@Urzw}=(vfqWvvjtqbFbt4Fya9!LTXPk}35WwvjLOxJJ!i zIBfn5Y#sf8;*Fbo4M=MO`61xzX?#b1>ZbR?6&~Mzle+2=?A_{$=8USK$G&cXK|bXW zvu!lEGb+ezZH}-6>W2uJ5Q6bB4wAH(ZnSM=^*HOD$Eb=&J8^o=1FEo{oX@sAh0HOX zFuQ~3)rn+;-)#6vv)Y;sHC9*QbC)5C3LAl|11&)7SPnhpiz-Pu9g8mg-Y;OTiIWyX zFzs_lQ(AQSG;fI>ryIE)JGIQky}>4Q9n^rSTP^TbU~WV61%bb#<0mjm`T(?S4j4YJ zhHpJ;$SLn3PSv>0#toQ>6}ukeXIn^r!FVSD^Le;1nq-1Gcd<}1X|#I&lI!HXIl6e- ze#Pn7%kU7D!POFnF>(<}PBv;^?+NyXd|lXy|62VF<5?(+2CLA*m1 zxDC$)KPnFth_?f80_0ee4P{ABfliNrfyu_4(ViN-vZ)X6y=ce{n6eI4DT|Vkk0XWA zTqBrc8U+%kc{!3H+w{1Zv$isF1-o%fiZjjEYy#fACq0GP;OU(P#@3g>{VH+2KJ{J{ z_^<1OCzJQXogs!?PUmZ^Jn;*bWUFw6=6lhyB4=SVR^l#@Lok`Kw>6qzPBJ#OQK zx3nGOfkVGfrOTBXgf^d)kFgLz{;&C1x6D}wA>cA`hnsK>5|q?XSe7}+PwvGl-elsp zH*e$5YI)eZCm0!|OcXHEB8DTF*M~1iPGyf_hM4Pd$C?Z1alu|#e(qk{%C-^eRMEMQo%q*_BTQ-9@3?#8cYy4Cf# z#QZWwJ6;LDK6Y3VwEP|Ej_d^W1#jr|X{6h$N(sD&7f(1uD!1hHL;ePcKLqszv#G8~f|ds`I|k};f0Xu7%|{gR-O%9- zuYoEg9Vo?|U zb$bvxzxj}Wkrhj-tpp<<^F*R{A%yWVB9o@Mj8%xMWYd(jSiWz~udWN?R#(%_2{y1I zuOD!CpV5XU^+Ny6*{iFO>aX$aKHpB-khw#v4!KRw4D6;iI2}gA<;08pts_9z5(^wSfbO}$u${zEY7TGu6pW22cua;DpOXWp7E*df${0+?kF=z<-bIA%8#=Iy`-kFq&v_rKuB) ze~+tV@Um#8nA797w)D|~D{j-fCp~5ZNGE<%ED?`ITnCv!)xh@=@D4EM#Iw`0{uE@5 zU5VW4U8&5f0yujmhP03jhEDs}wC;{zc?Id?IITKe2lqZ@EG zS_h`Y|6tqZwvu3H(jIa@O{m%Uy(VFgy_Et+hsX~W9b14*=Wb#e~v`tuUzt+zhsOob5tjfs&!Aw9- zw%1-8Gk@>ubK1EQ*bAwUVcrk(R$vjXO+pJ6@0JkY^c;+gUjtw3v|5l3n@p^b-O>T< z`RM?wrMu`OH|L-Y(^jFs#Gq+Li?4v`Cyr(c!RY5_*$!)bC23GJ;GTKN!3f<`5ZQZ% zHF!>R92?${tD*ZK!`2eh;A${f_exj-LFcZJR~OKzE;}lyJ`Be8b<$8j1(_XMih2Wr zNPD)DfH4p;b_BEI*IC<3xA#dlx*2fet`V1!A?sjCcN1%u+6F;QFNI#*j9;~oQc?-V zNu)ST#IQ!rw_sf73N&-qFz9&K4*eR>!}{8P@YHrBN-bN8KK&89B2vW#J(pn4i20- z+R+8OW?zR%o0`C+Nec~=wLv&IlH&KYfg)xx!MuKa^j`hBaW-~O47fcrLa}VS4qQ^0 z%DT(6gI!4txX-Ty$I-9AQI2>E5mSaV^H!lQ@Xh-MJbz>Y>1*ZD_Pjfgd*T69j`{}g zR}TmCy*0w5tq?J*38w3CU4HoP2h+}W8E{Fy4tUMW;h-}ih)p}w4l0kHf+sn8@LG<= z)>VS$)+ei72;R*9W>14k0h>;oEg!AF3Lh30z((>_r(q?7l^qL&1+6BoG#`SQz_?0I zHO;kstUQRzR++$-dOE=;YeNB(xu1xYi;2>nc&6~9iJwYb{T)7m&x-p{XSfP)o^cMZ zGLj-DTS3sg`~y6CPzmZS_wmald(2PTQSrmWpI~lwE|GYYrP^N69>fhnvecx!@zDA; z(pI=5uq!2QeMHSYr~!H>RtlG1)l=RJHJeEJ8* zH~2x7fTWN6C%0Npbip)kK3X1kL@m+cKO=sHg%*@|2R zIW*07{s+;I*TRya>d1ja?LFyG;MVRGRYUv5l4?A`jE!F+iMAO-Ws%X0sl3U!ocm4Z z?N4F&tMBZpP2jkT^bK5U5G;*&OjBhrG<`Y@x9&W}kGr#RvaceN(kE7j@tWvrX%3vw z%f!m>7-7=F#V_eo1e0X8LZbeOqBg4z;{1wp*@i7rkn?X0wJ>Nm_&1M&jNKo>u)ZEl zrxyvM@voT*-V+?*e&QCa?K~KF`x5*1ktbmMf&u8vo|~jW<_jxpZpQMH_C>t$xJWRS z6AnonIakVxOj^wgdp6ScCH;AZ8ofJwB6!=^(!I~ypnG7wptIpe6W7y8^B%;pZs!<_ z`*bD?H4T`WJ`BA8R3qa-mJYp8}618!B13UjsY z|1kCD@l;CiIT6>+n*Sgl{`h2nwUao{V2bfb!W08Nv7s%{S z)b`7X^oqGCjozHkVAbsaI@2b=o~+~i zhUrzTp<;}ynvLLZ z#b-1?sh*#->jLHr!LWs@vX94ah|63}*zuwNq4tM2r4Ek*kgo&r>Lwk-T&jHJf8>Bj z3SIt_$%g7Y33np9}MBj>2VemQd^LA{eFW z_tJh2;bJXw6IN}84p`Z4M~iL_M=c^LIN7n_8r{hkAvveMOwlFS6GS#k$WY!J$WKD5p-iSi!=xk*gs><9sYq-pyKJyovnJ?Ol6F)(!MNE=kSOXC z%m7uXq}K3&c<&KowppVdUhLk@goK(SC;fad!7s@s>KnuazJ$!=L>NJ}^Ew+YxxAq) z2DUaT;J<6zVVGGtvDO)lE8k6q%|@!YxTJy~&CZGZXv_)5zcn~Bs&uV5Qf$oHZ2pD1 z!p<-|os8hx+UHR6icA(+(2@BsfV0i1p7$N>_L4S+#$5QXX$zE``~>svYT{G0GM4lm zghhcXQPL%AJngG8|GW7iU~CCynQ=wt@>*wcvWhY5sy2(U9k0NIr6wTv?jp!sRt_3O zM!IhK3qIUY?@%|mPHTe#(KFbvx(rTl9)#nKOfgjH} z`s@itPGlgxd~1MsWT_Eb$6lguewogEIeQItJS3Np$yIzYg-eokn)(=euKealGggx{ z{X4SYx5WgHT@wh}eS$!5L@0b{JOtY7I$&4k0)Eo61q?+n^QVVO_XKE&7sVK{o~}X6 zo~2pzC69cRLR{c1Z`D9ZXe%FBySz{eW)tNwr-6#wUH}&#v!JSGf=em_WVI7r#1nd! zODBX}pl#$DfN|KtW0nc#SyKt7_-3N?pGzaP_>d7BKRcgsUSz?XOdEx`K&OVYb>O@8 z3y;YTqM>!6Ja630DTuSHX;`|%1mC?K%v|)|&Lr(S&MX+1#^5=xfH`QxW7_`Xm%to? zS=0DJYFQaWtzKlr1}sd;lpk_d zQ{Nx0XT}C^<^60pGm`>`a!`3d@;fHp2lunh;I;iLluvjL2D^x(@}_!N-z;LM>C3aa z{)+6o;}-1uQWdQ39nNENXY!ae1Y^EAR(j#$LFb|5Dq_|y12|{9l<_=!4Eb*&`?D29 zy>(XxTzi~r{S~nMoeSBMTKU|l?KvLs(Y69M95-Seb$>E%lfE*+Vg11C$gaps$FhEL)uALleQha*z4eV zx&{1*=s#=IK#&+E!!MB>dt|eWx!4iSY`sb=eC@k74yn1{3Z(d;9bLGK-;&b97R zi+mBgK4v>|@Eyx+8*zeI#^^x6z7o(&&njs#Qd6}&hpQjdns5iU^s^9j6~ zmcTSd{l{#okY{wXmouqdj#znGH;)-Qm&f=MjQS-N>8+QyrOzWp>;~Nsv9b3rdcvxS zd_!5tyKj)JI2xW>o54!xKuU5ZcpjO>dwp{wykC`oPf&d3d-X0xf!p80cCYC={p^etk4aJb4s{}V(Ci|1diD%j`RXI$atb@LA3>?#A&AXy zgopX((DzY&piip?XH5WmF)r^6G1Sd2rKCTWjR^ZJQ4d}Yz&?5|3S95 zxq+8jahMH0iZIh}0H}FX@}sHtt>?QULWcxH|GVFyJtPQu6ly>$QRsPWzKFJLABOGh zO8L=jS;%AJ2lHxaf%}(Z~TM) zlUL!}N;$`|+^-iQ+PoDmRfqFi53Y7|;CncpWa)tQ{RIVasW6&Ug895&N9t;zA+x7M z?4o`e$R>G-Y`*Gciu>Jg&3+rY2gBwCE5SC_0gPJ5z&bmUg*P(==1>>F`SE)gC0&A( zH=W15VTW)ZGy-@3al&v(P^os#<3~dij74jVPhn+CsFh;s}Ex8y*m{$0bDRM&6V0~g7=P053#V=Y?)uhoyk@!f6cY1t$^B2@5C za}!3BM=*20{mIP#tu5O#PQT;k%cA?un$Ce36o zUG%32{Z75iV_bB;@gBt058gud!gr*^N`jurXgDp$!|xKvQ&GeW={%l6jlkDWM4@S) zrb52yAbgYbQgge`76DU3FazwAof3-crMf;MHbd1Dtxnc}nSFbtuG>i+dS)9qwI_kX z_y#aznS`KmuKqQ(Xf%^ryTNk7{pZ6hADR2WS=!FaEpOudQNDRuT0v6BxQ zAe~e-&^72sXOdsI*H2Qnc_`tXVVCPSz@CCI=yJp?m*+AC+bZ-&zM7e(yY)EFi!z!G*Io55qaHlLKcQYbO| z1iqi@A!tM%aK#i(nNks144b_EfW_o$l2s^&<*zB>())^dxw|5s_fEoNt_Y)1dP{B! zS0y=xeSa*ekcik7-CyXk;&fD%5Wr(NMOV*l8a($9f#0GD^^K#t=ls%ln^27)1%@cDX+y& zLkeZwvuTn043@S}K;sJ8L@71FRGmV;X4B@w!1*Itu=ZvV>?*nsX2j|!C;SQIyRGBnn(F=fm-yMCfYn0QylboKP0t&>sbiCBdW(mCtm~ zTk5=7k$h~YSBtfF5%s*&a#~|dJ!DQLeNd!tjkBRnviQt9Dszz(+^+LNR6MAcKO{A` zD==f@9hlgA4~okE!l#W%uyV^o{@K(C&t@3GQ= zN=pPiwDuDIcQck?9!&Y*G#mO-dE{bcwbBFeoW&RwR*aExD%BpZPH-_Pg^spA(9_#a zN<_pG^dOP>JS`&L>W5)w*=jibdm%Ji?t&eqry;4N8>URV2m4y?@uNxiKS9i&O7s(X1^>%wjR@EoatO#b{8~UDTfKpa=6606G|$|!F%g(@bZ5JvnJgH z8}qGjwPQadIPHP{{}#ZLuW#UI&~ErXQ}Dc>yo|@V63pRKTQknoOsC8z7_pyE2hwgj z|Dg{n%%yf}#B^@fFNj-G1=cU*amXjqA-R!MZ9V>h%ce4DZ@UK;)xIQu?F_hY-wZbO zmQe6M7oPuh07a>A=|wN+G4l!L*qo!1@!vO7cFsm@=Gipb>4^)nSTJ3@V;xZlP5ce+ z<~6W?sv;f{^9u|+-@rMt!L=l%yh9TofCbUw^k$z0AFB;8H?196pUeP<14QSMFomDA z?<;uBa)QZqE0t)go}d0+D1X#B+}v1M*6ME?5=fsXZ1M2 z{2C#L70Bfm7rD3f!e8F9bqiL;J)21Ll1B_EUaFJLOr-^Rf8^*Jhtk=uTY=m zqj=1j^*rVv!JH^4lvJuqshLEdX7sKOwYsf98F5C)|I}A7&XL31iC|KHH5?iEk1r4p z(Nw{{iVe`OIucqo^@TUIGaUZYj%xb7MWuJkVXEp|RF);w1)?|dm;i#g(|k^%d!mr~ zRx4t!Y#NHp-+CbZ=N9N1IdkSuk;ffPO;G<+jWm`01K-9vc+03@dL()AZ@CM9%+*21 z_&+Gl^}ajgwFpImVm=%9&>?Urf=CHS$emInwc$PWA>R#Ch7p%c}k2d zJHA5MUXr$W|05`#SI4V$Vkr&O`R(ho3K`92&NsR5IMJYcwA1G>5P1==X90Lu+` z(a)N3{G=sr;W5_;hEY5#2|x0MdJ`>T3#OfwnLBx+C3;T$XtrFG$DGK9^IC&=~&`ZjZEtyHor?{YMY_k{FEg z9ZDcrc_(U|WW{41ZRasb1hWc#l}y~EEPk{>#BPiseSVSSP?+2}#4Tv9ftjn^4nZ2Y z_{2Ycr49M4isPh>5VO7pW*3lDjH+WWa*;Mn*cX9L&MAW%Gu_bFU<)48e??leCSv=W>B=36_x9*nXCym2!3!3}ga2U7DMz9X3hvPcqp>$Uu z+`g&~oquKMo^K7DUbh)7)E&ZOuJ7S7*#y(q-%zSQQD5vhhU^7a$5AE?_Qb`Q=wfQ4I8oM>U{9Ay-*gb57CiM?6k8uVg2!yf?{}4Q_LroVxz=p@cDAI5=kMY>Y zV+skzZ?C3QTcyAFn1zTv7I;$}Z#f)2ZYmUWmtNltVHL?O;*^oqQ6k>-vq`a@!E4M>5(Rvk>{`~UQYIHIwI0FkvIw5OHabd*J_Y5 z(+o_8{(@WUYtV>~i+D`=0UlGwJsXW$NloEk@ijFOYkEFPT&HY_R4x&PBMA+1-PQ|n zb?@&7I$d8d=_R65P_bpC3N=4;qZH{==MSZbNvvH zX(5=7{I`rI{ z;ffd*1P_6=qsSeOu^b$7SjkV?_rpBqFTpI@DknX9Z=Bf2RKx~tGnJ~2$rK+7d?w?3 zZn>{#kL`QN@>0W2i+?~s%WF7vMj7jo-kga4dO+%Z1m>0A0N?$SiT$J)ev0Mr;FsDE zl_uPKwjJRyYPIBLv#whblH?@T7$IU$nvW4{tDF>T^mfZE!-(phbmW(WG{BukRb0EU zlW&jvWv7g*%ickgX*=}abQH|yUxA`&vq=ShHatsG!~=?~z-E=88uC5HWAq5d!J=Fu z&r)Jv7ZIy?_PhABr%3E~-GJu0iMWoHI5I((uBqafW#1v&rUc&SD&fEJwUE&D0jf(+ zz~lQDz_HK`BDxmBbT?IOdVdOBGCavo+PC98#*|=;RPIT(Wr@XlM5`X8rHL-hw4ip^ z8Ph!zNipR@7ytFt9ixiXR32IVp^0n=qPD1k?B4 zX33D>lz7@H5!)R9n0nXMU#9uofKG`f6{uxDz;kmQY%EdXF|KkiK_*hdDg%fMseLgp zjc19f`!rn1+X>^2Zh#HBigaBGyj5k95FagpsoanfnVLrykKsncU9YyD5HNP$0>(R~nh0ed!>yxNp^Wre{PnLW51dnk!|AXHSa-&(!cEJB) zb_}Wp_5Sz4=Xx+0yx$D(znz0)Y9ycVWjkq=4uR=2j`Ne|aE8Zt5lqY{bIGw=cH+ww zBG$d)xp=*c5#4W+y^LD|A5Nhnc6RJp?zu?zV8 zHytkPTm%bcqF<|j3(H69!MeG5h^unky1-+O5X`@*_HpBu7>a+CiP)!q`ck&{9O%u} z)?%*K$u;|h?0L)oJiP~Y@rOcgK^HiZfFPICbZ~nfeZR#G=5MJ}wUvksV?V;mlb%S5U z3pi$`h?D9{AVU_;==@G$_V$j1NmH)F%Ig=2mkK#@Rp&Bmzvb|l{7@cqkzl^9`|4!B zQ&C(d6S3Pi6{4#b{ONFUwAgZGC0`(RF{t7KBSJv>9|>9~h>S`aJ_ zob(Jz@Eb@WtE#M61#=ECO=6PlLyQ@EtV#V@N0VK;(uiF;!v|=$ba-wR1D8T;Ak@Q{ zjaKZ#WA+G`Sb`}ZsOVhPTSINXD`MXq`$gX>Po|Ii7>WbO$B`^)8F2BtVG?EGBTbT) zI2Xko?=L`!+&`veM_;zsCkZC>5ar737|7KqCEfUHY}+2eOZA?BNgy zZD+6wTLmR51^n5Q``zrh{uCyME(5NQ;O1O&=GVvd%nPpq7V zi7ueIXS44L|7>yz=JAm^l8a?GsME(p?Al98;?8C>+PkVzyrKO!O4T!m%nvzGwLt;9 z2X#P_VHP}&u>>9EOyt-TD?a$|u1ve_8Jzp|4K9s-4+@&{*z;eG^wjH%Vh&R#U|tf; zBJH9~_pne(VT*`O{%(yfzWgT}@nZ^&g(=9A=zMjQy$xmBX&k4HcV%jD%j4t zjw-``q3qyzR27g9JDtBn>)Q?}8K8>cNCsLG--0-daTq_EYJ&OoVztwW^yAbDchcsA zZlIZaKFB7e*`hpI7P75Z8t)SiRkX4mn8DN z6LMzD5$BoyOkRrQqAEiR5vSjvlrlQqy~$ z3xONWPywS!Fh9fBO0L_9C^;pv9W+@l`x~1hn}10eDa=mhEn7QEiL&m0FdfbJpy9ie zkEEF4$z|d0N2Sf`c*I;i>>R3ygH(uoWFdnx-!J5sfWt+8(hLbEJx)(@XSM=m|K5;Y zIU*VTb-gC;qShl{O_DpH_6#^o!{=TwF=&N7b7R51GMlfezj(ffG&HBc63c2xlluna zOpWlP-l14ROwUI@a>Lwc&IqHiAeh|Mo)WKP!>EK8hOE2t0OsJ-$4GNViMSz{T%r1B zLl5!e`d>`-#XC?S&EpHi>e(}}Q;j3;o??sL=NMrBtbb4=Z-Ao@Cc>kEiTtFoA^d3U z2&QF*SgK<;o05BO$m)-?q8D@(Q-5NH(wU?I({4;2Sgwc!1^>TbZ} z?OinvyDFOCX{2>gb*nzUH(CzA{nZx-X#ap3vqB!zC44;{3C87bh}34n0ct>=AzNRv zoR%N;2?fT9`5Sh3igZRSyA5-1$zi?sUjS7`!k#xppg{x}U6T;LVB?58qRjAOD-B#X zq8sj5YT=xjWC9l{@{@K?*m59(iE8kb-dS{!nv!71z8l(rMy&XTZ1YZ|o*#weTSIb- zYhz$pz5+H^{swzWqM%8RbbT31Va^&cwj4YJe~oN{2h&^N25B*|J)((ClitF7W#Rs2 z(^-Df{v#OAD`TWX9iph1{f2DJ?}@P1*$jZb?@;V@hc}&b zpCp54^M>Kazx!a%9XasQCl5xol3Hk*F0L>72=t5({G>e>_G#_}({OXJ)c>-Cy1v$s z)s!Igu+Ch1!@f=Ix{Q1&#iittC&KSTs{CgSExZdh-qjE?Bn$QxYT#P?QphyF0gBIW zz-!fXP#^dd`qXv6{wGa5Mqik;r3Ay=>5<58J)tV+7_!@=oN3nJF>=e$K-ENO*^*iT z{zNJ|P*Vfv-u_LL#BsoB)w#CPfBX95B{pB-tJZn(-uq8vTNY`cgP|``n|U&4z8-+Ze`q-AQJpn+-GF;}Jw%h~+VJ&-2g5hhU}!nn|~t=TT-u z4B2V4n^aA+LYAD^Auj3r8vF+kJBbg;P(^Ft1;Yf4&B+#C{qV6<9^Xu(;av24MkPU$ z)!Qq_E}TO%V}GSX_ISZs-%(i5z63KX)j)dF@HLfaXvqH47t8iE3`fUbStFO7WsvRL z1R+E%d@@CWBxHYs^61;d6{d}sB}{7m14rd)c=uG5E!bq8)gDsSm{|e7`_4eh zi*~TNS_u6P6DI}dN1)MPkzMR)$(~j2&wid($EbG{fU(jIe$vzgOc24i^)Ho36`xZ& zB?j!M$5H6vnOs?O{6QYWU93!wS`XRBr4Y3K0Z`NuqFL|YRYM8gB|zGZK}Y8WW8SL7 z=E?tLnikz+yn{&6l65MN87XXTuM*5ZX1ye|D~Ae9Fkt)6b3sFYZl*F%uRt1VTxL`o zyfhgO>!iWZ;Sd0iEzBTtNhd@C`4^Wpz=V`La9?2?^Xz0Iqx$O-gVriCKfg3W?Bx_5 zb6j{sM-oh~OL6AyQ@PZKV+O3;O?R=QB2CSovjP>6Zg0DUcDSJY6DcVz0!@pvi^^1cXwD&Rro?;Wa_moV^~nba`U$ZEQ^Cwn zg&a1npoQw^QOgVscsBh7EcZOYV?GI(bb{G9{ix)SWih2a!+`b9cA;+hYQItNG_-(47^2QmkW7jWqp4xgr+P2pMMS8q|l+G?l-dTsP2HL`S53MXkI+v4aay3q{Druqxv;kGAN(P| zc1|bod)j5J|KujWt9k4F5mw(6ex9qZ@tD^HbJ(X+vTH*rHC&5~CRUy*2+>53=BA4y z%L`z~v>veiV*y9}rV|6Y0i@r<3DUIXFxSKWIYt$G`;(3df=RS=$Hgi3`0cB3ynSdb zG<}KYCk=$nZ7snZ9GxS%z4K*o#E+u9&QdPjp;|3J)dhN_wP5Bmj6EJ_$=mbeL9>@R9ycz%&y~eD`HZ zprn9GYSw2LZw^CF^0UMZH64_9B1!WrC0mXBba0XoyD8&HSfKnA9;zr{`5p|&bSYxp!}J~oE0!CbtL&> z=AFzwS^3nJJ_fAJu>h9c)k8*yPEpnNEG(NYj|;p=MT6AO0$p{;e=G^aTA$8-YKD)>)1?8={ zM;CAVN?Ga==c;UCZD{@me93)g!PZ>9`J%{633DQgs*Fd(%FqGMR@^5yyZ2$^+kW`o zzoB^dN@FY|jkRPqD0fa+&?W?vd!fX6$j;YPs)_-7@J=T4?v) z5+O=t*Br)eTP0s0HrGsr3^zTTw*L_%Jk`Vl7k9vljvo*UeQ|6=3j9}hg~zA}ZviWU zSyOB6TtD>{6*9(vHG7!~3$*WxLzL6#YyU|=eXbIYBv+}P(}`RpA{Szglz}LM6eP!| zK_Cf5i7bwUe%Zw0RXz?{`xxV~Cx_q(I(aaoPFQK(!aHpQ!7$GzXY||nk*Z#1z)toa zLa%7-L%U`TrmsE91kQt)JFs^tH-Puhd~jvFT=hG{=SC&3J;bKk4Gkyl$`|~BQei%J{f}6J@uE>CT79p{xlrk_ycCg>)>LNHT@W;u^9|4MB?YrytyGeYtIwxEgIkI`OknIN`P#oX0*k|Ft6Z+-!nm%oD3 zm3?r^zK4*6#xkB)t}#m=hC=-M>)=0I18-h!fz!vwFk-JW42St5EP)B8h*x>ov` z(tc>b#@6JZ1;ZB5RL*4j8u|4P+^CFO^2@D=!;ZS;358rxkfuHy7!-h)U^O!*4EwF%KTt1DW786W(nE@L{ucl@`N|b3B52H1L zNs^!TZ(a%6BG(4y#9%J_ZV`X=?Mw883-e-X#yf>aZrBtxkVXtZHLi2Ml7@XkCFxdfAXUSQ{U!F~)yVP1%o0ANkRQ3K(yKalhn7 zy-vxcvilmce$R$W3(6kQ2O5aX1_ z9E((CFIJ~Pgv%R1wz}B9ryu_F_&c+HS2&NEEns#L%!i^e)Tf0B)bl}xY;?>DI+CVo z!&X){Dq#falRghSh$7YV$5+^)PV91s)GD&y8K^T>gfWfd7+sxI=9o_*JjnhE`e|eX z{6hn2Nu#44X355H_>4L`W)l;@ zJP7&P4gqUO;}ZE0XtvHEfi<_0$9!GnUg|-wl$XL4B9+ff*1;JswQ#YM9NlK7#vgJ2 z3+La^rwHboiVL-V-74y$vmxtJyByv4kwJ&fNJSsw`$I}f4ybq#i+yYICaBGV zrE5(gxo$Hmn?47@vco9OA_4yEtcR{KhPYt9F4o<90Zp#f06Frv>=us+A(;L(>!`e! z11OL2hU`L{X((awE4rgaEWQwvjOM#516LZV{q!9;sg=_M2IThl0UdTDx)rJeOO^c5 zwzr8eI+|<^e;DCSqqOn(-cxAwmA*V?`)wX`gJ87$k5Kke51j9jNn5Z$3B}%SqK7JJ zi7OAiLQhXC@Nw^%yGe0aqmi#baltffpG(Mfxeh38^GEH(uVe6y_i*%_F&;Hd2Zv2M zhU9kX@EG4n9uq?_wVy6fTlz>QI1e^tw=Nlta*1zu+P~{!Z2KEsysggn6nanXhLWEj z!TquXW}eW8JZl-cnyCjR<_FOFwhTzu{Q!lQ#<+ezv3Dg~5bi%Y@^>qW$0QSse|tDJ zAt_3-Tx7_G<<^N4JCvE^;#~0}6A>JDH3PjX=@78#CofJ)*^mK${*8pQ>-8Yz^nI+9 z?1B46K7)gvt+14g#)I6CHn<)lm}DMPev`*!5{%oF2&ydFLON8P&yAU=2tmwiM0DYu?RCL>Xb&Rx=a6$X}PlOV*j7r0BW zb#>|BJ6ZyEx6;5rX#m zn2QuE4nRQ`sUaj-U`=ghTvFtQ4_rCQPnwhP7N{hc(reeL#!<1-ZBYhn&nkCj)&4t( zzPXprUiB}_0eiW4z6hyOOUm8v)A(Y_4&t6LdH-JcoPHRdfowF0J#V3zrwk%nazOIGU|u;V`sXAbBMfz_!M z$lIm~xVF+3y?by^MTHkxaHHYkLbzRLTagWZ{c9MGFk^wz(ZM=9nxJ^qatN8WACjye z^O)Jfp-`@#=+nxgrL�GlKH@1KHrVs+z~-3U>th1QUL6fb`6u-_HJ1_1Pb~?l5zE3<{-RA_c{I zusdJJS8hj+(85A8zYi&OhM<_KuOLC= z3y;|;?965FDq8Wfvc0Dp{fKIKDoRa#mo7q1ii@D)XR9!_m{Ae}`qp>F#U$dW1Hm|o*Bd_*jCk6eH21R9|Yt<>p z2}oxhv6x8t6b;`esbeRnKaf-y4K4ZKpe6ActZgoUZL6Nclz(ch>MvXNzNI-^dcA|W zw}|9?OcQjSw!*Wa2qx*pE2n{xXDRcg#8G+WUFY6Y!DvfkF^VJhY@9P}+^h>=lF`9y zZZ#BxAnsfzaD}d+-sSL)sDvJ+s<09HL)iUc1KGEppP0kL%0XwBP_sEHV5Snx?bo}V zMmgQ50*(8zO;hvfJA*ROr@S0=ErgVU&a}cshmEjRmt1zSG~ayTWJJC_)1SdKzfX{U z<_jsTR5E^wI&9YsRo2Bjp1BfL4w0uX^OI&EJexTLGXp+k22anYlIrx>mY4#@V|N~E z>Ar;gQ7L$)xAK|AArHavMg=#CZ#=)2NQ)FS%yv4Kc!X*7JS#XM$|@UmG$Fs1X{ zrLNZ9)V?!%tj|F!#z#65$yY2vPEq+#J?krsO36eQ)5P#+YJV8-k&bLq{$cKSv%T+d zoG{-I`)##Fo=f}EntgYmDAK$copS;HJFm=ROob1@R)W!d7b9Kv^EZ{ePmf)0?!ur7 zHTo}2i@C5Z&t2c3&M^g@tr!Lo8S)VODH8?z$m8t6PvFTQ?-m?jp-WXJ8C0}OcFuP!#j}3tmHAz zh0*vEO!4<-X~C#kYVlS*_U_cb%o)E}IW1@?oH)BzXW z48c#{U4dl|*LX~gu%Is!jM2Yl>5sf~)M_6+w(Z4iB)!{*F>coocPxI)>(i{xZUU2c zXFzlG3ckmqY^Mt5+!78hFv51ksNvz*W!O9VGT=yW@HCqWxcLF32S4I5+XYMn!8j4$ z!RkkLRPHW4HmJ)T4fHT)c6FK3JLJ>(x`3}~GGw|-q54lS_>Vl^AY6|vnW9TKxP72U zhmwgaPK9Nk6tVB)r+ma~`GPoJ17&R@rV2Id@<7aJ;JMqCbxrt9%MQd-Uby9?5Xt%WxS?t{03@F7?vjD{wd#GBSq z`>J^75{-WB-LrQf$-F@vePBOrFM0rBZ&YygiY)L;AvYUKX(-uS1+%tmV$Oh;URVls zJ8py8Rzv*dStdj{8Dr_0fmna-TT%n_V z+zuD+)X^cIl3@B$RqWpW1Y*WlLdjPK;?BQ@Cw^M^TIEgnYf=Z}Z!q9p@d4IP_JZ}6 zF1WpF4t`aX0YR^X($N1Dh)W1Y-LK7A&UGoZCAc3u-rS#lIwKuj8#936Jns|D)iHOz z@m%}{#*%Nnp2`dOhIFyrmI$c3UJIiCa~^%fcHA6_Bl&K z64TpEn>Z#w?=BL-ON8ORV;X>q-1AD$gSm_$=F+j}MG_}6EeSlA>xZvDO#}JuDp-H) zK$3#x1Y2`_dCYnN(@rpl+bSMEb!4g35Pi05-f85jn1P%u$-$89&yHGaVLQ(!;Psds zp@?56XLx@4fic!Na2Fi<)uAiL4N#x(FEH-$e%QLn01t9>zzR2Z(v9bz%eW0LGCx`1H~~pggZ14gz~TW?%+W9C@1IFdD*^L#ctJE1X&FT$oG=Y*^vyoH&4d@y_ZMjTYkpkUl-TU@XZE+4Vlma^q+h^*T0JamjAcE<#hxt7>Z8k5_pJPF@?v1`*#ID763 zlNC9fT~~e&lIP3=ueKq$W^@18P#ej`UpwRZv%XIxaMe&@AgF&Gw5?tk2ur&Gy z1z~T9aYi~^J9G;!JZwTmOQ$l9Q58(~peNAqZw+kFv&H6rCgA+riOi+Z)qKrnvhYqD zOE9{Z?^4s`Q>n|22JG6d6XKdV4Ya&$6pE0mMXBaKe5V(uOyRol+?yZ5=2PDAvR?qQ zQguQe$3khMpoR^p>tKYYB|fG*8jo+EMJv5R{1LZDc&A~4`FHOD)p;qHDi#^A-`D7( zs&F}`iyDfOlWrsZqoYXtVFrADsDNAEl1?w{6fhMH1D{!d;)WbXeYITZ?~`(YJ+c6* zJp1E)vxZ^Kg`Z{fEJeUA=%d1iz?ER;{L7-&9h^yde%EK&R)l`NH)0k=L?N~M8%Tee z4k)Zmhb$70Y~MrLetsqM%9LdBG-P6D0WXrKq3+uS(2+YGE?hOnXT;VRd#pl-SYsY@ zQ`mCMCz!BRMbx0bCC*RM^x5e{Ux^iW*f8&x=b{UfrD*dPf%sWC&Z;=b9DjPbTxc!=yzxtlLV7rYr}?dY3TJ)D`=SQfP6@k zjPtpf;50)I?+G-*@rjd=mz_|vsS+?72*&qt4OMnqQCc!mpIs1ch`M?aWBjNGjhf#V zUhgyDB_o{jo|C~{t4M&n#pV#vD$nm|E)1KFgSwkwydwpp{~F?`#l&~$P3ZrXh9(Qo zW(UD6&U-^;D(;kys_(~MmtK_a+1sDFnL&cK2YbN$v9loVQ8Z*&XktA%BI(&557A?H zg5wi!=$$+OXItHar)%Z#Ntpv|&+3c+Bx>SibMv7q8)I$>{Eu+#Ai;bMFQVd?BuaB` z^kc*CY^NjEi8KS-vgPgB*1Vx%KT`! zRC$+>$8abt0Mbe>!Hw(&7<*s#Yb zJ+?#b3!~*b4Xw`n$rn?6L-WDO;5y{Q>f=i+QL2*B7~aT%f|g8}V-yQz6CS`araxY7 zA4EEi8sLB;QAKKofsRDzVP7CjS~S5-JOt9T)Ayy*&Gpz-rM*m_jP2k!Q6DVRNk3sT zk&Vo{234O8aapM~SNpLdhKbU4I}R*?60X>=w-9S6s^Y=xqQTVnE_^m^M&X;zA@-wi?|DkVJSG^Wd^OqC+{=JVHJah0yQY5Nu|OHpBIM zDeyCX0!(mFfQe}`el!mROg6zZ>&eTun&>)rebQm=KV`!|DT7MJ)T5AdMA=yL0!qk6 zHmA!RPYCKm@+676OI!uqEiO_t#~uCy@Df%EM=5iVS4{&^;1PJ6=?BM}>UfO4@J=fv zm>w%uI%Ur{=e$TA_V~p`pykj9KJV&ATw5t;X2NAi%6}S&4Jyc{_Vit78cw`!31&yS z3ZCJlM6U5Bi5*5CrcW-sg@(jcp-Hayz#~VEUuo$Arkr4|58W=Ew{id_CV9h`CX9zI zpJUOZrD15tgm=U&qa0kz;$Td+6<$VCHdL0yfcc?%9zz`@DZixQtnR5F6Iq?Z98&gX z9xm;}R1jysrsjYAXyyq8;yQv!i#L_dvYSo~Atm_;5qVYG`=H^6d&CM;-hxYdC3tDX z!naF<@Vu73*k37{cZTK4c27u6Kr&PwuZn75DtB72C)9hG)|H7&V|FxX-|yrx$-=9% zgm_TC`ctizI;>syO!Q>cb>wSvfVclB(0W4*fNp@pE)y(&Lk<7!4TEZ1(xOc; zjUUwTJ->fow@rJ#7zX9}4 zzlO74=EENCuVAx@g`)D|dOR6uAK$>-8CA)ASvZQ>`)nahG!V|7LxuYrJ%Ty%>XCHY*>_ZJy*67r#D>|o zzz`{zte2M5J%ffFZ$L+>0r@KWlXmOfBxAJ%=?y3CC8Q2L$7~Lk^+EV!PPJG%1O`HoWitj+dY;K@v|(xzw8IkHURp6Ep4 z_vCIRAgeawh%|9DSX_!hfqO{i=Mf2HNETxHz8DWLbwcA@M$_X5AX?|t5p=}K9Cp1s z&tuLBlV(FO*MI5D?iv?Ui_~@4ZAnUWQ_@#j>+V#V(+fD+*Fkb}G|~wk3CXTn@Y5~< z?TGlze+Y(boQ3B;8Hzi7OqLXH_gtk~} z{AeAv@YY~DY@s4^_s3G&B~}KOvq&3UjSS6<9|~8Sm4H=!g*X8W=cw$kX%b$!&=ecW z4S=czGtu{9fD-0d!qWDkU?ZyJN3&TNjT6Cq89z`KKW#ph>ZZf?6l=+zy_mtIF5g5~ z6Z-xkW#*>|<4n%w& z0Ew;gm~-tNUNac4`a@cRNzEqr@eO>{$PvGt8jq(~ZUXDg8kk!G_l2E}8^P>d(nofA z{WwWnlny&tB?0wGn8cVDjHUJ39+QZ@@BHtk@S7ie>7EWT{f_XGk?QP7*mlqw=S=8= z3<$>m`ag&B8^d6qQ#zz3u7>$9jd_ff@bz3oFebXcrS|PM(rMY`4eb++RMXvl8WZ$Qkw2zPy!%ha; z&V}=xUR=vBm*(So%^Z8L`U@*0r*MEle>^eJl62@9A*-EMplPYXW1a|~wao-$-Ww(j zFE}SnU!u!?C-RUhb+=IAh)+C5d6gWFo0kEGrCGeFFV4IkRy3;NYW?dV@m9b=Ssf6+ zc0OKy?FvjKjWLUS0wMkIY&g5woX5xs-o81+aB= zm;7aK7h3EbguwS#Q{u#!Xx-bw3~s|=}QtH;heFr6O!I1risuI4dZq&R0W zaZRO?uc!Sz{|01~9uBdN1i7a#VXrj<>8EvZ#zz-uRULrG1rNhF+K0hMlKCM={@x2m z+;DeYU4?hI5s4lTX2NoZ!J<|?dI9Qzb`tlCl$u*3iUhuw@XgEc+vjv+*5&=a^GQg z-@vK0%%qM|G8dOoaJ-vAa3X;2$p0Q_xtJ5rIZDb`AKHFHZDSu9W3>izd#LbWwZwjKO+QsV%pxEmh zxOC5e{jqtl?yd?H>^%Yck-vFI8w=sgxf^irpE@G!?aPLC>&F^Q9U=5T`<-GYOPFHB zq_^&8^iR|<`jd=>3&IKFw9!oYD*h>>R_y^J2c$!M7Dk1+ea8U%4Ac$eP#49yfpef` zXb!*pZ5Lr&;}h64TMzUW_GKFj`?CEpB(mh6Xo^uvk7p%fBK^D>UFAEbYBGAC9X&=4 zPj6EWy*@x$T{Iat zZiCp@pZc<8>G6C+i}BmQ z|G;Z>?r#G7oNUM}%7EuxH^ZwD2e~o9uJt8(3q@Biy@P)Ski_v|Ey++Z_c5%Ig$U^ zpjY=9azAY;-JRUMc9&FU=%5=9Zl#{LQnza{d-a%APl|cl(G+5aZ6^)iZ-P&7 z5vl8B&3@b8j~)HYgN(G11TZrtj2>bNkCiaX{gyIUzZeO^&U^ftAzwM$DOK_}{o=^l z78Q)3NCB~IXFs6`MM|$Augnx8*F7L3JDbA4YTL-H-+7>wZv$_7bZ6hzny_8(9U~JG z4M2Q6lcgzOikNMiKQYa#KHBxcciPXu8uI?SoS(6wTK-l3o>b0Lr$tDyF^2rb)Ap6g z6w_RjMG{ALfni>o$kBoM(0hj+jLYuD?(;EbACEaq`kXSRm>$w-`XHwK&~Ika>bvnz zBaMW4rtyk`SGN4J9RZ||uO>`N(t{A(XNuLqiZ5^BWy=eQ?B5r|gc@lJ){pQFtoE7r zu=&ndIQM)AtFLdw7L5=8U(KdPs@z&2#`OIk=2^a`V#zrpp`zJGe*Tg@zczFP$-X3q zU4&4(DXL6CgQnGEpTo=>JK)u>xe$G46#I3Oq!5ynLRPG6q6r&kX2!njc7hcz+AOJ? z$VSBEYRF&I9aS)UjD$BopK+g!ZTU_qvq{t)Uq}r;4))nGRGH$O^AU7Hlb{w|NX0C? ziEm=am3AG-o7@C%|15;qQgilPs}|d}Yfo5nSnB#7C1D6+u7#?|eIQaXbheRDHf;>C z>t@KSEsiF>rU_7N5`v8s(bS#Cbzm*UY_&|L5wBA`Lb;w@E9DNMVKD7Xf4Df?n(c8! zpDo-!n0;@0jE-iAgqenzlexO`tFucLD@}|9qj72c%W37xsTm!J@4;-G$dADx_c6@B ztj3BhSmJ10m}k^NPdRZuTr>F(JXXbmmzNd1o@>kA$5wfZsiy4Y3JAC2t>D-vWuB752`lNkI!sU7dtf@eqjR7|MAx12wyxfAZJD)wF zr^NxVG3~;B+#Lf2PrI={HU@+7RCU&4jkFwWlrYN>Q*y1=?)&cNipdH?VX5J7KI4-< zWMlDnq-`xE1?7MXo(i5mug)GWlrT8~Xn>CWH(ry2!1{SSlp2_`VV@GfJVc)zn&=4| z{k_1aHJ(mr2kD}%M@*!HnxfYVZ^ac)Lt#^UB>&XI6c#+aLEQI#hxpG0G$=r<+}7%R z1q=Bz2$`P;u7{H$T%6Y`*iz7e&fQ#Qic3S_R z5Y+St^tBDx7iya!che>~5G*P04W(nE{fKEfe@`)`YeM{JLqlQr$i@6vmCeBSKR|L8 zeWe&tnR4|peyp*rw3qHPm^~837pdtmZ=MF*WBMT0zx*#Kjy#1^*VWl!6IQ|Z&TB!n zK9P^gpsVc;Cv7(0I^XRQ}e+Zwnyg*RKnN@RLlT_kgGvem{%d`(+f}MS2@=K|F?GVB`ZG}V^4I^ia?h4}2pLljN$AQa_N|4~*J4Lr z3}_~Of~`+p!^^pM!A$)#Ec*C|?-JGn9db1Urn!=@*HMDYSgF%%w6ul}N6h4i9NYOP zJefJpG9l8-k1P1I zDiUV@pJ9d|eQyNB{8v$u;Ha%+oHS*^)c_;@d+J4Uaf2%nGgfMEVa-Ov5e8afMzQe~ zc)npCjTGPi={0=6pvjIvufep;dwi!mCH#sNY5azLC;8zQLcrB=1sx4Yb%9jG{53wH zNLNW?qH7F4dq&q%=10kHjR6B#_ckT?VStm~zq zkEaFO95{wOFh>(^d0i&TWIyuvu_ipaaT1>V_?KR^{nAdl5iza1hAGoa7BLsX4TKec zmvH}1UBmy{k|lSTl!FqHG8o>yoXUBQEmVcUQLTiyG(hp0XYhQM1?v_2l)a;-1+xbF z5#^MNWXEfCk2kmmF`73hW{7mr+7R>0#zuLj#lvn^uz|2OUtlKu-osC2yydAqF^n$p z9mLL2fgZB4&|lUGb~PDM8)`8ieNOjYtaWuix{48(91Sa$u^rq(*xln2!SUZbikT!$ zXw8q}WDB_B4NDLN~cs>vYtpft=NsV719(XkCYUnm*V)gpHVDp)2AG8fTo)VGmv{fDg7o zWQ)&q;O^*hYPTA|CQx#QoiAa`5VK*Dnexc#V#T2V1EF{8V{YK>;kMYg%^PuEDaN{q#?2w?!ZGb44Jv#dgMAuyf1wR^ zueYHvGE0x0Gs%)Y6XnJZ3uuGH-yU!>1rvWGo}ouaCA~LKqz{2LV#Xc+qR>9AsyeMhBH<7Uxcz~Vy=)pE4E=VCI+SJ0Vx3q18Iz-odCyDn=IYja$m z?cY8f)H4>q+*sRNgdw$$9MjJ=w>MJFX09{^oWzTE>DKt>>}?6UZ)8H*oop^il^$UtcwcqkhmREl@Ebvy@$Y~G_P2|#}oh1%Vr~L4UPRkUm-2kcS=)W6=H(N zcqGLB4YxfgGZaqMS&@5sc5rSOrpixx1;wQe(27#UDQiDKd;dII<+z6(cVg4hIn#r1 zO7#Gw`5CjheLApiv%bO2bFFYyeKKsBAg41;Q(6wXAf_aBm*PpMc02PWhC=eBbiQwv zzdSNApR>%# zlVw0vcwZs>T?awL*h`P6FJfA4Qxq1XRplRN7zsaGL&&tq{?HT{!}%ZaM|E91i2a@e z>l$g(l5dZEFzucS4;$Su4YP{>aZ6Wt;g|wtIWORZ+gmss_5oIHG!Q!XEuo_+l4e=} zVv1d#DtcM;mM=riZN@o2lBz|(J2iv5HPRK-;{2#(tNVc;P#cL;0R7W!6RyMEkpS$@ zAU@BtfS-Lf8dfikgi(u|;f%F9dj!?Q9o;=Brc@fu9mL%E;j1t*x0UyNZX_hWYA0Gh z$3o1~7_RyVh6m-YhT?_Apo803r|5hLG0dPko37DqWa_RaZe8|H{%PhVc-ZYCtSHcC zhhPaJYySZ5M4x$b@uE$UmV=Rq>B%owIJPa2_ir&0rr?|SU`;(ad;2lB@%>lw{Fylh zo|NJnpc!-)VI^vQ3RtEN0@e^){bV}CT(1N7aJD<>UU37rM@H=GW9Dpi`)%d7>rxBW zA_)_ZnB!AEC&VRfkuw901xvkduxNG*u~%8ZohnPG#S~vWW;Gh!3XYz+kTdipys|Wc zKFjWq&Oth`L;oBpZgGd{mrp{baVNHC#b7r7k3ad~*8#-Q7)wiz=ZKm9`cHhsi9Pb4 zcE*C=nm+IuJGgCE% z4Al2yyPPrm{`&~_MaX61GD(wSiX==XV&1uV#M@s!ET4sv__D8KNWn{M`KXX>+_-LE z$z7jj;)*`et|!{)%SPPa{P}gF&<`>?XDFLg8TP-LO`f!}sX$EL!8F?}H&^))#MnIQ z#l1f^nN#t&q|mOk0+Yy57_e1HtyxxA<>Sd=0;CHLFpil5Q>$*WtF5iszTe+M)W+Lz zJN*Yd%pAp=`o4je+t0!NV{Op#k2O2(&R{T` zxSrmdAJX@x2{D)XkG7*c|B=hwjfIi=hvdgbJmFqn%#n-vHx6#$m@JPT4-3$I)~*<~ zGWcf3jiI>eyua;gg25Jh#hHE45PZT17Bzi@gAazVuN?GXkxx7=LQa(?w8|%(Y0mfT zswXdyFLgE+B8Qd}*XR=E!98xYn4*TO6cHoJ;KZ`s82hK-^eG>FF@J63l=t%dC{Hrw z@L9}Y*$$Q)TY#H6o{d?y6`1={|R8{n*OdVi?k@&02>>!{n}6&=A;*{T}lj zVncN4z1b(tG!w+E>S}76S4iZ4`WXu#H{te~<#8W=Wy;M<%FwkU72G3|VM`AQqvjb! zs~k;jg)j+wp|+!>XWVmB7Ud2wB(xYZEX~>2yPx3C4Cxd%R~k((#EiF5PuTYFNcpHP z#=;}}TI{3q z*Ptg`2;r^0+0FWBR@bwbPJ!9dXa*xD-g|pO{7)(0IiFnXdI%2Rz7H%bz`lwlVEaL0qA=9Ky`8wc--m1zAyg(qk6ojn2pkC zMj|G+=f;F8$D#5|-bTXnW^W>759hjY?}^&NBC4}#?D-NNu^reG{+~c>S`vddjc(?F z+nU5V*Mj8s?d?Lr|SR_{$`S-98XreK-$` zDkESh^BkUX(sD3F!c0NT4IR&f_e?)|X?Lu3e%ryNctkPMa+)v z+6q3juiW~*p%8H80(UHHCD)h}L!6z8smMZ95Q`?KBllq-nocaW%~}7g2$F|)W|`;+ z=wEt^H;u^RyLZ3DCj?L8mp_gIzt&R}(?P;GBc`TlyduxTO#UA#x_+z*=k7Lc;7&}s zPN#raObMH)gxmTZSU*KAv`>wpQ7(aX#c-yk3p+99K4io+@m_z8g$PzfusWa2Z?TGo zf@G;9KTW!5YZ23}&PA~?(nvns!%&#CHI@qt?8L1abBSX1uXqpsqr!pA`A&=XqDNP~ z7v7^eB`ELh!KSQNLhKkFVSDF(LYPSxp>9hfZ@TyqbY8NAj%J=T)3zdJ?S!+6h}#@_52%GH=o~-kX&?3z{|xlo z|M10V8c^zCAk^J?&);~XgpnDiDW+b!XnPTp9CB7MI;oL)(a%sA5zLV8XM3fx|Ytgu1k8dLRt(=Y*X;DP9OMyxo>#Q34wgnj$B|) zU!s`4l4QgkF?|pED5`u4n1UZNVaE$quIpH$q8O5-81D2O7u9UDpf!z|d`cNZPa zJ_&OJF$?%CMbF^9j8?o%SnK|b8x@emWosDPRba!v7_cF`#*vwGdcfi%6(shb8e+Dv zmKrn}WRGS0a_`||Su2U2b&m`>^q9Qd@|E2D&VlEOLlpB~YAz2$%&-}Cifxarm?KJ= z!0VmnQ2)UH>UKfli5m_v`9kGq0WA%Q?mUW@9ca>0RM;!{xn?{&bkBP@rBDISs1Pzy zGm5mF`bN4Kqyss7o??Qf=JF?q(bo8_;HE#e`~6HNn4TAu7upPYuG?{?SmiMD{0wtz zn@OeL2wLcx`_>dhSF15+pTnr7V_8SNcXWj#)@&l(ec4c(2du%{T=0H*n_|MHi^d^_ zz1BhLnDHxC8z-k3p-KKgEcFPBphJ*kqEkcS7~fyK+S6w^(*H>HRgWvaH)lX%? z$EAna9zXlBw?{1k=X-82JiHl}|K=zrLmJH|#2mSvrP!73su<>GC^Qe&2fYgwa!0dE zbTne~g?Jz-8qK&aPod=p5hFUl9NcWcmUYR3A%10WZbcYe^S6V@UD#~yid}jKTPa3E z!hA){TaWdMccT_5PKFx_>N78c-v}onT)xU#>`0+K9^yyZ|9C0ryvagm-Xc2F#F(9! z&>GOF3W4+HH=r7$#nRUHVD**_WPg3@!%jJ^Mi)?jq#|T1VtV|Iv$c4fm9YK`-kaz! z=(m0ZjM9&w7*WwxJT4V1WN0se2l=9wLyX@QchXK5)Y(-<&!O|dIOu7148C{o!}c6G zgjIgfW}kIQrlUD0y`ei)VcBjAXQwhuY5UsRNU&R3LQXl$U{6dN#jIZc9c;0#RuTLj z;`e2Ot?nD#z}JI27QZUGsk4tm(_kPL9VfD3(AUL){oZ867M%G3Cd(gD%u?xlqmLMi z8*R3i{yet(*TYB{TGqfv>I{X+&$W4%QY-@FXe#hXNJprI#+_NTW@G-mk>=t?x*4-y z4ZgtI*c4c`J^=iSJFxLDjM(7@3fPeqOfe57OjpF%4rz@4w$h3*e1)gD&mZzH&F7NQ zP0u*-xe=#;PM;jw8^vwP0YAMW7;~%%eFYUTG3XjxusZ?6%L`!e$|sQXA`>nSuZMrW z_(03P-4p}T_r@GCM_r;5eym-`Ecjz2Od9@_-`;wgSZed!{w%yF=yvUiOFyHcTCks& zkFs7|hG@1z1>r%X?5n&YU5$Hov7P`b>n$=hte7UtA1GfsnXcTI2)!HB@NPwk_*Ym>~ z{P@$A32^F87<7J+1Ronqz=jLpZ#Vn%xQkNhDm|WK5OZX3LBffpLCme?#=?!+i-_04 zc+#zM9#>(6f-y0k$^&aP&fmasCr)Ne$96Sprpo(g?FGDg{$IY&zn)-Yc?{+Uyo2bE zt&qM>P57(vm11VxqAFDuF`?ab5>o!eG2;#x3$M2R1TN5vG&|XFtynpC{Zj@N*ec@q z_&Y78h@&w>Dct^T_u$kBb>SA%RVXdp2=W3KILo)d)@W_CZ#NZex@ZXEXxb$E4+q4g z#P_swQ)V+y&!J?5NhfWy%}B2U`AQx0Thta*2c5`80gPxgBR-zqNy*@S`Yb%T-^{1g)crlVPan09z+_o=v$fg8rc1cw0f&Ns$3 zzWkXor?&?*wg-Yy86M+d1d@2sbS4(UoroZq*|rdtCO+j4cKXCOpFRVXHxI$%pB>ok zNye=Hi!}c3xTjYL(QZon@ldE{;z;4e zIC;v3YUR>LK4AUC9c=IEu$vr>*^Hf|mH$*l(9+P0yA z$;|QRIB%bF`J41~(*JM=5RJ`RgPZ8RF>T6$gMB)JcHMbW-c1$CeuWV2dS95Ge-!d- zIC~8amPIuCc_bBEdV)nf}#%SC6F~4>i3&qo>$~!6Yxf@RZ5jOV~d6nNl zbXFBoaZ=KT5{Uot8dMIbQA|C`e8ZD(lb@~k;GoMnP`}=Ry@s8w-;=^g=*C|ZV{o5h zP9Uav(`jbo;WdmVHpv#19+z+W*~InkdX!AdM5|-8GZv**q6W&>uN2%{v*~C=IZxn= zHqy2(lsIa~!QOY5AT$8oUx+@t@77(?_vCMiaSW#zAH?Jh_G0evhRmhD*d#lAl6;|# zG4Ex5ksQlchg%CYs6ms6aY-%%l9>fQk2-@W=Mh&kjyc!Z02E!M{2Ky6`I_u)RNRUG zF8+zn&0T3U{)mABZ>AgUu$%rF8~@GXl_@h+_*PX+VRq~bx4Z{XgC^^a80LU=fqL{y zdH&8Gv~jgFTj|ZNTDp+cQT+%ub)oQllr}qlrUpA|(JEG0dx~O`r3rltF}GAtGN&dV zj=vvgBwR1zQKw$Z?MpmCcI`U|&&!X{gfekL$D?zSXrASp?hmUIy`fMF zX}Cu3&7(W?-ozrNr_*^Rc3OYM{Eaz;CG)Jg?MZvmZoUSQ4|UbNB* zaNV4N#;55tJ?_cc;R&`;r{qIVpy4?-EQi$gU}NuhVp~p5W9MZqrx$Ifgh@ioRN)Mh zJz$t3x6)AXm^YlC5N1eLdp;u$jYVK|1nnoW(Lyw65|jO$cco)6>TAec@(jjJ+YFxb zSAp&aH8yWyBFah)SlP0VFm^`{yyfrGi#9{LH|dC(6nxL_{Z&iF=?8{F&!e%thv^`4 zUMrZaj{Zas^26K}aL4@zXdZh<9mn>c$)%q654-xpGtZk~z~UY>tR6g)wArJUPvPC} zT(JA^BE?ur_oe_btm>PDOv^_JnY#>yn>Oe9K1K^5R8~rK27E+4O%d47NdU3jU7YZi zVj3TzG7?Wg7M$wAR=D(F%X^uyUxu}V9R>+J>~RNt=iLF%Dbj8&MfwoDL(D#_Eee<9 zlvrbPL*ZC{N6xr?Ane`KK*Yot@#wo)m!lU=#MqXn!QlgikgA2<-`RcHF+pbR(h)yk z$j@>NcT#1O`#gZ&3-3V05UHLPDSbU_5o7ttOHqC~$Sx&YCREH@A-7cu#Nl@>S^c5{ z9GBpNDU*lUJAOgt>96OQb%MtwhRRLjpiy`$gI$ET((5Ol=Krqmz zgz5z{fZym8`C~c-ERpSuGR# zbQlgkUJFR@6S|$rfu2`QN&lbMNvqpOXuS9q9C|0i zXmb@-G&U0-Po0RjRGBh-Wf)uDCWL|F+$AI zLt|r`2RJaba6@X<>RK>l3j(u5mD4IGk0YwZ8eAN*YPAdeR5r#^i%nEC)$u zcR&&N2-aHqKu=p7z4ax4tD>EeRDsHuo|_(sY3e*X;qQ@o%rESXvU`xkjT!uuDJa_` z55Z(I`wx{g4)J^?RtM48EORl2a{u@Q`v1HEyW(6}-!UGdBVIw==Mebf8xKE6+kraj zsJ={M=xB;1%s|BSGa0HlrM`e!-DDu>kDSUcHd&=Ss_}h1wVNu$hCftq-5=C}6d-0NK&Z*m#cXwz;uF*ubjZZ`2-|8xqz3+4p7gPBqO}^vKfw;R{OIGnf6>} zR0o+5w9(%+#xx*Zj8BN%fJWeHWKP`DnO#m zn`^N7;G%76iPG^jtcc{vCx-jIBO){WpKFei=-J+Z2-^eLZI*X6mzd3aj;R z?BX}bgeUep>|ATIxN}~8xz!q=46){3p#uB&KIievliZv=6L>9Nq6=({nF0-Ux@N3)jIC zA45~$MtVl@yg3Sr(=R~b_vD_`@u(qn>yzQt0e^~lDq%bkbJHYI z(R=A*MbTrK;6CveH$6U`W51uJ(P1KH?*0T)X=@Izc9)R5Qxl131ty+GrKPlEJ8&)x zxmHJZ_{5T`RSME_zlt23mj+jRN;~N;F?2K-o2zo>PoZMGTZ%%LmkEQ1-{qcny}=Fo zJ5#wjAFaT|i`F}x%se<4j!ykRs>@5s!?&NQx80)PPVASwcc7R5m3TWnCRNK4h~u4V zVz)OFvP{G2XqqKVAYxM88x;P#Y8BH2nc$u3#hpD9$sJC<$%s~9VqHM&!dum8G&N|_ zzJ?2{IdwE$AxotjD}T`Xzp~xc+mhRLogxFC{3{(rxICq!xr>jArp>t z*sA=aeS^zu2vX#DVVX})BMiP_2+!}%hXp1BU|ha6t*Srti-CuAJy`{5rkG7C=h-n4 z7Hq_Hdv=`38@N1IQgnTbq?jnglx`YJsmWWvpWQ{+VPD$cz66XUr(7yNIaLP!>cIRrVNQxSq1Pt5js zRt2rcBS2<2h%IHcS%<8ZM9zJXS4Cx$7`cHwdPxB|Zn;M>F49}zC1SqnbW+ZQ!AcX< z+-|Kl;$%7n3`*oVu?{U_Jbl6;X*e!w4dQ9c&g_*{P|)xY_y?WYl~FC=q;s4tk}<6H z85XQCYVY!HOjnqbOELST(PSe=rJ+Kx|9KZ>S&B?pN>t%|?@rLClXXHPHY~la<`*H5X`=22Gv#`a=~@I}{ghe0I}nERU61w>5kn)~2cUJbpwy@IEko`C20P0-QTmW}Gm zuq%9evPMUwwo;|^A*e^pC7&cab<@F$?Js45`LP&zKegj9>}82kbcq+$c4D4%&XF?6 zDa)j50rB3L^@xN)vt;a4%R0D#U6cj8!eLxZcXmfuFLtl$SIERf6Y-+CN| z>)CKAVQaBWs5{K_jdAwSet8f_Ggew^(VP+eY#iRv>fryk1t>kR$`VH!D9H6*I- z#H{b869d`K&A;LD93xhDTLGL?y$g}#1#JI&4stq4qxtV4eG8Z(X3zP>iV^7(nUanu z@L&BeSK753%-w6i8F^)Z<1svh!~>Qor8QK`Q9KSS9(9<8g|%s+4eOe!?_lx@e1tpP zgcr|w*xXbKCX3Mb-dx(>ggl^_K8U#)Z>LzlY&UbUv!MVNp1}T2=g9S52bJP;BQ7~y z@nBe#TJ4`v0H$k7AcnMnXr!6Zs~Yy(2Vr`-687e<0Qs;22uSQ_NjkQj;;*BG zu|P~4d7SX!%Q?oXhoSK2nkLM+uSp(jTPTYm4}4es0RJJl2gSZ;^ZRdL#raYigeHF0 zCfeVH6BV;zLn59Be9^-s^LH>%wlA#Ep(NS_&z@xF60Yi;Lm8dYiG z{F@e2#>Bk^(RWbXt;x>2f_I4q%)2@Pk`fP)c~J#$UQ>fze@FoT%hG4#JSg7Y4ldr6FeafLdR61IV^~2$>cl>R#>YFs zaZW0kyKDl;51l5DuvuoBZUby3kKh$2&9o%xW#fn#hiN02d!6E#`#75R72P;1|2y)p zXXeplzs}(*G=ce_S{1g*pc3p|DrvrF&YoN_!1zN9e}z=tS@3$mBjU2lAA~poT(1NE zdslkVN~90LGQ{jrG~1oIrC{898VX+~hjQa~pOugEjZLs0Rsl67s_g2LYM3xnjSX!7 z1obJO;Kg7~)(P7ge_U9@bxO+RxVq^uy8Iy-@x~iw%nOGe=Ra{5XKM1|Obe0LY3mW= z;^%IscMd!8a5Q^AC2%{QZc>g~GfqD8&wEfBtFjfYwP3hLon4WH4i;Y3P~@e_I$#fI z+tF+MUH3S?*Rw^ij7=gY4sM|PH3;I}p7HwW0>vat3#jdgv8m~7*E&VXe8T6(rTaK# z)?1nK$8B4A66(@K`*w5O8Hfk@NyqBI)w~As129tDFAe6NZQ&QY=n2!O*?@LII_Y)r z46IJUu89ZwLaVo?Adcpzw6fWc7{}L3?B1+NU}hK?3Qk(4@~GHyW_amaMm#CZ*;0kZ z44*;F!Yi(pF#GcxU{63a{1>S&9Czt0^cpt`ga9S+9()@rqT^x8#-2i#D1C}4kybXx z5VOlC)b5dK9P<-jHX}9HlYY0omD4&#*ojVkBR9Ol&WKuwUebYzEW~@$x+?=7W?X{7 zFVqD+41Q1_z76ip{Yr+6MF)lNnV`~DUwE?q7rkhOvGir*jhIibv+Zu?L^9!ehC=oH zZlt1v374-mRO#Y>8a$5%gBXo`K1{kd=6N5$(I5oYu2>28Jren`i>i3d6Q@9Pj4nW0 z7W9!-!d%BxzCPh5#Vk#rm@9}`&*?HTv9}llY+CAL?M!}cw&A=M9#ou~J_&wUZl@`~ zRA+-b>D6xUV3M#2s(%^7(tcxkA1e>uP3t@mHEqz`@D>_wHG$hjhCg&sa*3~1P)rD7 z}WGJsi z^yKV1o(wL=Iy5F zvEcG2Y3*>oaiNLHBr1^cZZ z>Dih}RSVhs-ji$zX(U#sACY<85@2o2a!46n1=D+Jv2A|QB=DjXxo64IizXoEk&YKL z@lc+ffrg>*>&PQ!!NZPx^UO@USKYCyj+p%>*bavhMO)@0U2?FY>eO2Q%awZaz&D!o zfe)Ct;0qREpFkID(Hb8k$)zb$@m`;&m{i2n%s$Gb7>~6bgrnJ=ro+u#X2Lg@geg`H z|4efV#goF+%NXi>rxHvr=78mP1E@avl3YpqOw?9AC0U*wSkHI&VCI2J(8A2(|9`nV zTN+IsVy;CmVRF6CCamp*hs6s$xTyC{+`ES5${XGEXjR=2En3u!G3piF;F^YK!L4o9 zu-&l}JnD3heVpRMe%foyHe@Hm&yogc3DRO$&N#*TR^MU8x4;(ZxhY3XX@CuLf4{L} zUKc}Q$Bb2+Q`-3GP`YwAw3w){iD6ODXJ=p5 zeti~b;Qz`qtQJNToq#;?F~y&kgsDc%de=^jgX#>$oc>trtRJoX7=Mz}UfE5dbL|GW zX9ZxLQ%QT+ohsf#0g9AU&ndtbl|+9xwvjpGJ;>JqChX^~nQ$Se4MI;DuyaRwll!=9 z6ETHx^xiZg#=W~av;NZ_#k}r@g5Yz8xOg~o@>mtpc;Y#@Us0lJSP82KeFYKYy5to& zp1>tLZln79ez7~&OQBq3jrZgRI+b2T({rExY~7y`EGKMYMT}-V#k3)&<=PbH$H^^< zUb==tkxqYJJ)(@LbWT)?BN$9Ap%*PgdUa~n;>+4-nC*8TOU2KwhJr>&48OGMHaWgy z2j_gV9KF(VXfLky!&sd%mf&v-^F7 z*lAK-;E(jZks+q(@KiW6q~G-im|cIC97mDQW^WnH%lcvGOE>MC$$^E523BUE@(a z-V3)$C*#30qK>vJh{+f6|ao3!z; zmS&nYVn!QGQ^YP`gO)}z;jpedIj=jCOn*68F4hG+qfu~)YP<5xFEso_#5g?5f${^% zVC>%v+4=Rbq*aaeoR$VFzUZ>yfgRbJ1HYg$8`Vbmvyd?35Hq%;isH*{H%u#+2`SN@ zq_}%6@%GD*kL*+qW{*UN1cCMuh$rl0wxI?Wk0O%tQ*pKV6UO)W26IY3!nd*rh+3!3 zuC?#L?y{+X?dv3rr*zTm5mO(1K4E&^IcDt(#PE@XySAT{>zPrPc+uEQ^dRmv^9MND zNZ}``MQ>=6Z1>4k5Rq60FV??=p?88I(eoR`_o#(T^dLC18V@eY3>LrY433wSq$=hS}pRE8hQ}YHlZ9D1rHRbD-1EQjo{R0y{MvysErm`HSoD zecUFB@s%*E5EB|p6eC)1GTS_4LiivVAOFZhen_=mE>;H}-(a&6dZvgr2IAM#+8Luo z13pqEq_F%W{JHoM-j#lU5hq?i=YLOv%}odJ@4N>_-ysyUK)Pryh`F5RrZAaxgGqOl z3EvEZxdn^jnCaaFx$F8mFkAkPipUqns<815HDJ0MRjXVL#KT)K{8_W`pAgl}~1v1v_WWrGQzRKJ0jw$! zouC35CM*Wlis}ck-!t%P1(aw%hr$X0qHhS0v^Eknb(TZea}$`HHV2|N{G@N_XlX(p zM$GN|mlacfU1PMJWkU1gj`HCa=?cH6Dsl%U+8e4@Lp)zZ7q>J_7~OfqlB)eFT=Sm_ z1NZ;#!=;iC(1^SOP8*g&Z@-REbjbl~(xs2|Xlb2x3Ne01PAcjeFENJ~$OPNE4aDd) z=CGg1VR8z7fG=MM?pWGBAELpQFZu!dKfa??b?#vmnCH5K(Ymwn{lh7U(l`o_0~bNi zM^l)cv;r<@>d=d3ucRLWU&MTmT&`#vagNzJPli40XUQewkIH5Gri{P;F9gN57RT-#=tziTCUb}@zS+-5j8s58YBOG}Ob z#JpWMPVpo0Bolz6sk>_}-@oOSa*yA9rBPxF?AK|8s5abypvkH2n--Mzd;~G4Fhsi! z4$oW%*YECxv;Y@~8?^^IxXgh{Efwegvp>UpXfElt>Ce(B} z$266uE8Wf3DSa3J22svqgl>vrxXbV{o4)DV7C=q zUrhv!T@9pQ_)^%hP@Q5bB}^n@l;1}v78<)SV{oQ5KOUj9`k1AB*?LJCb*K$Oe41eO zvPzm(y49y0tedLnhFudo!W++S1^wJ(PQB)IV@oucHukiPABEBe06T=^&n-c@gKTj7q__iw^0rW1YdOAuK>yEY zNME)ep0vAx*7lR&<>w9>xOv~PCW)woO@?xtWQwtRMlsJ3GtB+r2^uGL z+3~C@#fYYJpKQ=bJAElQKiLIAt2RR1hAohLY8>QW=m-buc0dnfBYJQ2k}2j5VruLy z6}!7yGBJTTp?l3DT~6;*F1EO$)H(8pI{1qh?OwhvJJ}TvC7)M8{nK{vE2xEzi|rv? zZwpi{T@L!yi@?i$KK%V_1Kqp0;b{m_KVrUEfnwy7$r+RT~KdorOR%$p1xp-_Y! zmF^AQ;^Gl_-wt{dBRY52 z%WZPo&zG5q3ndDNgjS02zw(}9UOTC>;#;6`a634E{s@LI*1+QO)sSVp8uqRq2}>Uy zg zo$n~dN?(SyFlUA6&EA1Mq4mxS5WIvptSO?$C>1Q{oHbwRTZVgM`sR z%&h3y2`X=_neTYwp;BFFSAEb=KF-9$&Ux4`@a%yn8l~kF(X2I^+lSmXhpRC7X`M1ThctrX`HoXU8~mG9h)yNM>xm zEArH-mzY{x6pP_=5GM10pl_$(*XsW8Lfs1%jC=so z7yDsF3QKwTYm+d&5EH91G+_`ojnPk#2}xai<+C^6lyXwTI=8gQe%Q|_j0|wAwb+8eSxhH7q(Fi2*u-L&COL*_gK()tph}Am^M_-+S zMX&VWlg2gJ7@Q4pXK#Tc+O~?L*`7-=BN3z0t!rG}r;W@)d~W)T&?9*vCGx+056I0u z8z6P@FZ%TqpPMm$f1nAaqGJkL!DwD7Tv`|eH;3$oRn{lr)Esr-9YW!cRWU@4zX#8f z9#BkpKE*JI*)sO3tMS z@&@?JT`Ic~{mG&7q|s>qF{%l~L`)G=tkH(&1-a16wH3t1m@xf^P&i>f^c#2;(L+#c~w zz(4Ea#P59Zo4b_h#oax88%~-_8mM9kvlcP!UtZg8&kASC@F0JnXFE4xKqsCQ_7Xq7LKkP* zN@=FeFQ8LkD`E`S?Xj)h9M5R}BNL2TyUMHM&kpGGG_`gU0+(wEb5~XJb8bb#4Rh(D85dH_Uc~%Wq>fh@WHQc+ zWWxRoqKv;(AwRY9k=*%01r_)^?}?%f%wg)d;!J!5hbJ|IJtmkc_-e>rau#-eH4t_V z?=KX-Hx(+!xARu(UPAPtVtQ}Jy`dO)#6+yNwM&dDVN56B`HhB>tYFWPYGXU%vbUUy zEF3YiQVc&C*+Bv8!!JR_$)Dgf_ce?es?G*a2!b_jszN~r6G4mXCtgNp_x;Qa>xJrvxAElR^10-5%Q6!73)Ni9>)=-97CgJT3C@)l!6bM+ zl_iK~CcCcdvLC(up}~UZXWEqUvF+J6Ti}a?@k7k`RxKviK|_A@ zw}D`-dV-uzE+MlrCKJ)jq&TPwst;SiX1Cq&b^RjP)z}}z%57so3K*O-U}IiihwgnQ z@;*`fc+2Ax_+i5`xoH-EVf$laig78Sqq%{Y;{kG}AkI{N4n2rl5;n@&=_;@|s2dT_ zZ&vrLq#@kHca4RvTaDq$-S5-^M%?1oz3j^tL_Y$pMnk#Hi2!BQgMXEe@}J5lzHEo> z?Gk2&gb71TrzgvpiZ>SW_kw}2X~sd~-^~av=mSZ$N~b|+k^g0qgI#*Ul@)L4LB8w9 zI+`0b__sAXemRGqv7co9+=pcP(Xyyb?0 za5wHKIb72f98QfTsSlH>aBP)r8dXeP@^2=ab+`y)c}XB~fDN3GO|& zPp&4<7xaNsZTV!dmpa7wqNUOKB!~!OSjVxCv7KHO{Niqqzl9HoLt+y#2-9Z^?hT>$ zW}7scSBNn2aXo`Q2nnK?AmDwudaP2rP`)o zjg@r=v}(;Lox)nYR>IYOF>JVl+y9D>f~66g&@zf*j!SQW9K=*5=P+kZdCAMi83-59 z0I;-r3T&P>o`|`)Vxg-~^GGW(_uHoTx>31@;k4Sv;FnfBOW!ja$UFPxub= zE0?g$$}8;ed!5;u|3}!F2h`NH4L?mZol==Hi_B9pb@K8Zrho^nStHo@uy4|k3czMBE2NsrjZexW~oGV{cB88 zI=>l)FDWNSLNF@`YjNp7r%r1k!4_M8yNtRnVtxiE!TCk&`IzO;;p0S2SX!nI-fIu> zHmd^oD%~bnb#c6i`O4J6Pl)l^)*vgqe2bfsCs933{hBmEJDJ>^KV9ha_9mp%rh((^ zd+;+M5hlGl4QACb;@*VcO@TAk?)-v>HSjqt1a3|dz)8CY@A=^%FE@z==U{aa^ZB7D z%}>P4b(<_(|KSGrBtfF`ZSgQEY|nzEi#8tQZ2KFc2Z|<<|BQG9;SM8)Uiu>%Zy)8a@t(POlKB><_El?8|IDp_VNLVfTRXPM0U=ZIg9jwoWV8Vr5OzNXVpW0D57y{jnjz%f(D zau8JnPW!Wiyp@5kgj_VTRSTL&jkK7_j#gZcM2vS7Y%Pf?oP%qZ-Jm_zM@gop#{ zIbD?I{8B%dw@!^D9yCxo?oWhn=_Qaj06WB^{zWrW2K0X*wr^kF`5yQOcI54ohr_&* zNN87a7hd}0fJ)t(S3XUFm??ck%wQ%>Kg9gdQJ0;VZpS^iBvJK8Rd3p+K8i4fLP@8` z(R$Cicjd5hR|&W*Q8ItpoUh_!zf`Uk408NP@-J`FJE;W>x59Z++g9_hMrXtD19~DR zkhvd*AtrXic3Hni^SQ}NjQsgbfq;kYlENMCD`=w`+B3yiT7?BkSUVVT7s_$gjp%;B z{Iu2ULg3QRe1*>A2ShKvKafE`U`)&Ly!(~U@cC_P5wn{41$e~dZwZkpj!fq|RY+8Q z${dyH`E}gJ)=K5_-sxh6q;4WQR4Q>mYL7Iq_RbOwk6>jw__TTkJ|3TlNrRkBoMsEq zH5q3A>dQYr7X;l+E5svU$uN@;6SDV&Y{~ga+^m*{DyZnCY}MeYyk_F5v<%1ON=)bJ zv+uJwgxgp*6GP!Ifc8~yBH7>=mJa8~Cz19<4bqn!grKNHa6VO=Uuo(LpG&<&%u=>! zvk`M>p@uB)qYdXU+E5jvcQI+`bzP;}YngI+KrYy*Vf&)>^*}PK;p{6+7dcb{?wvGv zJ9K{aHU9!lmT$5%Z8qV^8;{KN=ptWZdv=hN_th z_a&_?9j#1szpSLiE-c_;MnF1^f7w{{t544ah5jkyXrMeh{bIC$njur-3y`?B!cge)1+*{armh{odju} z5HY*iE#QQhO=a`tMmq;_<_`>2?TmLT;|9!8E)VLjq_bC-XZ-@>yx(HQiiZ|v;_v(@ zj@;|h{Vn_@#W7+xdV{j_N0PZW3c~A85}C#kAZ|Cvz|t z;I*U4%7Nz~*H=M)zX*WHoB9y9i=`#ZXIG~OV#Xv?2`{^MLCq+w1?qf}od!=+;(zY_ z0Fr~BF~+IGTfDA-A>|xYCEJkJIqFJl4>#y8bb-0ggJEXmOh_LCBBp>jQ_do0!46;R zQGqV{C#ewSk9SCIJH4-s7?Df2Yn58pJ6ORUJabZ1-R3n#pDNorP z$8IGDNsrdFoOfac@7ooQpGzGG22HcW%Lq#Sh3m zuZ2+f*bG*gCyPhm@Kf;!L?LFId6+QIp7Ra^94s5#p&3N20#ABXf}kw*qe6HIZPcU?)U-e^y$0H3+np>4m#U~-@tXqf(l;+lP=lk*pnYFtMawmU3hx;+yY z?FnM8Bp;9`t-d20_T5m`Z?7d6+qg_=Ft7vZ^Zlc^Xe+Fm@#-2sMa)^fAL4;_no$l` z(qO0!odP5K#ggyM8(>aCCK*%T9qy0;VChgSVlFdGE@JwGImn&Ygvq>%u_0i-7b$x= zNI5LpnCLG5h^^W+_^Yecc;EAQx8dHH-S`G`ZnfYmzrBH)fv2G{Oa`~N1d{3NtKoe~ ze{66v9nM|8O$$uK=;t`B1X!5 zHkF9c_*x}Y_G^NF4q@WKRti}4>pec@;5T7X@X;|ihAgivq`o(qniKgj*h z&G}KutDw_+^nH5yz`pg9M9g-EX+n(jtET*s{Zg6UB12Wrc?*@k%R4GZCaoq%Fuw*j zpP!WVO?+=?jfZkTo%r4?-(LWamZYG^b{ibJ(jKmR81vJTSHgl;6F@oL9b_^q5!1*p zEk3HLMVuQTj|`b4OGm?_LB2~lSYJyyEpRreoBkHU3Yzhb=p`)1n>ngW6?jhK=O|2iEaHynoY61Hfy4ATKImi#=q&zkPC4&NoJocU+CHHV%k#)WNrD%);{3>eiiJ>I}J0uHjB~> zV$Ku`#8iEh%GY;qEo)mWQRUanB_r0JQ#2(Ri&0#fpQi3vBWgC`gD^QM>I2-LiDf0b zpF`g0r(jaF1`EqN!}}4&{D^?dkgn$m8|2sFdrRh0eZw$=5R<*#K<@THN9OcEqFOxg z6v@=tr%3#Q3T|!*>@midvv)PvZLfk2!_aX*qY5qw*b@r7jEpo@z?F^*!BN^8Jo-xb zS)F5Gg3~Ej`~DVe3TAZ#kD1TL8Zj}h$wJ&KHJMhtL}k9>0P#6LT=DGPS#Ejr66oE{e z#KJpW6a%f-3EDEVup+pF&B~|_?S!dtG;4?ky(q@c_bI%5^B6)JX2Y5|6WHHZpO-F4 z!23H0EaM`vygpFG=ogBZ`G_gGcE5~d5%y}fXv+~ZZn3A(b83xr zbu6Y9e!DJDY*{2No$0EeebwnnOOr5+)1@*o;gU*2dv`xy`wSBGr$LwBM$mJL0pFmV z0394I!KtVa*j32(CZ1u|A*QXKtFW$nozz7oQEk4{iyPK;lPv1_Z4vX-z8Rm0Ny@fk zs>HpaVIrCgYY~7&W-roUcqj+g+ZlrEMJ?XJ><$z;qbqg#Rd`f#MO?Hx=1<#>m|lq^ zh3M?B($|?1)!R1e#7-I`>-yu3h}l!pjQ7oXFMc;PaV$OqFCc8BNinl+?!sJI4=BCd zKn{gBz^&v&=50LxYi5jy>BFSikC=~FJrbSW8>LU*NK`Yb#t@@|N}1L|H6>j% zdUaBaa>Pe5Ux2FW^z$^shO}L@Q(!?iJ?OWigghAk37+~S! z!u9fRr8M4ABtC028P0J_>)ppt_3*$|uIAopE^4W{l72T-9sG&GM;EV8P}~Q- z?Am4G!Sc7CfwpgN;@&`SeQloh zydP(KA5634q$KwWQJu_$cfQxasvsM>&3A%frEwxAhAmnuV%}ZG8B5ts}|KH}^oz{3_h+ zR0Psodk9>~q){?VCSpGIwviqPS}b$AYN*=Tw1%_kUBPKoHz}wzBQ0@(&U_FvA?v1m zfalv@gVvnp;zO|8I2Br)@gup<0?4Y#O0dRw+JQZ20!P@vtm|@7nkI%RK#b)YN2xG! zvn(jVP*uIvgY!4~!F@0&6)|HSw8ZzuSo<5$krc1nzJ}ga*cr|v19n?IfOnT%$nNK7 zN$uiTYz}l8Qi7@=6#Z)+(dbsB}vWP67A3z+sML<(l5KIsH0-32}5y@%_J1|T& zVy<2ZlumBzEi=qARQ-CRExV)E#Fa=^i7!93&P@FIbIH(~5f`;M5KP8XzCPo0w8d|{|k%~qGc zFD>ILPu-T&y;*Of%`jN?O_kfZ(@Vi*pAJu((Z`iMf**$`Vo%6xq(fK)j)Dz<)f?+! z%kREmpCgESvx{NWtFa2N!dI%JenFN}V5oBXFikP+O*OaM(MWtfH}^wVgWpG}?Ee$C zUqv0dszfw#Cw0OaTnxMBcOO9ZdfX%vOhVwfryuk^^#klib%LRe>`pUdSEoK=T4`^Q z&U+gwK{F4g6&agb2Wfg*USHLh*HVNU&E zA?&f&<`d6;1X|-kF}k(I;=DCFC?NK91x(*!N7h}=CdO;S;L7)7kZbZ2hFxw3F;Cg& z8O3gaE{K^vL0_toA(uT&HdK|K^HI#drbZlJByox5FTr&OlP2*ChP!PrJmg&rn|tZ; z$FPTIZ2TuM+%}g)dSEj%Gi>ZseHexqHNl1KGIBYR?agquH+>K@rb=aPt@S|m=BAC^)EG2>-LE|g303@PcjT08l+BYz@wrFT({`)bh?5%dOjTa?!-3zJ8AL=g+_Nz z$cb!%txb2yGHk6!ug;YWV}%&?ylvJKGM~vdqX%kF%b|)-?Ia{^zK+;M@$hkmaY<+t zrP*+>2>g_K{E-*W;gx1HKKFzT8I_~~Rb9iNm&ya$C!zCYsESCAvm>yH#cv2=I{$n! zGOlfr?3p_{x|S_fv~tiQQTA<#dI}Cb3u6b`x5FjC5JTmukW;o zdxAb(HN1ucx7@(|k{Z7~iFPPq(!6At35dDy;NTqvPLzA;&g#oX-IUCkSwc=}o%m|4ftf(>IwtkYRUY|Rs82)TJ*_+au z{6xc#N<%R}r#FfIG}@z!E*cGeSCw?-UCnjKc&iEclHP)lZH}yDe0VYtO0O!`=Yh zJ8|pEdJ}2zH;$J4o_VP)N@G^uB)T7{SN+6!1O7;hT!^sh$(Kc#lJ;%Jz>y`_pdt}_ zb^&19gJDkcUy)DK+Mn13c>nTSMFD|M76tXnY_-ViL)?&#yJ+?RG1WoajR?s z?Pydz^k2ZKcmvU3|M{#B?|OO~F$|arK8Yci%e4JOe6JwR@t~KD4Z2ool+ zrogT6h=%gLtKh{9j&{(_-8axGvDYAv2 z&CPkct9Huo@*ScyOBf~%F){Oo$&U>f#Z{h^sBUzXC>B)3lWtDy6lv)Cp~`Lew~tuf z^BXJ=Rf#!J(L*HsUhEvN0fbN6jqN6nPXZrwJ?w~F4EejX`1HU4rGwTM5z~?_S~g-< zZSN;vST>bQJu6YQICzS)SU8jH8muQ)uj=;2Nza9mW=vY{`+yU-tHs^;2WhrhR z@)I$23{!y^k7{#y3vW9PZc0>xk|#+I-AdyQI4)Kg3z_gS3w@m*7=}8!bZr^ttjkMS zeX~FRQaDSh&yR(v&bMK4oIR+aMLlEaVa4}_tlratVd@Z*_oA)ba^hmnN|2~Z-W$o} zvl_UiyGzBrp`Ke?ob5%WiBi0W)Nu@xcIzdSg$(3(1xAzFeM8|}3ic)*yb!*$*XBPB zex*2hpJm(iED;y25ixtrP33di+jEy6N>qC1Z_6IedMuw*a8g_}Y7{yO3`6@vKcB!b zxo=;h6LKK`wN)7L1}WsVO$5i0OQ3j_CU2*DuILxY99?_Z5zwwdYpp{&`LOXzxUM-8 zRg}dPS)EpM#qn`RM9kQA8obNL|BeYv?8|pf4I(R}2f-36Ie4#H1Q%j8c#FfU6w#mA zqSY{r5n_4=n#vc?TEg9bg+7}uFJ*}}r{#mz#VFLv(Pw6@!5^7fD=yj}X(G*V>^r6{ zYJ2wNmjquRNu`!BG);ihI;&w2ufbPreku2F#xO0|qM0G4;G;zD(|rl&^%0LizBSh} z>7@K>?HmQY1@3p(;C&C&!nOUs!Mfjj@ubmPfMWJ;>(1x>t0f!L1vbE$jm`K|84qM3 zN$mA>W|;1XQTjBK@6fU5{Juz319fk5_D_iH{rjB?%hG3}Um#_2ohS`;Lec}h4dgmqv-I zs3e(;`0Xa!J+N5bXXkS<8uj`W!=$CY6F*NnOqfbj`M4EdpSq2F{&kO>+!6^>Yfixi z9aI&+Y$3<$uZiD{4a1B;Oy|g1!q+v6xP9vAhd$6mjH+!E8=UPGF8W!}qeh*l7geR;0!E>GtKl)KHDPF_8gZ&uB1~DB*^%u6sE##t_ z8>%YP2g}BN`mN}2V2pyko^dZ2hQ6NEnbKsGC+cZbnmgl-d7Tw@B)R@K>G>lGoW~yn zvpO|CzdnxSEM(1r=drz+f|yeMk-{U-dE9M7L)Gjye#(;yYlVsFF?nKG7IO`uyW2Rn z3Hq$SN{Em=QR}1_t?1VLrY#pq*@`++ehW)|oP6Ly`>$X>%bPSEJufbrf??(&CZlqN zuz2KbZkMs4>gFO(Wk9B`V$HKw3fhLc)fMzWA%)UETe%*~s`WYZ%UNg*6#58ma5YA1S$z5z?s7gw4k?&urR9IXpm8*|u zm;zI5+lrAwilGfN4(IFf^cG0hHQ}3o3MJRQKM;Sk-ZmXN4rMd3efYs!q`W_q<}$m} z91-K@7%04Qoyz&QH&pFzGmq0ha8eAGmPg$eg4X{bL3@D z%+8B>1Yb)7pv#;Z$ccSK9yMnPm-AnX2YM@FMjzfRY+OE(+l3h3Duequ@|GgJ%My9F zbvfdq{T%xl(hf0cr~EqIGt7fHVtw@A7>c2@2m47YoIf^Mn5h}v%U z-OOT`y@*LAdP1(|Sk4PE%g+oTpPuL__rKgKOtQ-T8$%5bx@c4#TyLnyhj)Al)h^BW zL51F=UDgRwF!~Y9d>#VFB5FYWK^w3SU>3n5cAz~GvyXdoXSs~$To4l<)Qg-l*HNkk z-WlQ2$S~?SvhojxDz|i`IBf;i>C`uHe!ZW3a(5#tIt_DxHM z@kNZf@eyl{6l?A;Gegzfg${B(R$Xw_wvL8O)=D3qtc|`FM!d0x}q-7@qIPC z^IS=?M(!ko2R{Or#%P#l^Z{-dSixKzT|sTncy1MCGxoxCztr zl$pn;OQ{(}Z-F|*&u`|NARb=}78AO?t4pZY}Vg2m4aD8b% zIO)WULM_yFz!Vmy79%X|KAr`)gfw|=e67w+D2F6d)StY&CiDG<8DFsC&kc0J`87oGe5L3!`wuS<)$#}h{wISV#L(6 zbW!wmFjihUZz7{Z9B4q2VyMARyTQ?h8ADs?ikT^&pM8Rm{{Ez-*=q6`q7f<= zRRA3w*87bPU*PZp?)3VIEx%3^t0}Xw^TkUrwT^-319BmAzZIOu$%}Mvjx)?X#C-A@ zY@O1j6Q_lkCv)@VpAWQ99v{D7>e9CWxLN2R#_wj@rv@>$M*RXk(sX#5-EF!6OBZKf zAUHORv>E#f+6;(=cW<-dYlscZ{lzfH*mskTn41l}wXR7!?oum5RST(_%=}lO;$p&B znWJX`P+frDX*S9Rpblc{<)FD71HR?M);?J1SK~`IUz|exMqou=hud(>=ovuHILQ4G zD@s$$F!_jynReN_u%9XS3a`$==QeV>?ei3&F8VS${Ddk{^iHFg_yO) zcEbn7*6(v=w95$17og7?9U4ScjwZAh4AAXB!>b;DVIju!bL3t?4|30}1j>CC5Ec0p zrjMKsT}|2NIr@!wr+q-o42L@F@mhME4Bwj(-n!Ci%}fQKKUQp>wICCvxlso+0Y=n1 z(b1(dRYx>DU`+{p>ES~hEqjvkSFfSptvlfQ>M=aSs-pFE(c+@zGimA(lh;sUeK}5> zTV;SZ^t~2}oDUBaU!;06+AyQ`g9iV6Po3ybqdGKAwW1hxY)#E27Q_62VDhYZEZMcF z9HRVC!F_Wd9u!T4QO{Vex(?eLwNGklhXw{FgBJ6@s19f1YIm?CE1$WwRjlzov!w?JQKjGyABSB#=`+HhIH z?m{qd)Z~NXYJvJXsq>z8vY^tW-pvCU4t`wJ@iw`?Y%!_En>oPgI(*7iLXR~v=s{y_ z_zPy3PKc?kSeW?!=SSInbf!2hp02nXdsT70^DGfVtu?CLQVcb5H{2=(Dh)MpEjE?I zlvYZz`@ReLko*b$YJCBgO~Ap!OD({*2h%$Dv%Tqsm`Nc4iQRU-lZ9#G=V{qo@jKB= zk+6BJh>5&_wkJl|DTW&C)ZI;`$z7QT-KP~oxbJB)6!Y58Ju8QCJ1)R(<0xo+YYr>@ zn4ady4zwj=+Fy!EwBldMcA+}>#U@mqS?;R%-eHG`=@_Re8XlI9vF7Ft!?;e+5&Z&X zcZwi1?F=!SHJNBD-a#LSAUHNW3Ql4sc*|_2awr)_hM1CO1&QnQ3uRw_OH?bPB=SWA zb}O37{6$QUbR4gTW)v-8rnww{q>0JQh2*2fFuvR?v8n!p+&1yC_<0Ui)8f;PRzuyApWvJSZwze$ zl=G_wjH;r^YjTco?`mMsw*ctZIRruqn}a->?alQv@lJC-wlm;P`BNP?RDV3C4mSR1BrDtrun3vfkltPVb($% zhEfnDemA)cvjH*Xwnv4M#x$8{l|=P0V3ERgT^IS9?Yg2@Jz0arZ;Bg!U>}=m93;#z zbfA;|QcSzjiX;iAV@ZAA&#>~YKbT1(Vb}Fcnmqjwa9 z9xW&OmCS8d#4v7%$sToC==I^DYzJoE?-(t}FK)ecr%2L{v+d3>)N@Ol15;@_&0!cZ z=N6mC9I1*R{KF)&w9{u8_S7F%=-dSRlJ|t$$CTU44C9R$i)W!i&G1LE-!IUg7I|78 z({7basx;@Q%0Z=}aZlQsMI85z?+tyVsk{3~k~-h_c03^|8RYovFOZRc3XDtQAlkB! ztQyXwF=iNl#GLsZCA1ryCcBV@uA$x6oRE0%I+a5#yM>5Hpq3rzi-?(ZDo&X4_OZ<3sYE3|8ZEb6 znIxO1?8ecakQ75>($;}Yn(!J7?nmqJw0Tw%CXgLi6N|TgF)4PcgRwjPV9QVe*1S(8 z6Cbig+r=>9h*|zXDWp$Nmnl*us%veV$^936o~F*If5&!W*@LsWsHm`A!T z_#OYlFW?IXKNCUf6iKSKF-v+$xp>lI5fhi0D(JL*CiB8v4&J{|e*DM?ZfkZ2?yPSf z(C{kF7oZq=bvk{;HwbS5+WTSpgciK7atm2dSWJ4%uEu28!!YMm3iLD5hJ>65anb4+ zMv0j9(<6ks))_LtI}%mc+ES8fqDUN&8^9gGYKVVg=w)NOgkfk7)ariC_-8B4iHrJG zGP3m>D5$>#>+WM*XQ~cl4Q64YmhVJq9wMeVdcRO^hW!N44_%PZYbt82K3(~jwfF+JN5Es%<<4W3j>>Q+H7eJS$B!49GVRC95G=B zRts&@vt+k0YpAoPsl0q?o}3@^L1uZDVUAoz2N!-f6l1o6VQ2`ivx6>gads9-m|aH< z7gxd|-&5c=_aS`0@RX#gF-#T16e30y=O!r6=gRtBlc;P%+bE7sTgpi$eUwq7aN-_J z7~hO8A-rrTruavJc+w~)>a!t#k>5);IQ$@|4c@~wO+WY%mCrGbF zh7gNw4Sp;;27}f;0Ikq{WV?c?9IGnCz4?R~=ic`PXZ2UI85bogGWeoGrg?x=|F!Pka&aJY>(OxgVeGGh)C({`+d zp80zb^Aj=i);Io+RGx%)~8V z7ztuF9X%w(fA}QxMU2PEmL&VYUtC1gSvkefv;?|0G$u_k&&R(IO+59;F|d-_T92FKFoP=}vt7h2 zc*ro+TB8^mzoFUP6w}$+fOi%I?uW@M!nJw|NgV>A;ChP8TAw7|0%sVe8)Ej{ zZ6oZ9ZII2y1N}T_0k^g00C&ej{x^mmXlmk840R37i9myW+jFq$V$8RzUcg0!l#usF z(!lilY0x`V4n;0rvq$`HLe>FGauQx<+j%QwxNmxS_ci|*#bbkllFWgAeB$k=t#W2GVvvo#K;Yffw zw;Y}Ku^aUjI*Si+SMysds0Zq68R`Of3y6))P?~8Q^I=uJt{D2hXKKt}h>7D4>wY3z zTVSl`h7a^w@fLPoo+3@%RCF zX!}8-c?BG9X-n>GWEiJP@$;OGmR_2M(62~M8hNr zHwc5pGlFEYFTdMx_9rlX^j~}P`f4RmUuSsa|HSlvVaV_B|I>4j{(B0V_M?%qbqnd+ z31>&(FPkmeZp2)A=A4*6(ugy|MCE>bD@Akc)|V;&A*XRqYDwE-2PM01>iddnJmNZ_S6tmI@Q?4+IOZSE@+8vj+ z{F?g1q+VMBs_jqUz$QP4Sn?hYCSB%Q3}fHT>yIKP3Nf|o4+*9PX52Xp6SditKFI>d7!yf9vzU+#~MPiwESJwGtM2U4p1HKVeiy z57Md`lP0lRT(l>Mx$#9UaqfaH+(-=JCCAh&n<*+~V>0{7d~sB$=(a-)m4^Ck{wYmL zm@(hu?pX36znU1NK7dbHGu>%dExafjN{l|<6&EdoVR8`@-c45+{j3WYg|=sy@fanf zt>qp*O%SDdb%{yyPYjiY=GhEQZo?NH3&g?DI&j-06J~Ea1_Ao-@v%ZO=k}CH*)yRG=(h*ZeXcYIKiTuD#J7(#&rB;Aji`kJS7A?_y=%DIfK$`kVT=(IZfGfdxo*yBBui9}XGe2ZBN26+!prXM2We zwnR^Kraau;l8a*E{7J+y2dh*`u4QabM6AlEN zfz?hWkWeBe6;hUYug5SJh|#cJA_Q;g#yvr!FyYG{1zB`mzGJA3h@sNhZ2dQeKGIaP zvGC7dG0e=*FPJ3aRflpnLIFD&yoIR%pzF97Htq>Eb5L5VHsVy4p^}Q zzn>~LHoquOUft?%43)4T#v44n=UANvpF?&3TsnQ;b;9CAT3d;&Q-g9TQ)Fw8W>OuT(g z&|2D=%MX;OW_4Y`RYYHqKRka;Ms)#-p_%u8FjVWLaZifbv(bp3P~=LQY;uXLFb8sP z2ZBV%gLcu3d2NfZ>B*$P{V^_rr2WH)##06t;KUvaWn^Nl^3A#Qw~JrpCEn4 zF=?v4hjSMj?$!Q%uta1HRAIlf>)G3vzUA z5hSJsLGIb7(53kv@@O5y^kkSLh-r1oTbSLkE!PH5n&gauym9zDd4I1Ha_SfOvuJ;$ z`6p)g3kk0gagq$o%q2Bxg|KA&1=zVI9mrQ_viu3d{A7u>FoQ|4lo}_Md z3W;zigz^`c;nsx=c-q^KjE`ag$q;tZLJ>1bwo%w-*orF*K`+N*6K;)8sC=01`@b>t z^ZX}<`UPlf{pAC7`Q_P%$cl1-%nN%7c@M4vJjsNn#b-%z8S`>jFiZ?$Y_2a9IvJaC z0$!bKuf)ox;q;99-;HuQ|EA++b_@JBOrWbS9}{$#$e!LN+eVavUgT9+eJ=w7j+`L@ z^VxTkz&=koV%nUVEqJst;WY3eSX5-6Xpn%fv@zqaQn zS#5rY%sy2NK`B?^d|f&$y?L74uw~y(4SR1=5fj*Qp3uU|0p@>=odH=kF^6uf! z{+}57tR+0vD_-1bL`)o0J5Uz>L0Ep|fo|Y=3)#)Veci&ak~H zKuqYkWkTFOBd!E<2X{uL%iVhC%ZCN8`Ws_|cN+C_{BzN$G!EPJc$wj8;_+A@@20#1 zIC>ctwM&C#+kMEKcI*gTWuIpmVun0jC2Tlg$X&%|CS#sIlC{{nLU7155;0U4peN1$ zXrrjv(C>!s4b^OBz zRz86?F6W49HOvD5xbd}llGLR?OpZxz~42J6R{+EuE2$w6Q zKBg4*_=LjNZRuFde2&yqG1t%;rgEr%R#WRTbeu3ZRG;%eOm>rjY|)g@!v2EwQoFo= zAL##-hN|lRJ9YTpd%TJB(LnOMODQzm4~NhX8L&@vjx3wb6sWoEKoCpmC^YQ7>{K7@@W;pXejb)fFi1{#axKLfM%k@c=sQg31<(1zKV_U#0 z{{us%`A^JyYzMx7o)7t)5l)6qdkx>_gu=Q{SZ?ZihRpV2s(L?$>4TUjZ>56a8eQ%n zy6seN56b&*$(N?|z414Os_OrVq1IZ*AYFb)tJ7puQ9Nl=@(N7-L!s-;r%-zD1kosG zizYCP6=D{Ij1mk#>u@!Ar={Ok6Jj2o{!O=ydd-DfFZO=c8MlpSIb@?+JyvebB z*U8b$SFk2I1iJou3i>boh~vM!gINqi5Ob`2lwg~$!=>R3{dS0>tk>=v!oF07p+@2V z4O25pm*3&*g?-aP$-$Ucu)0$iw0V#YJG=sjUp~%!=9Vcz{GbVhI%=~T3mDx|EVLOcbeOlY}jd|#|PT(Cd5V{LoXJA z!}w5GRE2Hz9Z!*j`|P_}&#ul*h>_pqglV&MxD9?1mC;srxmu?e2^S|+{EeYbNa~0F zCx)Ih-b0VSH^+?(HjgL!X1s#U>q24m0@Tww?kDrRGK|SLQL}MDj10yJU&rcj3M^N! zlg|>2>ImtR=hGq@XxMy%u^dWe?2Jf_7J$_B*ZZdT5Es}7h2%1}5gDcno z?WnmIDaL+Y)H`^CVGbh3wa--H&14;Jlea|GamhCM&EsvY6Q-UKrJ)`u>VBZQz@Hiq zilNd}SnBh$%=eSGVX0(G=Te*_6#~JMr(kSxgsh&)Zh;NoMQM&9X33CQLXo=;S9n;W zN?g`gZdTYqcJI(E5kuW}6hk!|S|m$9PpYR;X%0#C`K)k9!UrqJY|Mu``}!&zgQrlh zI7oaxu#;x}L&O9iX70Qhf}@8H_xq4URdZKUI5^rxR=UsdzheFwLlMmky_g zn9bSt^3pRGrTqON*5aLperURAR8{|jp=K17rgXK0FKsrD-0@Qqi)qEMPvbJI>68w6 zM^}>6k^lN`7$zPu_iil~9+>NL748yM=Itr+*|P`9c%2Aqs&!I#H+4e(H_Q<%DLGfL zhWK25Kvr%ohJKb8Vb`N{XfIzwoJX;f7RoRx#Pk`xO6a&$morCczO;*!XP9=AU9@g1 z{3nLiM$tv1wkMSajYxj}yv^ihuLtB%-xAoY6AWdV>2N}CCeiA}q`AsI&oso;3!4Pj zXk9KEF_jJ*9F6XQ3NwhR7;N~AZZ zp7{S_GV~1jHw})2;~o-6=VG{E5Cj^i3mAsBBD=85AH4-0vqh^w%wqk$!c!kT?i_xe zA1|As3;MqF;I}Ixh9>oi`2x6TRGL4rH7d=Q=7zjY)HJf`TsGNPRR{@Vg5d1nOxO@I zh$!bW%)btF9b)Df>=#;>>T&!LiOObg(?~VLwlX!n9)Dv}3@f4T*#E{<&uPi$sV0!K zt<%U(>=f5gej4s4J%MIEW<=VFd2Z9#qBSC>+2MVHmsFoykC?I%J%lHnN6Pj$zb?k4 z|42ifDYR7npVCaImhiKC1DS|pUq7ehLzwamtd%^0UF%ztD-RfEJ;P{!QByPiiO+C&s1&ixg7V5M4CmpAx?0Es*$~DP(Eg3z)Ld543U~ zz!<9sTy_q#J?$CB2r&tD2ZX`5^to`v?4R&Vh<*A~s@89hwWT4$&_$!p6eWpe%2G5h8_!t#yfRGtNa<2J$Km?&7jxJ(iK zUQ3SM)OVJ;};Fj-3^uU(JXOnF4F}DAjWisn_!ry&wa$t^PzcbS$I38 zpjzuBI=ZN4L&HQ=8hW6quakbBG=z64QjJ$j`e&qYCd^$K1PR7#lsjIsE{eaI;V}X+ z%Ol-{uxNcQ7_ZKIug@r!zB(i~((WcZdomr0!mtAjw$Z2A51l-)dlGtXDTXE|X*XK% zZ}p|*=qOFNmGKyUhmXe&%zjX}#$8#mex|r+xlHS{L5y|$FJakM31^QOi=&##a_kL# z@N5 zon+O$xrq72FjEjC@gj1gy@uQiygHZsSVdf#nJ8a3DP?B6pFziBY-)C@Ow3h3a-A>g<*fQ! za%asmASSp;Y;u~o0-F`#)J57?oi@y%T}C>8u7cS1uH3nszc`y3f4H}3A|&oR4QDIk zl`*T`Ma*x8aYT&irZD066C-ZsT8YXuu?w^hJEhpZbUJ74_Y^Gkeu2}dQdpkz4b*MQ zz*sv2zUnmRf8v(+Eq@KOzZ6L|Z=B;E#~uN1n@wPXsqiV4$CQfDQzGU%v!u5oW_FC3 z&@9x1i&!DSMw$`i-nTFEfY0t69q~%1E4;?0nFV_F;?N+sT~DCLXB_=b9zorkT*yl} zs7!u&nwz!qFud0}1T(S{p{@5w#i!}4jsO^DFJhMXyt{MG5Tm#YB&xsO-4XPs58`g! zbK$HnKN9pmWuI~)V|lnmwg>uw^ZhCOS(h`F$0 zmTG2|M@V8mnhHD&wJdllbS z@?53AN}MEXW|Ad#95YT}Q?O_ssPqCQ{0`9I`_5k{lk`p{t;}v?RAd$e#vTWLi(I*+ zK)@w`O!soM~R{Lwpkkf$kUIYt3T_F_{r{C&EUF$T7(>+-EOaYVTMn4C6y0w2!Zfy9`nu*#q-dAhGa#6&Y`(h<}B zw5_l*T94b<6IPM3vqx3FVx8JLx)Lh95aupImlilgJOpZ8Zt`)~sS zybbxIrtai!ekr*w$%Ep}3E+1JZ-?YOu6=C2h?&JO`H10u^TL5ax?JDx=v9B{r?9?p zTyb0zT|<~Ck$B`a9I3nqHeU-MJpVq}o5jMgURYpuHxle)4SDPEizLKd6WoLn*j;oR zQW}$B-`n=&?)Y30)4(vV5tG!>MKDZg&fPS}I_Vd=inzyqiV=CqQeD*zuuLw+qL{l7 z{sU)x%kF_ims{|B1(pC0xel6Gx_H&)Cb?H-3U@kJ!?pwQa1$q9Ot3R2-9KiE7$w7e zK+L2CSA@rtG`TFqboDV*uGtr)2<>)O@I4d-btg;UHFmbPU6TiurguU8NDO#1{{+u} zhl9=!BR;q4E=jj(4=ehA2b~1`6P87TX7xaFm}3|Xb_D7X)6qRyuo|ewUB*RAU*fH3 zQFv34Fnx&Jt|s#T5cVd1HGS>>KPeHVQY3TYoy;NB-uty>PNvK=nWK=*q)C!WQfbnp zNi<5-K6^V2(u`1KESbt!nIeAc?ESg#`+I*szu)6`{(Ebc_L=6`X_O6`81L~nweS2e4eBOEBhAs`dz@KkWeh2q(cX;ld|n1Bx%}xCFwjr z<=o}#KPV-l0#`ek(4#Nh<*B_MA|}T48DhwY>N-af=hT-lAG?s*(mOAr)=Y`*YPE~0 zD#~OU*S^G@sEc6y$w)VqZ}hiwr2W)?Om#JaVIwbaAgA=d|d+Twf> zWAf{%I3T@3^8rG$az$zKrjSJcE*DWWrw!}IuuLy1ktrqlo?jxPu}nP(QSz&FiG?K1 zereHk2xjulqg;OZJ1TP|sqqMYO8;J*!CN_W;SU{8fkT^w$$Lf)n*YHZihqwKj}o!5 zn#{oQ&!9Ip88R-L@1Q~@9`4IRq35W>7=6kWr8zIXr27%fM}x84I?p=l$5?U^9Ll9{ zj8Eqc1`Ot7=A`}`lXOVJD4Nj+9hNX}bZc;V|8M%#+kcoNC3n!eH3Bzg9miZDoo<^U z9X4Ggzkm_Jq`GNwKMfyK)#OaOoDe6|obSa4nNWN~gM`V6mE&I+%d9JK?I~dvlW<*T zzv=XCj|=pmH8=559s_l~Ls&M*ou0o`%I-Fiq%k3wQZp?s%jrI~Z?cB`ZEUIRgOeBE z{AMh#eRGbL$ktumpQ6`@$P7dEBXUVDMg|K~5&Pp=Fveb0k*?#7ls1L*!& zrCjx|5{4oekC%hE=3;WV%+io|Z5qfATpq+nEL_A}^h!slvZQHV_4g3}HWwN1GO@-* z!rTih#L%Nh>BI?b)I|F`(E1Sq?Zgf6IX;ngPnI&e{G~;kPB429%;Fx6D57i@kbU#X zjenIZ=P8GOc+11-uql0tk}5L0`@}s_p$q3+g=JsT>hMV-nNofWJ6tc*ec$z`);W>E zg7?l~_tCk~IWUf%a!$H$RDO#-oB0HDb?98K<99jrWGOkJ$J>&)9lm1FGnKn%@U0N=0MBJP znD<|G1jkXib~L6{uHsurVyt3&zWpUivyouJZ;avAF;}RqHX8DK_3^Z2aXfF`qh4mK zl_5@Dw0Up?-`?JZ(onK^B+4{*?HhQ#jDywR2y`mb;D@?w7LN6kY|c}<@Za|K4JGa2q^djmNi@4&-4SG))e z$UHpTIdNDQ?2YPe+5DQjeu8cG68=IQ2B_5z29wE3?Y_|H93VRzQT}!u^85H8v2{7`9noM zLZ5e8=s1x01vYJl&1QGz`7}w>q9u$g!3@59%8Y6`PrW9XKg#3z$e%jG{kP_nV&5D} zBNLTeWiT+QfPvo)@l5mYT95dXF~}Gb2APH(pUnsJ@2&3O$W2#Va@I$$OkVDzPqHp93}0%E!rhR>qBKzi(-d-v3u`_>-6s!^cgN-mo@&SW z1G$Cf4Xu|Dx}-`PSgTtM%dIl32}^}k&?h`qI(!x(^-BSIL;jCs_B*9b@fuu{CcYeKB3?0Q0WBxM-OKGb7?0 zcY2R2mApYi-plYFy{OZAx=yQ(Qi@K5{?2>il;3aMO{{ow9roQWW5}N;C>a=v>Y>T- zxVDwjTKJg%O@hR)b%=hV*T%ofwRkDUeqehNmvU-l> z^G7JrG0)<0NU4%c_Dx5`Ff!@lWfp3>Ct=0L$1rX=M~vA_B=iLx;L7o%R4OsyRRE?e zrBT`a4)xGfDq0#ZVTuUGxT+ghv(lN0Sf(N0s&a$Ay0V{aXr>WuIX4a_v3JOvh*X$u z%Y(<@tFY~#h-YPwkT)g>UAL#8IDfIMd{BGAc}FqQ)B_R!lY+&BvGk1F(!McJ7Nw~q zm@O3s+{ow0C>L@<@A&1$r!_s~x@@QD4C@Qz-`|FkQ3`VI$}uwV3i{>7BV+GF*z62| z&vPDEPamiMaT!V(Yd(bT(o>jyUQ^EB zgD1{!8;%Pk88PU*bP;5$h|;_!7>_@Z+_4o0sn{u`cV_`P0iiCp5-I7y|Tc-+Wqx$yD>s`-rpkNIyU1(sovu6Z@yV8Sw zS4R=^nP3(i%;mJq_EQlwQ30)dUd!l<`MA`cv}>0LR1PXdQbHmL;>*x)Pb!q`Vo><* zKJh%A#@Jn?6Rd{;->#76Rd*F*V2&dSYE;o9#a0lmo)H)Al&XknB^WhlfeYKPhiV;9 z(s_P^a~a-eL9I4m)7?r(CWbVqB*C(g^Ef4Fs_f*;mV zG3lYO2q{8cdK_APvtfPoGR)paz;taT43>D~{7VkwPh{{X8ZPmR;tFBb(E~qDPe3PI zU7@T}x;-aL7!88CmlDJ|Xzisytj@z`FQ~@&`Le<{-D$5uA*6cf7F@}ppEUY9THhz3 zZs~b6ncPKFnHTy|c?f?zhmYSdm@3^;j*(Zq(YKEox^&hQzAlt%qkJWd9>F{{3*+va z?4$ZBZ0I9a{1J^`RB*+2^OBS2ki!Dh$4mzONnfbxAYtA}7z2U{NK4`-6Qy(e7mI~)QfJzIFs@KXxHY$YeN+L?~|6STN6;T zB?KlrE1RPAuDtgdKW#aynfY8!u_vBne|mF#o)}$DQ2o zL^+a08*Nr@);h(Lx_^_sj#>s@@wj zujC47piT(q5A6KR}H)xa0>ln;Xcu9F9K=($Sh4gQU~|a$=W2e~24tX%Gvi z6|;l^+*0A${L5I7zYRNX=%VYM3L%wva24iYk%U=8Fv_dWbFBy5D2;I%@@2PF&COf` zsMRlmWHnBw5&D})Yg!lzm!=_uc$wBLAoFdAPc5a%1?{?~;!7uM;o^~z!Wu3O_q8^_ zyO%PG$A1=k(Br{S6R~7E_{ZQscZ$AbgAaRp=3Y^GzydP(I)~Wg?{kxy9J$2 zPH^ay1<&&3!j0@y#K0I2?~(LpKS`+f~Bm zBdJiIz6BQjIzeq%jnM0`^lft0MT`f*c>NCJ7VL7NDxe|1_9ufnd9Oj{ad5vZ)W!>z zDc8y9k07{SPJ)?T82;Sx!L#TBIQBV!gWl=5J!q4lo5ToRn=`Qe!cwqy<;>jGy>9G1 z>MlytO~Uvo7VTF67jfU2%C*pt{~XYPesV5Q#`W};9imT?HdEJ-^CtkteJLI`45 zZ{mf@NBCGrScZk8OI4O|?`4AE|4#xs4c!diId7Rwfp5uuBS|ws!h{lxr@9+=XZum= zEO9~xcilkqf*HT7+FsTgcY@>z5Ho|E1~JwN;#jvObzW$lk&F8&yKsGFB#9X`3sXJr z3Dc}2vA|#s&MYiu9^UJE%AbUOo+HF0?MJ`g2(C*ig523l_Jz?=nva37c~{M1emhE&93=&fydp>dlz z?9}0gW1Vygv}%f&6oN6l=gi3q?5UqKHRK(pC-Vnpt>vF-E|(cNxg)842E4AF#-WiH zVDjNC96V3p+fp8xwp*bZ9)n>!n}xuQ6~b926mK?6#neaM%&6{qH3FI$?&>$3jXO4uyi0&mAJvS>N+;ASqsDXP|T3O7nHhw6Si!P#-zxZ z7`lBeWAZ@%#=D+}Ma*XjQ${dHW(07Q-dgGi@v6V_)#UkILu9d=vt24oufWT|Q=}8mMPbR8JVCg08I4MtV7A+faj9v4!}PwS0#mg` zX{rcj&crb8@`&Zs7;6&o_^8S|Pg}^pZJsIH`1%06MqVV%v`>K95P~7gy8<%@R+{de6ZrGyhl+(V2_e!S#(_O^8AQGkGnyzEI5IdEr+4BIvqc#1!(#bg!NMw3Z zH*6DQv0{N6zD*B6&F$kD{&GM3x02eL&sMmW6^VyGoP|#`d@%jt_yjr`@{CJ z8;;~TLf;}8hN`m=+b;+y4~>NV8F51Mjxr=aIgZK40+}b9^91W+$y86!5ix%V=5Bfd zcQa}-RlkB*HtAFN8M1I$>wt8b&d}}fa*if8nloBG{m^fQD_XWWAm+&>Or)k`W-~c# zIxG~XY>O87MHR?Ba|#Qy{FzQRrGgMFS)E;ah?q{_Nu6|u%UsScbE@515|efl%!gE$ z%j(i@%kKZ)h7}%BXxZU}6ywv#n&pB_dN*v+l5qXy6i|D@QT(NcpnE-9n8%PfLY5~s zB*!y1x2FmZDndntPLeR%1T*7m5;w-%l={A&6voUDWDhll^PhSL%iQm5g)ylOXqkHy zt~S1ic;yUg%PyF_y@*}cEbwA?0Q}!Tu+hCF)QzpgeIGZ(MFlVdn=EK+O5f&iPf?ma z1oQn-GFPoJhEl}V=8rMvgZIYB(&h>>#~oW?KxU-`JUIf}KR*A)^mD(6RSPZPH8v3E zg8KuA~M zz)k;!u_^OGCa1qswWa=oSwL7W&~qC_!4*j*C5K8xF71S9j4aZxh#vaTW7BLHvd{Qg)~V$ zU9hNh7yczpw1*d*7C8vc&#HyDy$Vs(ybINXXE8f}KN8&PCClcLgqcb(C2JG8%V`6s z=|q|XTH5AiCV{f|n~bQ;;BBG`D87vX^Dj;N7bd)&Crq+jg;AB&!nHLds#v?94CS>_fSbZ?o>{FEfqbDY5~(L;j7?c_Cr)4!fW%diTGj zIhJ`6cZ2@jiJVjx+k)2Y$+YJD6o%$XZ_n`(W*NbxmLzbGH}$5zZ6y09rIe2lUdt+t z@ASk$@){^l3pPMhF$cULS7jTfS(C)1-|K0)u7(?RBEQroq= zV6O5@ao?0m7#o7=Z(hVTR@^Z^PP`nx-HmAed%GK3e>(DtMYCKKh5MK7Vb|FbH?@oKFqGqzLeL86{0ke5@sL4ba|1_xkq0yzh_5kaoeWS8M5!p{HvGv zsj*w2^euweWOj%lvj#p+afMFgPUMXX$G8U!nSdREZDtqwO*`y_i2eacoPQF$P9C${ z*O6{-U@c;{^%bRYCYZ*F(cJskX7j!Wh!gU&9`kTu34Lr~8(&bqS;TC-z5@+`r$vR1 zO|l~ev*8G+U~u0&6b5Vh3Qn;%`D^ZH5OK~E7EAM)UkzP&_Zt$XtAz0)m}rdzu3c{x zYMK|(w1+2Xn}y9X>$tUitjcCIC`CYlsg$1<51Um^JIEyS^H^mFj4nHiyO(K@hNEv?n(A@)922e<2(A zCkiDa<|54R1Y@~;0qryEkchb>VG;@E$EDj`MGp zBx~H@S3mS6>2LE9a-)=yH#G1a=QxO%CH+N=j9|(#len9jeW*#rBrXAKAmPM_Iw_O=vhnzQas=(d1BIVpne?X{1q5 z&Sx>D@eFbz;|2cCTE1VHKiC-33-aV+W{Z6*|8~tb5#u#b#M~j6ilJHDA@70IvvLhN zzu1#MvSOO~GbWJQ_-Lbuaa?E*e|LWVq&6^7MxJ`}I+6e6sNt%c(e`v?L z!aZ;+G+s)WsoR6#vnoJ1A2Ocj^iN|-!wkF~-^koP(O&TXvroiSNSJzpQNEJO{oeZz z<(;n~4_yD5>Ugp{9j3CFHcZ}trhExg@kx?~+P3B2m}ZxAxMv(8Y@9it*Ij)I4`MAb zw)i_ET&d^xXB-qUIfkM%9|`9B&{)oUq%mcfO#+e=UQ_xvpHQktPSVP=B+NK>I}*N= zFor7s!IbtnPo~T!3o|ZFHh`ZK+;O_4-sazDnqtuuDxkoWyoy42F^i{ak?7(QE6j)=M(_K62Fs0E z7!4=WV`jbQ_vP*sF~|QAF-kv3){qL%4en!1DF!{CHln%Gq}4JZF__N0z8(f`(wU~f zC{F1AQ<|u^Q83?gNmwWZnXi3(5|wqcQRVc4*?H#`e`?2G5#wYeV!9H{sM{%=@MZ+{ zJxD`twaA3(nQKB9c!i1>#YLbvIu(niI0bZ~H;dm!Ax+qfD0K9X7B()<%-NHC3Xe4x zqh@P8(|uECA@aD5UwnG0WqkFgZO^_}h0Zy->{`v(2VqLQOg2GDK6D|5#G!^%BOI zV8;7!+(gTf)cj+l@1TC8`I3tE)YtXh{(mw3XA&o{>Ulv$$Cv8k>5C^Rvr(-4gvq$7 zBV-v!XWAhNGmc>1nqBAYCXAv!9VGkaNmsgHS*`gxhbF3}@INY$@%n#D^DZ_D8>^y( zc?+v#)t`M~l{z2g1#g(Hx3z_8nWSlbjKy!m5KMQs>)e;eCREUV68CI9Mp0MlWdrnI znkzKzUn-zDY!r6dzcj7SKa+8S^yjQynIsI*{AB)Z>KW+%T>#@j4@j%SRz8BW7geA_ z!ptO?MD=WLQD;+X1F;1hmtB;NKWHRlLzjyf#VMe;Z*opam__B%_8fg`GQJE7$DY}V z!h%LW*>){|OlX`BOLLydw7bm@&6c)jl!UP+m}?6&xXCxiQ`ZP)>E{h*X=UAL&F&pJ zg)}v5rHkNS(rg^F6^f&C=BLRxt`UjuZ%zo_Tif$jZ2j@$!#r>e0yCxEYktj5>FA6Y zCNA14f|;q3#aX70r<4v6JFSM6*`%{nl-(RzK_7AoZ251D;^G*L|b-Hj4X3fl<8H&Jb^5p|Y(|;8rQCRX&HMJ?7%p=Oo6cK|^@Ea;=ED zEMayL%mD9OT=2y4R4*qDxs#5C*_ztt-0*I?B1U1^D2!XhOIm>`$d#@&@7_~za8(2* zXV?mjziVZKYXcFcwHN`-VT}Fn2EOR?1`!h?VGa>Y(!pZxZqZokF4;FHPj;t9NBPJc zx7Txuqcf-YJX$n&LUBneF!u-B;-gg*6qt2m!>}yCRB-oxLaloo4W`F>^v}7)tS&5* zX?@r&V#bUV7tNhu!W_yuxC3~I0O*6%{rjSN??|(35Q?`rJL>-%gJ35i*?U%$`-Or$h3{Qjmb7v&!)iaB} zrqOF3OYfUT2@^~(>glE2H6Ig7?o5u(wJ&6DZbK;ffTua*dTbOi?y0*(X)5+h=AdHH z%4SSO#^Ot8`}|Xu*UOFWN~NR5^#D3-c*@-BS48(&B{{lAj1m_uhG0I7Dd!w>O{h@> z!{!H4i--GAGgXFC3gcFxY04hEMHNt71m4r_L`^H$G!5CZ1bqLpU3TL7TQaOO3#M+K zSZvh}rK-J|6kRv*+hDYaxlAzUmX~tbC&p6uj*{XFn+Qtp%LSS3gb1pB%ofoW(CM^? zWTl)HEt~o(d(!VV8qQm1z-3b+{>cgCk3YCUC()PCrSCC}P^xCsEjZfDO$y|%l`vTZ z^I~W&7ppUl%0EmBG52+$w=YkjWEWJZ*m3{!#9g;n^g!8MbQ8TCYbM8tuAvR1qtJLa zPPR_@9=&UKGWHJkg<-iW3iakNeV0j2$gdJcPB7E&rgG<<$5D65VWV%*jgESJCwu12 zFVw~f+hKD(3Od>QVYVj_p%>iIwZcJsd&=`?!)tvaHiWkmxC6hb(~}e671|U2cmx};lYf-j7^P)_-#_hikSNZv+`Ul z=bJl$+P#~oz{BO#)utn|inRerS`pbdlqH3@3qO zYc(~&p&^bQv_1w*(tZrrXk>c*`AlcDCxI98a~>yRo)HYSE}nbZ-IQv-OGAEY+7$Dm z+=J#Vuh&trCJrQ}Hx`CHok&h+2y9n)!hO#{xZaA##BJ6%b1MSJJ&Sn@Gd*FcQ37s0 zaEEW)FD9i^Uq*+QT&k>ud8_y~rO{mZ#&Ohs^2F`;rHtBjSJmvkwi&f(yd(T~#bIjO zG3;9%ib|i8qOY^CIRS>_7Gv4pSOjiwWp2GbutWUo?ck=;|Pf!Cc@8X zDFz$HVN^p9)v`;M3IBZ=i(JWojm(~?y}OvP9W8lobEI$cn_zTn!nleEhVme;p*~jL z<~>^|I%-(C*|>fO$Y|FDgsyT$>(y|W%|C^%znoxcl>{A^<=9NJAF@q7c+b!x`c_pO zV%(3T^h{qQOs}LD{gJlkItkP9C+Tn*bBAmk|DFC9b<%!nue9iW@tYSy_^ZoIAcavwb)zz?j4YIFqz1 z@>?e@nkKS zcQ1}cZMrvt%|~L=9cyOc70KQGQosL8bJJMN{chOb=+t3f=Nb{MMq~b zMqvHa1Ex{Y*k|Sk`(Uzwqf*6)#{m*v-P9xpYX!&!=@OLvYbf_kb++QB+NvDInmvZ>p8%hdbXL= z-)J;a2c|vdiegHsq@}J1eV!~vJU)(zh5pd9ByjHmgXVM;RBT0!Q6@R(9r&(&2Qoj; zB_g=Y4Y~)0;k~LVQ&A^v&tz%QEC{BPe<0_welc}~IEcgVTbMb|dP*ILdt=^o)eUOX zQehk81)Fnmr0q8e6fZe}&}CQP_-Q-7c1S}vM)VG{(rluW(D5)w+w1+zsv61N9Vcm; z6~Rzy!Cbo!iz#K2JE${lu-R<8PBMMRYRaU}owU)-K+R85`vj^Z6-JV>kMikk!D<^ z9p+~~;;-LzrfZx%P4JUn2qMr!M$-!a>&*o_stp3@KTdW)A?uit7H&MJ{@>z@u zyNYP|A$Eo`j$Px$ed8xx1nUUK`_;glMvqZc9Leikxsl=h+k!chWic{sHBT}Om88Xg z^+5(ne)U%mLF z?cJDk;wA>3n??ISf5^zxuVaF8Jo-Ag;$ub<;}rHll%~6caU_`i>o;?T@5fTAB-Lu8 zut_-3Kauv7o#0&mkbj;_GE(OFp;AqXNh^ZIRkJ+SBTt^al zROtUmhPGiO4t+ljn^OW}yB|T>r%!mh)}ILre9A=6xQUfd;}90&hUdMV8I7${qH@g$ zaeI0aOl#F|uJ+_|N=_o|=k1&LZ7MzJTSg(Y@i6k~rzx@^1H`lhhu2ZiA58oMBv@=; z=uCXgU*QlH#LSqef`#+$VZfJgSm)bfTJtnU|9ytIXa5t5*PAqw--UbHl{8I$R0c%^d3%&e+_| zLdB#E#7{hp#Ir$+``IiJQ!7amPB5V^37qNnz0|Pb#6c_{$s~WBK!3iGMJG9uf8ItW zD|>`uq*|7knWDr7iTMI`NgjAXnm7-c-dthVpMc#dmoZ1r7gyF^W4;?pT}I+1Y0?Phu6!vsT;G-2-iut) zCwwWH=XLJFsd;p3-Z?RA$aPEo3qh3V5 zVRkU+;)76$JIOr16)Q?}Rl?*DjFOQv7xl}Xx};5V2iXw*UF=c1-5m?sYfdOi915|b zBnJI-1%&D+lRXrHR>yJ}lc;;`zG}D`bY+&+U1K!nU&A8{Vymf;)BF_A>?oAJO}+Gt zDj=BDy%C(pPYWj$N=Q<&_I{E*T%Ag=(QqoijmkKG zTy-GblcPfz?M;o$t1-7R_g)}Q+3msjxdF`AW757!mM|3rGoxK9_bAnqis(p!UJIYe zW*J4(>rAW6Ye?>sBB{?tEfFjJ=7}ka`zkNMctj;Oj}C;6aV@6)bY-U5<}gWfWT-rK z2|12lq_Vh_nPGB8T(nsd<{`o8&x+<6oxG^GN~G!B;3V3keGzAz*oU@hiG~AdPGYh< zi5#CdF})xY&lZz}%j2ZO2+3CYe&ZFoHF`1E?H)3gHMd}@8-?WsF6gvIV2<926EROE zzd#+qELa)H<&E;DmbD}9?)JuXUcMhSzuRha3vwgsr{6|Q%Vh+;yM=}~{-g38kWiUU(UwQ_vsyjr#Ca!WCfhDT z`_DZzS!9T5*ZNT$;yWj!A8FzKCpHrM*r$j*=)?5?mBlQXDuWfDhW?ArlJxnHOt`wV zJ(DC%yH?WS^3YK(H#dM<+d)JA;>lUrxaIw*`x)D1HAQ58chdu6M-zLjsDgxwc#;yA zike?fkTpC8n>1g6zIL9`+xnVWJ-Q6%`o>`4CNI3Gt7JadCyCN9(xRymj8ly}mw6$O znxskw2*zo1NqxrCJ&Ibz`kRs-B#FE@OU%4iq{LU8PDdVTSzvNH7L`>s_(uq4PFj~S zFDeAI4~)m)?mmcdx=Z>EToy4#5=Mt$=Bga!x+b5a){=b_71WKITsE9~QhYrsoEjCfR5RO5Br87AMViYc+qhh2{_tmt+E9zBYf?M6}t zvA=}rM=&u?2ROYO!PF5gl9q5Zo_aRtIJNOdFWzAau>)cs!=x_Znff{|W?KmLq=$yw zz2ho6M!sD(mhR5iO~@3BFJiQKnA{^uOclbE3^)_+*CQt^39c7kBjHaRqqXoI^Sref zn=<3EYfTV#4pPPpqBaW4rl*84A(-Ee^SDD-La7D)NGI~@ja1obReH6T6@O@K7Rerd zPU>%Oz(4SzScT_Xd7aE8cnyn9m!aO3jIjO^&bak?zr^a2Z+!GB|*!$J)MC*!J3qIp6y# z)7DPF7?X22TZWQ9BL15!z}#z zy98uZza}F@Zy~QsEi5V(HMw$FJpL$FuU;vx!ql$+=ZoM1o@<98Rj--JtiC8>^d!sy zf|;>qD|aI(p2{Sct<(JJ?rM*yBH^rg&4n9?*+3cqkqYlaxQPC!_>rk>_qMM!Z_h6i*z_%)Xz9+Y72; zVMb+VnT?(pPrV{`T3whEUG;ew!E}w zay?f3QWRp4+O^xCQM2Y6=8^$|*-=SM_(aobx{sjl5f{ASKDUgx|YeZ||4&hgHNf7(Yhtf&x+%T4A!B#x3o7!3FZ3vy~F zzSd^%2OFdJ-(|?U)`%ThGU)UzMLXRwct&!f6#Hg~gb@g)rdv8UZCVC(kX&oad8-LO zZmQA;dYRK|jRmOF_)G@V-NtK8(sJtZBUqfdC6;67B?@TWrq22w8;HZYlW}iFJ)TZ0 zL0)Vv2A*1r(gDv!%&x)W`=*Fso{T@k%{_dLa&1ov|GW2R<{KZR_iyV(+a?#n_Td*~ zJim*iY41@(J%$Hggc9~AhL8floQc|ON86rwvUn~UKfOiV-!jkv`)&n}^xd$yRmwdXmug%abFk( zy{x-%%qW4WT0O!mtPnz`GAh1}wS;+1Fatt{)-GUZuh{PE^J0}3lo_(0+ZB=ky%S-;}$leSNJm6 z43M^`s)YGWFatN8%CWL6ruas6xz6n4{AN2}+BE$&b;zdzD_;IY!wFKqKIJO}-IuUz zcL%#`+Od|T-lpt@k$D8L;Y>&0ryjpnms|9BCLGbbK>M+? zxkE=QVXN{7Y8ubQ5lD(b&#s>L5xBJjoAkK?gV*S>her*9R_z+x>;4q4Bd%fsQImqe z5%}zvCt`{Qi3+VjFdZFFaVEtNDV101av7P0r#~Z*-ZlTc*w04MGsS;%tvE5}Uvt=} zol$1(Gw)*OI~}(Ek2c)vEl?L-iP@KP$V2fpOgoMxDcSiV=9YxfBbcMl{kfJ^)N z)#bU@T<8}!CeVw*yHgG&RVbd;o;CRLlC(1TBX%5%Pko49xhi5yBi2rv4Zf;@^(UvH zY|K4e{+NMI2cAR4$`HN!O47WMk}M1e=Es-A++n3xRCb-Z+`c)6etGjay=(bh^Cp8w zP+6|T*0{dL;_K~Lr|OSrCC}Q`A3CyvQZ@SQQ)55huV)&M8=<)4O~~tRfYJL*hS<_j z{w{r+$5Lj>aDsVaNOAeXTdL-{y8K96A{}~v551$8E*0wf7~&ju^>?_bti&2m_yXJf zCm7SW6Fb-E5t3E9vDq)aGmFATV}W}imIPiwv0($+{T++V-K6OX^CXNZ!R$=w!nyYR zKrJO0`@UZE<`4GtuI96x!DBLKHC$P2*?Mp~X{EQUS)5iX4tFGjp8NIg%!Wyo#UyV~ z>^X$zVINUuW{S;~h2pmvEn!%K`QTKYbE@bwwf&j8ykF}KbN=CQ+SBBkc|*ht*mdv7 zDu&dhv&!t6PhZ73g^GD=o4-85xYDkyLy3$zt>%V*%u*5G7>m05FVW>K$zc7a$|_EQ z15$F5CBf9rJ(Xh_^omj^7{lYAn0cy2Lj3mj^op}}n6*lk^*{RotD`!y8k%IQKB~hM zbY){6Kf|gS4G7DhOZ9tcg<+(SR%7g0%=D;6mG@spWs>wFI45Bi5zP3?ikuHeZ&Qg+ z)a8BNr181)_4yY84|7UR)MFqS-B$PIBff4_Wpj4^g2RP+aSnUaq!*|e(T;uPsmiF= zjX}4<71Y_ZSEa&RE3hHrK_X`P>=|kg2K#G7h#|hj-WB5B7Alc6HBu56)I37E!q)+@!hwRt7`w6+D0&SC-iuu+K$XJ z!Oh&nj2L|DyRdbU-|*_Q8aqOxJ^T7Z18SQ!Sq-PR=wqPE-ro3$Y33OiZ^=YbFbR`K z)I#0uDswe1Rm2>YFdhVRH^PJ4dHxHv^|88qKv0RSc*{tpQ$|z4!qx@n5oX1_jM7#GeeJeo2@O62^~U z^n0J+o|m;zZV%Pv6Au~6f_rK*_T8hXnvnNsbL`3{8McCU>B_GE)Sk6Td5>H6+N?0* zJ-+8_vX3W~F&zrV;ICHZ>8h_mltJMKT>RRVReSRbJ8jh2qdSyX-+dqO)wDZncJl+aKG9&WF1yAgzcNOD z-4G=4F|hmo6_v{$GY$!oKdng8v{-`q5;dD+PIsce-BFio?wmtk{rZ#+{qcgb^!0!re&x=}Ek~J+CvG zDUvjoB}@vz=v<_@?}qC1q%w8+^WR6Pnh7QJFcTx%E9VnxKdG~oNq;cwk_MYRrvv-C z<0p*Ypu_g~@ELKhyR$uJ6fnKJj)KL4a2VNyVnOL=xcY@N)ftk{rcGM3>jZP=u^A`0 zXwmO)s>?M-uQ!W+QA?|(>Cs8^KjY^@4c14w9eaFAH+Jz=GHm1aCoKP|!`jRy!=G2^ zu&FQenA~%tFazhX^KSr_e|(SL6VH$_qLK%yhlI%^7{8X8+~KZ0XhyCsU)4v2XI^z? zK32CW%p7(3oHMid4*Ean@q@|Cl_Ot}eOrUw zG_E}xXRgWaHc@6h#(lw1%^s{lx34fh+k;*IPd2k^!C*{ZM|{;^&tS)(_i%4NjX6T9 zDHIq+!c-B=_@?9B!|?v};VbI$n_D`{thT+O2YSw+&Gegy71ND9n%dvU!7 z8`5(wsml)(d720AxkY!LxPWdr)`X$syRqj-DzV!JXt5`Ql-Z2mU$FRL57xiKcXXc7 zhy79@W8Q>M#PY}IaAsKunw!4hnBg{N?$|^Tvp_o28VDwFjxV=qtr5N9g1WrA{VMZI zJ1^0pHubKpDOv&x=NT9f*G6P$rbk4yn`<`sw`X9K-_hsj`RWPY87Fh2Piops=d=h zX|70%_J?3R?;Yk;!$#4U{0XLZ7`10sJ{@st7JX=XGv1|jV;>lGV8hyLvmv#leQQAz zT%vliNxg>B zJ97%A=7u4ndmMtVDY1*pf|(u0(nXLWVYCV6_gqJAX?s)pio3d8ZxU%Wksm-0Na;uW zCpD8clHJ&^LI?Jm6Pe=Is?2^Pt)|8d)MNLpZbkBKG6-#dIio#(3S1_IqhS~s^xRXK z{q)?6sVtVZXS9UrLokhh4!wzBKqhv|LI26W7mW_;V6 z$_B9qcNa2^!ILp}I;(uP7>mZ9&^?P4=pnGW&c)cQ$>R3ftpGGnU@bW0n5-jk42*?14^C8Kau1820TP zlI0P2`KTTHQRO5vyGoMgO>glEOF}%qy!}pyH&-J{X|F`lNJcv-hj8 zW{X>3H?9}kI<*aZKN+$G(;hP?y3EA-qC+*=SKC$Cq4g5R;zSD$Ztlfe)V0B_mjUZA zGmjZ}ej@DR&Y>$Agm(Ld3Ojg62;;v_x^K#)YNBNXv;X-P?&roCbd5bx=#_f($$|+q zd)y+&)!{3&(lptxSt@Ltwho)?r@~rix8QhiFE(l39|R3CV3*hDF=u0dm*D}BkBG#) z6`k0L>w_58A(B6Bq$G_E!FTN3Yv82P;zsJTN-zGRIA*G33j`DF!yj6`VCfL<2fIu*z|v*Q4%JA zU>>X(!!?hxqJx~(<)2r)r-t{P!&!#EmD#TUE@CFV?8t6-ro+|_>BvU({3c?)4j|1> zE&H=xz5z^G!7$j@`C-?k5NMIfvlsh@FfU7_?1wqhqD2sl^~Jv2_03ka!EtqYl$tsj zWtf$tzoS7G8u}d%rfRVd{&r*^chzOzkbYuGv%cZ@dVRKSQaje@hd$eXO%(Is%5b^ml{ zB?E)?R7K2(WgW@m{TtHPNf>>uH@nI@m{}1&8t!#IIAaouDQz8Cf2APC*ikxc=1Z6i zf?>|8aIZ|Q=)*q5fZCNp)pN~Uf7vxz(x3mqjQQV~_6yswr5ngMni0-ixj7uk-F>k> zKOFg;R9LN+Am-{TNtzT1BO{m7-;-|uPW+25X<+ImA)GvS9Q4Lw`J z>|OF7X%rZ_X>WFSWf1eld?;S-@WqC$VW?|QFuOvS)BY0XvbLycg#`1_w>{@J*owXr zpf2yNWGK^{)}7-GPK%hK8@1S4%l}AImnkip0+Siri#>TEjPW-d0bMsAjB9rmYG417 zUTYhf*TbcNWQ>HlLojVg%G?B9D|)~=vOTr-nEP$_;sSif%ks$cN%3t${zn?cw^3je zDxkpJ$mqc?*}j$O{!<@wKDlGR(^*t)ZO6uXZeuk2N|;>|riNgQpZ&=(YMo7=4OW+D z#vCxyPY&dwtn~grF$xt>U>2(NWM`>wWx96g1INei$Q+>?*C1ihD-lhw8kb~c8}vCW{-bQZ1!=*rgT57 zpYj(;r03^OT`92gLBf0_n75wIIfl`*X?KEISTfuEeV&<&^@}l6U=;i2|6Vl3DWH&s z+VKBS_2&USyixx@UP+tMqLN6<8<9O(o0)To79ol(*%GpZ2uZf2ERhyUB9f%CS5nQ) zt5->zin10JA<7+Hcxl`RQe_k+L->uEW>8A1I^{O0!COm1x)=jX%!HD z8)4}bKF^NAzmR!kKNmCR0JF<)GBjRU1h2v$f$KCG_XW*Pgf-1Y!YKVwP-yKwCz;M-jNIi3iPMk8Id8<1bUhZ;)c$Xr$l@!O{(G3tWrjk_N z5HW*x{LNdv+KKkY?y*X-7mElF=Z0Q3^65%TI}^^d)fex>V1Co;eSt2 z;Kz+vNeP>@aQ76B9Fa8VLb7#6whhZ$y(&{MrH9vAY5^U zqxw?(UV~O)#d5@!rqRwymbJqEK>&kK5@`J zSv|k1-zX8YTf#UYX5fEo*{RGVS_Lm2-_+t|lf%w(dAsvDs~;c4v|Vn60uhoaNn!s$ z$l1Jnr$^%Lzk-ryGbj}rFlNcBOy`L)5P!uKlBS=8l>v`sqjJWJ7)HXlA!gy2Gpx~; z$#e^D(h2qN`QcYQ`N;9RDYtvAu%(|G$#D1!y1D2KKlV4o=Cr^UMwiscKY@?oXZV!q zAe%GVi^;t_4@Pe~z;v~p3wBTX=9~O`FX^Nu%tFLuyp3X=itOmFJGJD=r;WJ{Z_V;N zgS@EdotO#i>`L+ubb@w)I{CQmhnR%iMA=^)6NVieZr(2 z-3$6{m9olrBgAMPNi)qGG4)@UvE3d6-P2!7e*a@v+UMgt-Yf7m6`%hS#4f*>wmbh? zm9!rGhR@zjux-2+Ic@X?98}BTN$x?}A6}R4V`>FsRi828@795G`zKjQtBHuQl1`l) z5Hl>_n{^#c(;Qwr-pv~@J|tJpo5jd%^By%qZKNWpGsF94QdiQd@fq3rr8DA_VpejMnO8Nhae_kRxfs;x($7GHP%2a7|t6G@ZuGe<0%jCN8sn! z3D!N{!qj~VWc`?C(eqyLRWG-B407%f7_BU^9rL6=^QpiYE`D=_&qpKSNX#mk`^+sO z=BI=?f|%U0x$NQ25%lDhT5|0$M_!@lbAJ7UL`u)O8lo3>KvPi@j5&;r0^UA{u=0E2 zGm-Fq(+r>C*KTXu-u<(f0pa_>_}M6!JtPeF)~}SMBzlXO)zYOf4l(^@5o}MTVYD`4 zR!6+%y}NL{!q2)1f=j%e&KHRGuZO}5?c%$qgH8ohCu8$~nmh2g>@&O!ET`oWmzXxq z2ryGz2a&qRVd{VZyv2k=BBoHf6ec0&mg7~ne}om?&09-8$Vi26jE?40{f^tZO(}+^ zhTDpC9wY9FNiiN1_Kpk!gvNSoc0&y!nKQVad0%eG)sg4c^76| zy;Ri4OE>9Dh|M9nl73&2In?dkZuWP`55$Eq>5g9(@ zJ9UV!xYU1IBrmd&G1u<{Mw?_Xd2|}|4#|XHI(wOON2H^=r zsF=l3aSz-05epkxp)y4%=V`rD3A+}*g4nNRqT#tvmQaJOT1@hF$)^Q+a5s+NWuz7! zw8)|5MIQV}`O2)Tke-RINzup=<1~b2Uq0$fXCvmh;t8rD=NE5wG}|_vyD3_>rsEr@ zMqmT%(zy-A6}eEzy@N1?Y$(dnC++GsFmT>XnE2ow1hrOyrR8lbGqr#|o1Tfk%?N1< zlq1IKOD3yz+=#xt9Iv?R?z8KLSjrM>4Q$&qvY@T`u~=u*Sz3!acJ#Xq%m%xmZy+!2 zI{fbFMc}v#7(QAHIo^Mv=;l)}^(cgBD;sFV-gv^1W2-a;9w5f%MGpI6nJyh7L}Q=I zeLG<%%Q8F1TD`u8CDsq{%~L3deF%#yu)ODOCdBK%gwySpVcldy;yr5xjC0ro-HKI- zhU-gkufsBu8}m@9k8f=FZ@2W_G$6*_ypSExOM^a-Gc6L}RtkhR+^n{sSFGb8e zX|Z{WnD3^QtVe$(dK6-=bpOs%?nFic@8<~?;TqlVfl!|oef%zTp3i|M)DW~SsfYD+ z8bn;xCezXaAj5Js+$qo^?#{1a#KKhA*=;op`u$qO*h-i-#LQTApFQIAjnc=@bHp6h z)~j@yOegRSD>%anew~3h<20%&!J_G=i1Cg^_fcJ}wv%g;AGT|uy?6<{7^g$_H$DK} z{V_0m@Epi|D$TS-(hB_>F+B&>uv7hBQNF9R5Du1!L z}*8+{eVG%>N5c$qq0Jy0y5nZhol1pKdy8RY#vt&vE@3vFRUp64l)~-$sW4*T z4ERthr60aYo3t@v0^t;Uz~Uz5gQ=n3Ka=RY{v%|0r5Rj?Zzi}+sD{=nJX*D3CB*qW zu~C445vIV_*(^*L-xH?NnatX6KcIaz8V7Ia2}ew@PNC$O7|l3o(E1_9%p{!s<&#Ez zz?_ZVj$Zf#F;HfaS;ToH+u%%oZ?CgkZW=-2EAj?+|_Zk?r!Te*XXnJP`_ zafnH-+Ry5&3a8lZTJne9i|A8qf7zVa0?xuB7rZJTVB?c~SaY`u(k=5LdmaxC3QwUe z<|2g7m=7w&T^aMgX0l%wW$<-cAh^C$Vm2i{VX~B`ikLgnDqx40dz(VomGYgGUNBC9 zarN|>laplGdzv`6KKNTKd-+BC#`bKcFq>$e;$?zQBnttPWe%2i|&+P3jRC8SV6 z{Qoe*(%BIrVT5Q(jRr#Z&Mx$-vXioY4>KUbX$|PUuK@ow-YhrrHx zVuOb}Q3P)UQyx~(l}{e?{~25IdA%i!P^Ie9Sp{C4gc)|K4*b`qLy+fiI9B9NhZx1n zj6yTu_%&Y`Ecc;uqs}p-y&Xl2n}qR1Oxp!Zc1_!G>R^nP9DYa8e;rk2Q&w60Z#05; zx1oZBdGwKoj07^zbtezMiaIL&cA(2v#WWg(`lB7nJr<~AZB65 zf2{iXzLfB=^5eh36Dl6)%f|Kiz&W?(qFvrYaTSpHR)AGuK7>VbSlaUhYJyTgaor^7 zanqlE)i6Nj$K^v#+&0i+Khcg{CF6TeI;RbmHtEfXx#DQeewnCC4NlUMo2L!o!nG{< zzIXfbt(H0Bgf6_93)U%E6m~==*4#Smc_ccKXEn@+m?yRLKgV9ObvZIvvSuGNo>|L` z+gZ=(=1ATTXC%xn#Oz-MY=)x>Ws{;M&-dxeC!3UWx4h4AUUzRmhHVYF*`Q(L?ox1z z=OA!>4xDa!0MW5$;Zgk#7_?|9(^2`6OX*z#T^FD!-LoL3chNP5eJLGo!==}#1BiL@ zV->6HsZ8}r$5mk4T;B3%Fs0sDFD^F51Zz2yvVfV7hbdfagmxiw+H0Vu<}^&R4uMxg zr!!O5C{u&}-hxA!M`79E3?{L-SC?2a4-LBIY6@kVStcAvs9k1{AMDOnH<>;&Gdw@|+^`kAHmqS_YF<2J$ ziJ9CdlbNV~P{h2HqB(__87lrPeMEygikJ<|dCK8~F8yRtldV_&Wzo3V&O&m#PG@g` z|G%rEovxqT2{=;{1GdH3bSgHMev6G!wA_QxuQLQ z@qJbS_DN~*=d}f-kcW(avUKXyk)FP9zWEc+jW%-dPe$3B@!Td<2M_oD&V$43atJhtg4cIT@#ubq*>d3~ zHBs1@WYB0S1H0alVAib)#;&`}oUblq%#P^)s}|)<#bF*g!=~2u*vkvFd6!_i6YcXY?2E9YLNdg2EI3TP1kM`gM2tmf z1l;7SVWH+eW+sbOzjFh#l$ElBw$c=6Ld^BZNOsgB4{FA4EqPp* zaLROJ5`D66FP+!*3|=~lM7L`JGwjVp{H>Dy7jy9RBlPR?W=mMboE6Osni1l((~By!Rr= z@Oe@&2R5D+0ZXFuL3Z{Cb*QT+^Yg(e*o9}bf)YD0)WjUax>)hIIV=^9bs#1@{vi97 z^`o@bYROA1hjOjCZuHJ)0kq!*^b$fF>NSVXiBmwp2u|c4ITGgcy?pT5?a7|L5x^{{ zi2=h5KP;TX0RJ|8Qvpt+u*4{}Eoa;_|Op-9p zmS{@<7QKiOv(F(BI=@O7#WES(899$vQFdfvat_1xIA6G#O2g}}6?{IvfCw`!L&9hv z=KhqUtX}gTit*5rA0K>!OH<3CG_7XQdMT$s>FO=W>qvrTV_w8~UpoW4T<(a2rlx__ z-+^a&L)Se_!0*GTj9dk}HshiHqVK$FmnadVAyq=^Bj%<1X;!%)lxla=k`D~<}f}Xu+%T!aPnRZC3?zTqEF2#H{=3NwZ)J{vT*5J&SwXCM6g$7V=9J<6e z7ee782_r}sA7MqE;N9I6egtmyt_4@KspAuuXE8gHBjD9EZ}?|72eg}rY^0JD%?YU_ zo_JmH(0`C$kA0f;*^A$cLZCx)RDRDp(eWV6wAT{G12J_6Z?amp=c)3E_)N6f zjq*I;PH*_Wo6~4N4jyuBe}tGCEZ%qfiyqNv{L>bE2LhYJ(e3&flx<0|b$Oc1^j{wZ z{DnZ!p1T-mH&dBvm{gp!TJnKfj+pFuH`v?rE>LZg@If-Np3}_eq`cMzaDsZ(d7*@9 zn$L+MSpg$_o=G3VVJtRux<#ANYq1n=t;bOqcVjzDJvbNKONPow@hLGH9Z7<<9x)r! zS@ys8snlnj&|b@qafYK=s==n2vnW3fULz%p(8OUvycCVFdkPrqKM%k;_!!-xFWJ}ZvR3*nQ+-$p4vA0s*|?w$k2{2xY`0wV_0U~{bmx@Xk|=4MtL zEFTmF&qoD;-P9@cx?1VTu|QI<9!AXSpbR#6WI8n+*EHtRKT00vKR$KnUCv^D9A;`! z3svxc7@@m@+rDyW!tbX1VLkYp+b~Nn-(hC-NP``pkAe>Rc}^pz=(L_vy@08Ni4_KI zZwh-}o<=pfYss_Kds6bgE-c$OffGJY0b{Ww>3^dUK2HJD!5x9PwGW{5+XUvUM-CId zDGk!Lorf!(Xk}nHiy1pn@)y`AVGe( z*-6%cPocie$8F6$kR^8-+2wcVa!q~ECk3ZK^sHnNBdETIWuF!?E@%c2=8QSeTL+ls ze@dChUpVk^&Vhj{hhU_0xUCr;xkxYV@59eL^`EWK zE@VxcTs%Mt=d@kLsp9S_^dk_OpE&;a9OiAj%P1aKfQ_craH#MG`rht=1JVs`X>ogJ`NhS z=?|UMIg?i&uS5ywG+|p44!7PJcvHi(fFQ>%46Fc;SAJHLBun-SK1944AjA5US=rM~{TJ}Xmm;YNea?f%nG)=Vc^QU{EtE9uW@(~^eT~@(D7)PP z30r!@Ia5RUd;bd@+g1Z#%_CqvKN;jhs>EmlBuq16xReEKM@%%ed^SEs7;T{ns#W;N zO>tBcYS#lT%f+Ta84*QLxHLm-f%LJU8mwNOgxijF;PwC4q3k)>?>qz5Cw&lgU&Q>B zzMId8aZ#AbzL*(FHO$0Z=ha*Euu(1CVvk}<&`D?P#9R$_Bni7&0$veW(6JKJtmc@_ z#k=S8!F3S*{tr`KAH!Vg*$U4m-9t;AQ-ESODEMA2V!S0xCt?ByDC7#pd0d zyXdP?L#?*_M925WwmQ%5f)`%gy&6$h=#V2e+Y&VF!cDr1|0Q@n{1$U2@G>{r?*Q#eQqeikOXZc+9wDoMCLzv6r!B9bCkdkK$nLBatQ(G5XR* z&>b;NZ;nqmNXJqK5z}-&QAYWPP$Sgz`1G~e5Z3Pzw;K98-5tAY9o<@jKFfSU{kQqtY;YP4%p1Z7& zI>5aR?aNus&IJ$STJTeq!>$Z$6m+dnOs4qfG(y;ac*~9|hMP*tF!W;zqoYv=H_X#f zSLguq$_-)Fz623tBt>I^81oJ@wrE%wwZ~CQzNGsqS<8_WUSS%SE4+9J-Q$#^3&GC+ z5oBu=qc#`St5=#}SkN`JndIS0bO-Zq|0QO6;9c;mPXw=}!{HD2i`kvETg2R!FhdYC z?{PBQ<@`Zv6b{-%^=R4tSs!@it_D=nxO}nkrqHcaXd~*ks0{jcy9HN9zJ_#%OqiIG z3a9+i8N&mS%&d<4P`V=;%)jVE!hAKjsCHPy+>O54CI>zDB*C#RcuG zl?%`}1-v$6p8QP^&36-G0u-J5wd8C&q4r>NH1MNoJ3B?#{~O1brr zx2;Ni^lJ9N7UPR=LX_PJ75M~DK3}1~mkOMTo*a&^#lE=S+Z(}xx(8SCOM!XU3T{Q%es}I+ zQ0d)`@%nv{n%t5G^=c;$#TESRyY(vsA*&MobQGmUqW?J!Ov3xURBdJ`7mN zpBkmaZD=%<2Uplyt@2C#`9V5d#C&a<#^;p&no~b8_-IZ~tZ7kmWNdji;qx-0dw&<13+~ zYZJ7hXsmU2Ia;)T09j5R*mj(Re#2~-<#2*UHvii4IUMdOE$EXvJbPyB%kt zY=bYDJ?RCHO(bg;8ws-mF~NEJ*fGgVsVc-+cm9@n>F%LCb*9=17(w;j`MnZ?@4iGY zsD~iD;%3`^21ERGk9>U$w<1(wp^FAY=|6|dUZ>#C^)(RW+5@(`Nr&5o(iGT-m~R~y z*mcX6Q8tKaY>DH3RM=7TM!Xj>c_ppTgw4=}cTYiC>|$3T%CRlBb1?YBBbc>A19Ges z;pCP_5TITL>r>JIidVzA+tRl7T*5>mCNn36_4QdvWgsRc>J{yDJI{)P9_4E1xyf-%A~-Ax5s0Uw2G1guMrk1NcaM>opj+N*E2)5(on3h6mrE zb*43}9AOKQ^S{9jgXi$`%v~7c8U|4NrmVTRL#Q2Z!WlKxeQ)c#Ba>u|Nro7=G z9hqNBt?@xEt{b-6MR}?9=VtIS#P(p9E5OdD}{xKF=$Narba!zfIjt?ZMlcwTqnI9HvD7P|u~JN8J(S*zwz|A=u?D z#Ou_-l}TvK@Z}pcG5IjGMvZj0nF}YsdqbS-FPLld4(7zw!w9ku97cQ*qxmPTX*r1L zsk#t*tn8+;XngUg(BbKId+DH|cc{EycR&M+T-tUBO8gdROMD8=bQM@PcL0M;Y(G~U z5XB{au-h&ereFp53ZFV~sJRdDV+;5-wuqQP(h6OOn9~*E?Eb6}s&c%R{Eb2;U%tbh zz7alzRvK6dUMXL&=h_44Yd+j1dQQAE#5Hn~*I(u~aVajF{Rt?R_|=KeJ^4fCCqcgXup=T_Z<_c=>zaMcruc`Tk?)x ztmi;`rPhG;;UA#U_bIID`3*ESV>8sChp@n3fjk<22P_`0<%A#g0}X;8r2wxknVBDO%&nmR~0*@Xl) zSHr|<#>A$#JA5(O34eCK2elqG5WltsPHaFg;;qtAeYlk9`iq!rhr-yMNja37mX^G1 zrUD%gFX-##^XTCBb!fS!Kmz5jpy}No(0lnF{Mw(vPphtE%=m}!3k%D?zaI-X(6~`8 zx)w@ay@Af`e=r)|eX+@x_}h3(X*)GVMTM;Wo7wM?1(Zw~FYL1i((`Hx=%cr+Y3HVT zP$Wvk&i<_^U>0hi?A|rPm(MC>*!L$;l-P$X)td!)MFE{(Z{gjG8VGy)4c^RI2yeqB z8-sW$*Qtk?-OpFD)*ni#FMl-UhR(&@9`-%$TiBm&yZ0OxwR9oY)$d?ukP=B*^i{0r za?g}%pq#GsB)UcbVNboF|Fe3K>7Xf4|DTZJ<_*OP&%|ifN|-)~`FhHaH7vPD?fkAO zkG*i3zt>zq&pV+{XZ-gHTw}44>%UKMW4BCj6xSOwZV7s>06Olj>ax> ztE6b|NSG0bITsbm{&js$*}T(~zsh2$(KhF4O|=p9gte`Za37V$SO#}vgc=zW`v>fd zP&18^U*l_UVZ(D1QimV^!?+F5db=K$lLFYL_Z6O5jfXD1%Ef33rL6h{#0(!C&Z@v$ zs{OU5eEd>1+lELP{a|$$S}0Kr57HnRb2`CXQ-f?;pdeO4rv20=opJ9WDA17Psae9* zA`kFBSq_ifav+E}`Od{LN-> zw(aXdIvu`&dxaKR*zY%Ed1f%Y8lMTHj$DCSxA*XMVo&%HDb;cumfmmXA!e+TAFJ2@ zH#Oynro64AlFImcj4lc~ObHdl)qAzcjf+ZT?|J+mMN8H_e!w3`1G47ZcL=?#O-BBH z!|d!o24-tt18#j1l;3QI(L)tr6WSpPhuhT>#tSjG7B6Bu%oXXm4>jeUZ*=KVSy$+9 z#EWwK&?%N(r_EC)+kA9MLahp^y4wjK-W!rDbAQ2uOjW|i-C$}UJN6I0``g!O$}Q(+QG3SiqDyypQWJ9iz@B71(p5=C6qL2E zRzunRA5lHD+xwxeFRtN3W{wRVl<5s#vd{LcQLH- zS`~WhJx%%A4VS1f^4)auFk|Y(SOv07MW0N>zxsA6>Tm9-6J2cuA_!xK_Esd(q#Idq zx{|qS&h>7_6TF`pjUuq7AN=)-q4<%O>ssAqPA z(J&*#c2JBWnY7A)#8{~llktY6zg0K#no%U-X}!swXeF}AOr7Y=I>D^a(}SzKHw034{R6BVJ5vhC=S|g33D1T#gV?OeRX%b3r>Oa z`sv)gJTtmta4W0+Nttx}U_}1B(j?}CjLDvi?xer7GWof~l!OMWkabrS$XWF_bVO?f zlYeywB-D7pd!GvU`uIN0Pmmt+3#CCzMGV_#Bm3ou4()UwzZ>Tk>gl=9RI1B)w(@>g zawn%3x!t5izCv$ee_WeP|EWwyN173Shbr-G{f@pvjr73cA|}*vBfOa83dKJw!8pH( zE}6MkjK*HVWFY44Sx?q7L6=_e09OI!5PHJ#LTXLNP;SL;74kjEn0$!pPNGcukT(l; z$ZG$tBq+%H~E}j92v+hD<#wprgONwTtgy9hLWFF0q z%GaaS9%;(moM+KNc|7GZY(5uipi0y$jLF%-7{$FlB&uD9Y(s|;lWrD7F-?u!NcaZJ z{@T!fl{cBIU);fdzYEN&xCaN~t!dXuk}BecgegYMc+#7#G18|8Jl2%ItRF>N4y&ik z6tCpPc&d`?qk5D6hqcK%ZxfO>UzdbpS?|~b79>qaos7Qu2|^e3;&v=ynY+ra;Ph%H zyf|_n?u7KB*FBP^fVQ-B-b2jJG$mGRssa5IF=M(YQoh$F&`pnBxUHG7^R5 zJFlCN++@^BYpRgx?=8p;J9YAYL_74)c~2d(zse|%oC~KFXM#rAV_5m<57l*slz!+U zZ3K0Qc|NQ&Z+e9x9Z{<(fB)Bjt2m=ZZ@6B`j*L|$Be(Y^qaSON@ZTnc=Ov7Z>3?M28Ast8jhYdVzO|YQP4(cnDk-iq>%OW-6ov2S7quXio zB|6}pJP!)7L3;7VpU~Uk6E|+Hluxslej7u?B;-wH56-uw_hK~hgO&J%r$ux~f(E69 zin^F=V^Z(XovfU0Le@Fxkafqq5c7T(q+U;r7`*REyoVbxk?RM+jJlQZZNyU8q4^t@ zyd~WFg;I&)DG6hSm;=5$*>2s3(g$#+={60ePVW3kw}BD2biXor(Z`rn{?a0@Eq%xo zl+D|}RU*2z=H%gXRWeN3gqYRZFxCAm;M}|ga6HQoTn{M`3u+r(?|w>L)4oU;E5r=A zxsctMZB1XpLF+T{673sc$}HR*NC_Lk?K8bdL75h@zuAYx7;2OLZc0S)h`G3QD$VOn zz7Olk>@PNec-j@-WQ2e!?x_AwCusTS3nJ#Ggt0-)_le!vwybgV0$c^Yw<^&F*1Z{0 z_Lwza(1n~=??udyX_2$5`j9O_-N~OMMY0IY$z_x?j@Z?ks6~IE8(no_*$a1=)_Mqr zD`}Hwq>cXGQ+mP+kuVHm^xmDxYwW?$D-g5GGnc+=r^0N|bz+6xv;BY(>4l=0{^oti ztX3^DMO~3h{bokazfmDio|+QV-J=-eK8E1=cRGAP=h3BZy2R1`GkvRCdh}A3Fiwb3 zbeo^&xpoqL6c13hdfcLBZvRF@_EaLZ-HgZyV=c0$20znvT4d;91yY}EMh=}+ zA-|rRks}{xGWY+OKrFie?tjCV-3>j6)j(6mA?~6$XosW;?S>eOap&?%4>{2{5YwP` zp3iu5hko)Z#!`+F0E$C~8e5Ct-5u^HL3T7~RB*N<4QUdVJ>jD!iv z>tK=HK6vV+N9t-?=_h?9%p?i35HZXV`_f8Qo0A+Jan zZ^W$T2pe|Ul@7w)bLWCn{JfE`=+cdMY`gwLOF}%^>`c%ku3wDFqJElqrTPa3ou*cIT65=a>O;H&*)jzWP(hkxQob>5e`q|Ig!)35{ZY6-Q=e1>f1z8jDo;3d7D^ZP z5X9W>Ig(8ryO`cviM!{|nY2e>E`6_HEmc25ffQVoFyq6GiHUAElK%Y<{E3k;BPUoA zFWqp4U5={n6RW{&$WaIxWk|kwsWDsUNviLwQZz>p6V=?CUE14=E-llPhYv}j_+6K2 z>t#jMLlXt@a4QU&fYB<}An~{VfN)L|2F<@{5V>1%h^ev|55DKu!#VTgaMHd9DX7q6 z4&9P4ozm_ZhnUirz1XDi6?AqnexAXZ+>~XCk+^bJ?r)Uuq9b@9&Lxac`{2!*QcYm^ny};O-jsdf6*jM6V1PWxdNYntD3EnDQ z3Vo&DrU5aP-8@-(s1L22gXxDew%oJsrQE$Kt+use6o~GAeR01LFhVrKVpESkHU@Z% zck%j<7@gplA(b|erLzxQ!VW+;Jyp`>?l{I`^a=5|*(zb)A|~~R4?AJy8oJ`9rablW zEpA788h6i(wiQ-^ZEN(2$#yN$>w7N|^Vj$vJZ$bO?w)t8%*mqQcxKB(6ZrXHAH11; z06x;n*CPGy@K*dU!HpHwywTFG!{Li+>3rT!_P2h%7(zzBm2PYtQYoe{{W@&)!cHQU@@BiDee7@nCbn(+2!9? z($fbQk3j(0dh=SUf8qgl{mY+*W1^(Bi^n(s! zsyZXtrA^D|#fVV|t+VZ{bmz_DHnIXnNIwWCn?;j*{crl=`dI0=`RJ!Y4kv7+=cGn4 znmO}fq^l!P+7H0bhgRM{~=n!tbW7;|R6ND4#d8(GW2c@uVW01xBqfB9>DnjF5g1HiEZ9e}IeM zmAoRA80Kc#EO<@qVfYg{RHwIc7xL$em}AoCISesYTMx3#+4*$0JWaXNP=>Ph`OL4H z_L>!DTK}(lq`HqL>6(RE+Ba%M>A*kW!}^edgsy0rqe%4P%xSHJYs|u#>#^}uS7`2i z27dcS$(BCqCt@-r%s9kk&EC%%9CfGH;9_I-K9hxSnf&LUOIciOVB>r}l3?47)GPNS zpJu9&^62#?pTnSOw@pH9kbn_^K}}R~ap0#!47F!~|U1 z&)(bbO20--`)5r~!}1d!nSPG-sQ)WkOw`WNAU#wKN!eLdvTx}hD7c6VPhl5Q{PHb) zveS@x?Qmtd1SdHCRtLf`ujZ#SS{B&bM#MalFw+pTx5r^t_0V+M8&~MfzwdDrJmEvC zwYfU`KcICSZF4XK_3*1ciIJ-imGWPrJ5S3NB~r4X77iUxpg#0*W%mBF1FH`M!RHGW zFxgjfH)^Gs<}Yp1a}cu=SApT~Q)oxTX#5PL;@JDVf}%4Uxc8T61vbB@8i^|DK`INo zk|fnmn7GzR%%?TgwZhWt$}$_(gG_ceFId0v6>}^5AlS6-k*&e!Z(&>8Af2H-5pyna zBm4d1Wcndu#@y^-d&=Z8ze7)-vsnI9w9pgW5(JMf!9Q)li|;W1iy=8e{=qABM(|&( z$YkoypeHsA0lx?XsKG;2$M7DqqlVI;DN2|%h*|K}kNq@kBHb#}l*@x}*rupI;TQhB zzzViGz1lQIgQodtottKZ4=U)Ept#h4)O`2_{{=pU_5P8v$BK)Xm)EDltcG7qzHcZ* zTnv?^Y4jJP87ZC9HX~-apFcaDrs;9GNh{q5qPl1B{BN_JoM4`HV|X{Rad8*&6Z1Ci zyrO7qrhc*qDgW~we2a=;;>&+jhi5shjBmts6Z-<#AA^gtUU3!UTtv(y>6vI3VhTQa zu^ZLK(|z&Caq(*$b=|j_*Eu$hEzJ51waw~yy;T&2|I2g~h)TjI==D*TeANF2CPoeL z{^e2`mAsg-ZSaNA$CePTgBC64qxh8kX(A>^!W=+M&+t{O_dXk1y--vB(S8Jfre6eq z<=Ylc!|Q`6{BOnI;n(bLC0~?Sxl74ziQ~vqdMb>mw3GcbpoYPBg0rSgvBscvf z+Jbgo#Qd4;Eu4L;MG8;9gJyi=e0Sytz23Np$vnIt5541It9Ka0KitEI|8o>E2@>WM zV!Y38W2c!9rxo$knPGXD8kA+un?>2P6F$5~0~uw~hOT_Cdr89o=<%47k#!S=|9fIz zfKpQr`h03I)2|>9?r&NO>t~={+r1dN{_RE)GeUY^O+ifY&#kOq)DXI$L{t8|=1gw0 zehzP=Zq0cpH-Ro*!0WEI!JiIgqU8G-qNluoUUBNgxvUBFa=ySW+Y!uiCX-o^8Vz=J zK9J~r8a8$qGTwz!67sZ!xrP`kn;>?wtrcx|2eX4~a48l`ut!32tA`x|sE&T`>=Rq+Xxf z7wpeRa>1Ol4VJsj`~ii1n;~q$Z}@Bb63Pu9!CsRt#7gxcn5un;<3o5RbXX(v<75iN zY&r!S$EQQ>sWRs9+$0ebAYrNy6Z>KXyZW{nt%jGvX-?)`wj;+Ev>xM}C)Yry7gji6 zlK_u%-=S$pBm9l3fh}JZ2=gADu=^^K$$y_SheOoi%^vK?RCy3yIh{b)_!wpn$`^z+ zO-*`}eu5aycpvtWvI*S_Gq>3X=pPkEcUj$Ckl71q_DEFOOcx6H3lrSTN{j>Aqq z(SKk7RucIh`~aCGi%D4coY_@y1+ofHfnUrS$i33Q>{gPZF_5BZLX5rx`VJm8qSrje zoQ>yDK5xIOEU~`{CsaRJaA@1^UI!DFd=g7W1jF<4q@Q5uUkXnC?a;^j6|=HmH+W-> zRVk?dIJh|uMy>hGEXX(~M&mA(CA>#W$j=})WlaxyH)f#JXZPW!ytu<>-wEM5-;{`L z4>Zm^!X}UJpkvv6IBi}AA9LG5Z(k9FE^7ys>%W@ z+gh;{O$TB&+J&<88!h?~zO8Lto5P=5qb4)^GK3R6@1rwbgO&Y#tQvj;dK&jYu-5PR z^+hbQ7_;LK+zQZxpBFUY(xGQCTJ-{|ijPA0xnIoreo{G4h!l;2vZ8`n*F&swwHp0j zJzm(kEY2=RMHaNffn75UMf`iQZHvi0u{g=Ar2^)3Edr~pAHf657T1kyfwBNK$X=`o z-&&u5>z-`TTpIzEW~R_D{kk}4izSQ(V)Dx)*yksd=w68FoAruMNY#~*r0Z-UYH&4v zHbP;SN{F8HTy#qinm7pULegjF!7Sy^a46CU8vFJDgDbCK=8Q~;@HhhZwMW75HVKm} z4Vpe;{A-V~A=*Ev6^JoW8f)7w~RbDs~`QSr4si$|0|JJ?Nb*5la+>9xKg} zHz6|SEqwjm2lf~Afb<^kU>R0Q_E{PQ`+7NmpJA>T%~1){7csvxVp+3QtyJGM%<#2=CBI+sg>HV`q&=EvD*KF_GpIMW>NYH~CD`paey8bAfV%7gTl zS`>|8SCWxWz(TtS1TC(!?@JJxpX`{{0+DhX=p1Mcsc531fgNSq*6xRX0ZY*(R(g=U zAw^@2n1Jwjws>C^wHq_H5oyb~b$v}`uLu-)#swDQIeAE zk}%5=)8LW7o{Em6#^70C-i|kvzezD4SMitXp1}XZ2vfjfdj9`nf?n}3t-=(w zP#kmja~lNn9JH%3;MF`AG`voW(U?mc!Ft40ojt}n*hEt8curdzRYqNjF68}plv2j7 zxQFbj1&e{G#4~vS=}&Hf(Eld7tpO}tuEES@xo~reF2t9dV@8Cw!i1m<_-54?UR|02 z4|JkL%ti?lfSA1s5$v9{1JoWo++NEYPvvUo@QWv;Q&tWxhW?BVmFO)1GpGjnUsj z{leQ?<_@d8?q-?%VvD_$7bAlj@)SHQ@UukQuk#q`6*tjfO76Lxm-yMnnpBuz zVuEGYN$y3kEBPTbq4~cawrdf-8{zYuW*i1Ls4(W@#%Z>LN0vZ^W)z&y;~7t94e*ck z6r-`1zMELY%$pa=K7P8KQbY{CT~d85&hv?$*KCEdYl}0_U=0>5D|LGWN~=r6vg_tx z3G?#gK{)k1fXRwkHeowk1O>zumUd~Pr_4OSxVrZhF$<(sAQ3T_Z1%D1zs;jG5EGbl zl1s92=Tm#Pv*~N{!K(ThxP87QV&Y>Z%#{oYlb7lW1^&NS_b)cG*kuXuYX1_@i+)a* zK3mN|e^U`NPO9rnM~renFdNs+l{$nM_C)V1RBGfM?n~1iu4bbYjn#=l5hH8_LN^}) zBP=#Uo#w!_{+rnZO3s@Hodn1q3Qmu$ZI5@4rD|lVB4&n!$wG{u^&z&)Nqee_!(8Wp zQ@q{c1YRxlwb;827>v)o+7R7e;ZVmfB;Wl?cWoz2&jZ%f-wE%-EsAGrAgtF(g?+qwyUHes*s zOO^K~`RECSEnP-kf^+K^gXN4{ysAt?X8Qdod=1t?$+jJJRsT5W3i=|(O{#}3MU4J| zHSBBKG1O=LJYQX|wmmj~r|rTI-FU$;Lo@;E%V8V6YH`2WwU`s-3WAx5PV7YJ=O4=F z{@f&6SG*en9?<}k$1u<4EU|TTlJ1^`5~c<*OICQY{jS+ixwkdtah+Lw(+n4$^zz}7 zeq}?T99!;v$^q}icOg2Y0OFN%VE`8P1z$f8#_P7h>5BJ!?&Zn6!h$H+sBQ_71v8jA z*FJDn^CpVXtdQEhKSPX3{5tmcv=P+vQoP~@jO3P%8b>dm^o2{OGoh{vE}6I?3q~`7 z_k*DE2)q0k)<>L$&ufAq^#;qiR!8!u$3;R??Mx{5DrbV1r_m>#tPnBv5~dk3Sr2xw zZZL{kfh%<5oG!dV`i#7w%cCb0qJ4p2%1~o+9hw}=pi`Yi*}^p_Zb9#dlmyu8o&;`j zcexE=9IbW!EY$8N@b}vprl>ZQZw;F+VhW``?4J=c)Z{3;@rEsxi}#zF4cUDC*L+$z zYcLnRCLKIJphN+iJ9eV0@ROAclRYA8#*>@+5!WTOF zfG)f`ycI@I-wrRvT0r@1b^hn;C1Nx>5~e$191ogv^Tw{Fgr^8-a>`$|a|t6qT+gm4 zi2=WU1$e4C4H;3`s}OZ-Lbp<(_i8*F4)f5tYQWo%bn(kR5Sw@zltwy1c})ki@@$*T z#a~K4T$6qqBgAZF9J!=fd#S(pu#)VsoO90$qBq!1`<&Ajl7z}wrbN-8$dCs4t-bg2yzl${xh|Lge6D-#b=G`;?)za7Ae|3rdzwUA zDx5>VvEjRb6^Ch36(?^_p{Q)KDQudJzP{B$!z3%|g5Qxa)Zix3865%5UAf>Ue;oYo z3dMwzqxV7i)mk`nyIrz=)-BXBzz>3m*=dVL2y~U5rth^0_ctTP@|bZ1V-uUkC{8#< z%{{Nqnk|V(W0KYEChWgU8ByV+M)5T;vyX?$h%4ZxdkoSssl`4_3?E@P+_5E<%Hp<4 z^{TF+q057yDJBZq<2S+IhY=EaSK-E^N5Ei$dFdU@B+H+o_McK`*Q|MkRIX<*X)kBe zkvRvTwkwz9ti^zh`z5|QHdjyDR;3 z8zifS3->oi1&jm1EE}21_+_V2KF8Hr3pEF6<+?MH$e|3Sws=3-!xiWxy{hfxMZVT| zR&Y49y}Svpmu-d3S7dPJeO;-2^jGw2MFhl?_GvLC^>(dhI-ggI17r4q!Lo~Ze+Y*u@#A@n2f?h8lBy|?LUj?0d#tXcew?LP zZfQB?d@qPd%`TA&m?RB;a~8C*@!(+*2EJN1fI96DmWg%HHO@zB(wL1#1o%Q|*$ekH(*1 zEIc1E%%$U$dn(y@qzpz*Q@)8SM+Wg2uBtqTv3YYI(&gevmFxqc=9mX(>NmiMbyB!_ zJWZMvV2PFvT|(9YTS47@C`lvHmZC1zUT!XjamK$aDEsGrRUFq zuSzWF6d!(=q>xf`jQ{$J9MK%Q3}#o8hiO@ zCJT*rhG0@v9x!vNQt1^rnhfp#m^3vi`_bcpwdmiM7CstgMSP-u%RSNLcplB z+=Tu9#!~5GEtHwIA5MyQL)Y(*sNkZvWcLBvhm2c{(x?v z6(m2*M@S-X?IVVf^L#YEi!wn?Ifnn;Xp&05+_zcib{RG(bx6)_l|c@}_JjJ4P*`W$ zj(j>57@s)diDHC+xk)fP&ElDH+J~qvazLElBc>~R`AfnV#*33JgCY0MdA_Fwc4dIv zvuN-S4}R(n=5nyZvj(8Fj?1v zn522(lqJ~|Rx3Nu>(2C*SlziMt}P0NO$Qn-)|rud##MlcW0g)p&04p7EqWwYnVBuPfW zY)Sa|T5;{X{SY}qz!-I&;W0(^;o$K2G9S&V+B8xLOGEN$U_RwwTB}z6G;?LD-jNIq_5Zrx^kEV0w8KU-x zhL%eaWVIt;OfAm9n29~iaMRaxrcNTv)Qg7V+$1!=E|o65yOqZj3z!;$X&If)T$bNM z4I&R4j%x+^O zMb95Vs`-cyg8$11R2%h^{^~8P(@rBknnr>-R&k0M-M)?LCI`d^#+{);4pfW#oBS@Y zsSN?&W9J|^;UKi73mDhhNN}bE%=ha_Q11~%OLpC%*Q`DRFeDkqH)NrK)|<%~CrkvU zz+-+8OzpHJX0iV!N|Rt(bU)K~8s|&4XVloaZ9f3Wq2J%P5e52B|#-=ig898|^=Od#`?|Js}Uy-pGc910Nut z8HH%BzwmbOpKqh0BrC&Ck76=9S5o@q@IJUXLhRgODZ%L_Q~~+9aXl?JM!;02kWc(v zz&yRQ5l&pX2-%xzXfIPm)Ms)YoYc&KF9li1R_7Xe+AjQVx`Ym`LokifMCQ5WGKwNQ zf}kVS;_5Ax;^x!lRPCfNeiZ1misGZ;2AiJpC_Wm!SDV0fRR)}ibV2q$Gf>~7g#b^^ z!Pnk5&_?^G=<&cXzR{)$UBHB37VJLB=tV82LdeC++sW}_o%c&6t{YxcI%?rieJG1x za&V0nU>ggz52E>R!>tAOZoL3io#T<7n<}#DBL#JXG-!B`jvgeJp!qk1F|9!OHUkM} zc*AMt%oP`E3mI%Cxf)T@Vjb}buaA_2LImi9aekp_GM=4*0`E9}Iq2p`4(g9?ffVOV zFt5l(-QV=l?fOUXs-^%sC?#mJG6V-J;T(Ff5Y0$}S@x6*mfSOOD#1am3wu8OD4K0K4kz@Ka_9x@sMYVE!X$Af~tpnSW92 zTtygvN_g6PUclHA%(~;pn0xNCC?$qmNLs2>IbS5=6WeR4Qul+TKQR)#Cjb6D05difH?yLtv|M1=QZgLD6So7%@$RJ)aJPZ)`4}UDi)P>%rX^)M<&ve&7Jmt`drSq0|B~WcYSUxE!TK6hdL}@n z+C^wgO@;tcPRH}jb>dSGhO;pbA!OenG*7z{y)1eFQOj~j#aUh0tE3E1^p5b+*b5j> zf{6~xV$SWIO_gSls|bxQvF*G8bf}>`T{JTus`Iadr^iu1BvUBz0l92UN&+>SxFSD? z!1pQ^vTY}$p!=7QR-F{W9q&W4BQeFMkAXQUS9#1P0ke)^#>AarM!lL%Ws>Ef(uNXh ziwiQT=pEzfeF++L`mIDTdrr;* z0*^zo<~3-XmCnnvd?n=6a9kwp-tq{-pQR%=wMyi?@)r1*-+`DbvtVO*e^?VH>~FRT z(FAdgwjq_dq_>b78%rkX!%yksZlQMDQV`8)a|+_6WIvMz-U>G$+BSnXz;K(w;Du4( zwV(>dU5-XRN4}v)!|y_C-c_jFX$ub?D3DEL5+6;PfQclSOTSW?3+f)!lSncVq)RB| zy_{ZGT|seTv-G96z#;Aw*mUOe9w_uO9V$26;Z1!9e?NwR|6>`s195TWL_OLH+)VR$ z%qpSLju6cBx;W;M*GlSn2$`hgRp__V-&5l{2hl|VCrCZdyS&eaGmd3NlXbMh8Stfu zg={m?fxmwZkv~Tu^Nt7TM(r)wHYyMPgzSS+yRO17b>VmOT!`ib!6?ie&X_)5M%4t9 z!;~E>(BrBoS}rM$c9uQGTNL9bpW~g7oB>8@X(qfqMUEthifYXgvg*Xn$XLUbzBBwd zEL>R&veaof8x;fU6~%ls#{|qdg6Xwmi|v+It0~28;pmKgPY$ZoTc|!&vZOB69#d+{%?p+x6HX2-q1VWa#Fs5k; zm|TKUaU57MB6$<_$X}fePdY6Su!gyoV6zaS=587lYZ#t6)E!EZvDY zDbPL@-WorIK8fjc&bKy{YAuE}*`Z7D=tBuKej+8_$6n&KISvy}!b`UfNPcn`)j1A=Lq3(T zEh+`P`gy{l*6|>^B+NJc1WYl(4BC5=nYd{KCAU?bb(&ZwH6NELo-dyzj+~GM1?wvz zSDy%+PdtDkEpp;Dn7HLtBCUtVyxdJoqi(p?&bYD-d0;f9mA1Q%>{jWm$ z{HIXtlnGCclbivAhbVX$g03fzVL2&;)_q|=jQ@jRk*|=k5-Y5ss|m(=+au=0;{B8) zNS!_F^@^S{RS7x8gh)7_P2;r}V08aFybU2no+2V=B!`gReO`bo$+Gj_{sj)JA4gd} zy&-0L4qPWDS@qvZuzv3n@XQk)Tz(WV9|^{kIl>GK3!~{(DezX1B{ zX7G(RT4=Nuf+_K}V#>1*QE$UZZq!V3#883v8c1l?vApr@STF(-v+eiO_!>)QqSr{kz!(PS;~FpN%D zyG;d0nM!hp-vFbfHDGhRkQ|+odf((?rDyteFdh7sKfG7^@`98L+biC_st~mfN`dtU zj=+H2zu*+G7XEq(?>grSn?gBdSsC0q-FC;LMCyC8I@{kp2I&R_qu8VJb`C@G!6C7R zm(dqHzJchRhu}vMJCFW*sD76VuTPc2_n^acgL4Hv3onF~PlMt4wbwAo-4*P23TZyu zC-Q4(b%F^ERIxLgf02S?>a2Cy1c}nz>8Nf-y_mnn{ZtEqQMZ9pvv3BO+%@^&AMgQu zee=NqdXKu{58*~ zEP|?>OR#f@CiuAd^515Kfay;#6GWv2uP$7t#-1h#%%Q1Lhwtf>=h77tqZ*>k%lQau z!DOHz&J-#6rDqM4famQ`yaC3F6c@IzcSnc!eMik+Nw8zbAUL(?2u%C38x7wJJjO&g zvl&V-rQ&Sn;~6Q{p03Wmo__MK7ry{QfN8U z0F6NmBt18lR1C= zC&*1F_X9ucz-{0&{(9A8UlTY_CexhqH;6ECqicdnkm&+)D5mWKV^#A&wD~g%xG8LL zeT8o`gJ7oQ|@WzTy{OgCI()#~k{Og+dw;Z~K ztuQsPjIK_&jYgw=aCPWv$k}xZev4$mD@hok&k7i4f@wE%X7)UKP1TXJ&NoV{&NHtE zZSc#KXs?y-gRo&(tV%)i`%qX$ z3f)`nEQ8dOTG%2w0glgn%15(F_}zpM%;0BFnCAz7Q_;KB*`$62l3j`G>4P;h1kA_= zD82KL+;=v>3FqgKoJ&+-uUf$O=q+#=Nn`&xn<1FIN$aQA0gt-GU?HQ1Yi@^w-s}fF z=7exS98EA^M|@^nHvFOXlC{8Nr%Y(a8;&YGxw?f%l zkTQB0i7!C(ifSISK)73DxoAE`GAGZg(TcOkowUm>iAC6ZYV3^hwEf+Oyf%k>J7}c; z6S8t@!DG^6zGzS~@ec)FvBBxXHp7x-(eT$;8Bh8kfoHkO_y~DC_SQ~#YGokY;+7K3 z>R#DQp8$3G=@fOg_U&%Q(sdgeF)fr$ivFCrkX`%LRY<7V;Se*;PaCyIwfpYAOuqQ^7}bUGP9XB^XV^GNw^ci+(_>vxW9` zlDwVK^rp#rw5`%Js8sESg62B#5A6nzB2u4-=vSf^%HqhdYOo$T5*PFefVDLTV9t1w zn%%nudWS0FFDH_qy_fK!t3h~V@s?nA#=T&QowVtC8?yI|Q95|x5pN6pn|6dg6G-+8rP_;uAO~tMK*KmW}R%uQZH>JNH)u-TVpGJCTXtR1^Hj zP9a5~g$=u`@NJY-$N}+!Ba8>FP6zf@XD2u$(_^0HGrNL*QErnOVP3Q{Z-7ZiR>nFq z#5Xjz38pSr!v*fGP(pIl)-UY?Yn5pT{ZjT{#!_@XP8*bDSh(n(3KPf{OXp@7 zG`|r10!YAE5X_i^@k~Lp0zFBI>~FeCB$7`zB!0c_QMO6H;MQUdz7D$=N%h&iN&zd) zYKLBLwD?-zs}{)N<(aQhKanY{J@b&f{5}BDpKpPL=%-}5h1)1g0W*SNw(UR3EYFgq zKgz4KI(_FzYY=q5S03+4?n=k|kS7^|&K# zwmLb)%0ntJYZxoxyijdi)l9krN%s5FR~Pp!Cslqa1zeW+6HV_w0Ls@r02OkQZc{FS z!G8WQ;n5a;u(>TnV^1){nG1}{u3ywq8FluH+W_isqJpGmM^^!ti@Vid2S2;6jK`Yl z;0H;ncvOZAo|K@6H%*trI=WqOMejc9c>e?Gc-@BTC(*DvuMAe#?|?{M;qX3Mz|1C? z%Ady>mtU<^Gr_#GO{4LJs}j9%k@#6}IX=@Xu9qrbc#|{0=qk%$^Y-3&-g$ZaXLdI% zcyUimFdHiNxADlp{nO|AdLT=j=k<96Oba=8DhQ8bf ztD0F-lxr0jN>}q3V*#_AVBUBHGsVa2r~?G!kQYsvoC}hajcMT3EJxqzGP*a zZkD}byhv%+JQqVgL-PJH176B-YNHaqd&dY@btq%&3GcwWV>Ft#m_=~%6f{>(foU5q zf`W}TD7w$&F;d}u+8%;QIS|Nn9ehcxBtK8@?s8@$(@!#X)CKX(PG!7fq7mNYphxJ<|RO!nng$UC5XHK_tg+4hg}z7%CmuRK7T5Yc`JOIaDpi?-^^^be@4lW z!RGnT5~@K?PhzkpkD*JH@vTrpKCP6)yt387yYq>ZiKNFdOH^^!;%{K~x(TVxw*%Jv zD){WA!I10(h9wVzj9`5pb3?$y6HMc?tIXP*=hQ$gb++;J3Q6;-0o1Ge<0Sbls=UwU z{W49=`2`{v9h@{yg?A0TZ&Sr`qNk7$Sc`f^%fq$pJ0RmxH`*0=3_c$dqZe87JZ8Jl z1&$NUGw+W~jP(<$Oh=u)BsN327vG4dtlcHfd8UeWdyIH5$JUd^I7vwtr_NEqKSTQB zH{VpTiN`ZI)z=-hKg>lw9U-uA>jW^f%7YDqdcz-i8y;gXU@{3NvNe@SkEx(~^wim3 zE5@L#b(I9+i@S<`;MbmD#W7O^EZR5p9>r} zxdUz9W8ukN4<2(!XtXN?qZIJAVBh*Dl$WkLyCgmo{SGUo`b(!W^F(TR>=9%9=d~t@ z!USi})5Q@@%2=_yFTNY4ir;8SLGeH~HHnHv;(A}8N<3h9M+Nv*AySwll*cR=qA4I4 zx9!okKMJ2vNo4lC7IPe_Hcp|dah`aAg&LliEnv>>6EJH@iVuh3v^h(s+=VIY?C7mk zA!rY&6LH*h37nh$8WJYkz>%lI2wfmx?huS#t&H8i*)J$opJWrwl!)E3rqOuJXFIOZ z{(sCZB>}@pfL<89fn5n{^oibA(A-&@p<&i6Fr54v>Y^=R(Nr?$aDRkGdqglNha8)@ zeDNE~%Ya-KuW^*pYu)IASM$Yj#8t)FdA1T~%D>U%kaZXrjp&sM)>zmEYE!16rYaHa z9IzKITaN+7#ZTa{wl-|95KwK-Uwk`38M{nV#u3^c=CwjbL9zqOab;}tz{K1vM+oD-h&Y!xsvsNE`}*=Z>@$_r@DQctNHnS=_1-jGd^kpw~SSZK$r!W?ojN*$sVBc83BzV7?+g zZ)S)$tyRZs{fv2eR`vrq+~6$aNqc@L;*y_!XlQXC$eXto+9qy<6jN1v(}qZzZQ}Vx zdn81oM=(W>7Yf2Pbm%TJ5tt2IE~&iL7j4_<=P5wU0EWuzx_1|pMqRoc*A9xuJq zhhGaUP&3B!?rY&MWT(bueRC#@%<=)ay;6b(PMik%4Ttxt1L+5tkcS8}(;ZZl4_C7PPs?MNiHFHQ+vh`42wgeWB)xkci&LO*HaePnv^-ul{!3?lC&YYLGrTc#pu@|1F z(ASMkQ1v)fn)42Z9r-VYGbeGW^8aGCejkiMHw&G!mQ z@8+3+aU&S@H^kRTWBPNAh}|6GOs6{PBc~iAy0?QY)?M*mjMrFA-emDFCUWXv{Nz9a zlB=5!>QP=WDquN;)a&Dv$aAPoB3u()5iqL=rYt&)(HJ_74tgabk1WFNjy3l}$K$Ih zRU$0iFj601XljL`8y4*Ma3F;>oJ?rwLZS67JG%8%c~ z-}XPD!|hF}x-~MGN$id9%d2B<6yU5@o^F5O+gf7nTd9outJ&b43fGXkzXzn2`M^87 zDX_1Mj2cE^s47(0;@%QmLx~*5N6ZYk=s`D?i`b`M6{*d?@6yZJleV19gxlXd8>^1F zF>REK1`f3T1Ke_un{P%Qw#MR>r%-C$VmLTs6)0HF0h#`WI9_u*I;AVTQr#k8P7=(L zMk!Rq74uzdj( zUGac1$DN>Rcpn^iU_aVxE{pLo;)0L zf^!;60Zny=+EPR8jQvn+gV1PYg8oBFFvUYt8LKJlXwT;&c3wq*-Cq4DddB1s9+M

ROv4lv+@ml8U)*;FeYc(q15}s5%3?=&ciIp~SMNi<8-zxiCSXbk zruozfM)9p5eX@#-07rSb@ze)%k_GCs#9ruj0M z6EtxWp#LA!5u<|7r3}aFr6*C@l^IZ=;RRN*^C4tBiKc%TDwh?aSu0>(6O75sR3_k) zKmGWIvp){xK#vWD9+}PQ<1uIZ<8KMs$l|9gpFZMv^N+G@PdG zUyNdr3U-@lg-6^ui;jg%hKK(irCQ>8*5Z zgNR**WGI`iPD-y!h=x-daV}LZ8csm_FNRyHU(OhY{b#15Tt8bFspkRe+uULBBSXBW zDhb{CEcCQ-ru^Z3C&5g{`5Up1+28R<9Fi!bKq(sR@r!P?MGUa(^pR-+LSVrd7l? ze@&#wBTVYWn+Wl4BAVe`Llt_OJcg6baf1!_Z8*%5;DPwf>*FZnxEAiIb;N3B&5CU_IhJM3DiWy|hxMsl!-K?}bZ-3wJzOZpA{10D^t7P@#(-c_ez`H4YqrtL z$jTD6%&@7``B zIJib^fThao;F+j5R*Zj%cJ39TQ5P`d2!?gFV`NB&UP>^5cGsxUBaVnCXa?DFOOAz4 zb$M$qH{VP;E13GKl!cvi|K|%Kp9UNf+U4OPfzrMR*rg<-XvArF=D;L%RZU%fb zE(DV^pbxW4x`}?-B4WdjO`%M6MoLg<9>uLXIZV_&P0U#o$8Htzvc@4{!U@#sK1SHY zBnQQ08bLwQc38Y57{bPA;hW_uF#fwRLW_iGJP78~TMcI5`wg^ClZd6dRVexUNU|y^ zo4Q*nU^;GVVmi|Z=lP5H#clp30n>Yu5$-a*h3?KX1*IW7VdmfiP&Hj0FMO>Ey8$iH&!VMT-&0$pt~`+z{AGdZVYi9%u}W$Q8 zeqj>7KQi>25pw^*aC$=y(|fQCK08prjL6p~nxk@bB-#Y#l84E5tM|hN;_=FlHHL;{ zA(|!uvx{KR0xibcZ4Et#OlvnMerHm|Q4)jHPToHHZ#10Vki&5Mn^PJl*m0REu58o8 zQI=(BtcwwpkYtOyDZvont%C1V8bM@l0W({`gc8hIM@?oFonOqFbERiyvi`ER3fityA$B7RdCS0rG}^m}2O zfTw7&x*D;L9)eyZV}fy0z}IUBL(U#y?-`}fW0DC*zh0Hm{p>+ccqn3f9E)u~3_dE+ z+AU8jwhI`=Uz)r^k889yeP!{1SOL>{T?1?2H^?Af3wAG!0vEq<7^o+Ql@hJsovN_+ zEEF(j2&P}F8na;sDePQAI&{V}@$<2#C2Be3nZgixz6)>|PNBzP7Q4veecJ>~AldKq zFQ`RV2WZ0R>m<$5JsiF~k-`1W4F_Ydf36|~%q4=EUai5Lc(#y!d0WJ8U)?Ewp;;hV zr~Q!Pbh=y@;4qv*kHdI{%Hjq$0YeUy@tcbc=$oMkJoMsV&Fo0Hu16k@X^)3@I>G~( zeFEkt!5qD)%Z$}=p<4?@Y;eLo@yN}$C4sxHQ17GU`B8wwC|(pW-0{OED*;o#ocu<# z>(Q?rYT&*<3G|8cK5s)iFe4_y;iW=i%uNAPL@rV*h+SB*NL+Z7kt|<6gPQnKo*$t(40o!|4V~Fz+mvdZw_St^7@M8b&&-(Ynasp;gpogW1P^mxp3g6T7C9OL3MgSN~Uv4bp0 zCCnQolCnQCR28xGFa09?Za5(zHxY0K|A%h`O!-lAhw!EyO|DY~zny6?X)~#gJ+}pJ zT$>EN&kL7ctvWoWhF}h#v}YE_PN73@idcvF$Hje#`=P(}C_6=q|6-a(81kOmv8i(W zjR$u}Feg?Kdk1%-^mhtiN$PyNuMUH?%UVEV@O1Dp|L3WdE{|y>7;)VU=I0$u&m$PJ z=MtAj>iX2hKj=Lwh}1T#W*9&`2!ML!{!A-i0~_A2?3*y-5}XS?n))5HH_xCPWK zS$QmpH{xaVu|`gk4}X;lw~U$&E)k*7_f!UXReT$Y`#2UVxGX8;FsFoX(?c-#+MF5V zqzQCC@@+2nJwa=~G?Z#Pd)aa4X|DDW4pt3rwiw9d|P<> z!4}Xv>;==mv#?{&*v9Wzxpk zlEp1NJgC8AhOIQfUamxWY(%d0%ysb4J%30+RAMDTgW0C42w14aMR!@RHR$8 z@j*jaE*b-&(R2vreMD%%?nPF#EF)s4?W&<2te;ChUiO!8HCDK13EYn0%bY%ZG~6NN zt&s{iam{-;@^~XzS7<{k~j#&@@4`PP1sK|`R_-XT)fdpf&(wnhZ)R(?aP6scpcpyp8b(F5Y z6faFCLI^I$V=U1dMqSe7MVef>5H2^0E5FctuqnPJ6FJusX;8e1ON3QTKP z;iLWa{I|KN#bZVi%*In~1vjhp>4>2ur|`Ws6{J)kxv?QxIwgH0+wOmz93$+i5lE1pW?c}4I!E-1XI{AEdTg$UAmOy;yU=$ zqi5l(=~u3|q@PDTN1uCDqa-ru%)Fq9-)Jb|-0p7>zODfUHJ?SJRQ}NS`xhYVwkh~X zV~AwjGG81*PM&loJx1Y;Px+sxg%FJs!Gx!2+f_&QqFq0#vzqi9RJ^~5Qb(VpHBTjI z&D?9~p_V-6o+X^OQpCj@TS&=?=jdEUDl$&2M|%?_$kS&oo_{?@sx-hK_dA_SUKN+3 zvsu+VrcuN<+9HDKmmg`j>4^^QJW_+LP>PaXUEnP)tI#ccSyqO^U2dRFWRWX6DZ;B| z6mSnI>}asM4*hc( zs_nD;`&*Y*O(ey(R`rp5vXrGe#}6-L*)OOhstn0x{Dtgas`wPKBXxGwgUqK6q`j;X zo$h&$+O2LO>sJSGu2-J4aI7D8+l5`zKxSIk6A}BrRBkP6L$5YH*{;Tw$qPG zZ*KZbYYymJc;%BCgzxA^w*9+7GE)VwXqCl1^am(eO!QJOwEy$peJ(wSaq2mS2p*T!>&p~^cEGB?pV%I7b_^#?h&)uTQZs>nS+Vk)oZJIf=u>WN@aEW&( zsl>*3 zE(QluEBBRe1(>EDfxABOc&1uBnxyKAS%*RhjnIX>9xLFYacJi;kp#1Ft*ls+REY_i zt;Oz*nJal5xC~`0$rjqORYV5(0=UOXIaqN6ZrH5~_evJxn5V69u>3vj zwQb;|8P&#PP7sVkoul|+Yf4Z8b6O!@*Gv!eqJ zkcp#Xl>r}((MKL5CYXvd1I5QJ#?u)!+N|Q8eAH1tMe@@A0pmaS8?-6DBMnDNA`*;$ zWhXIQ378gd@+Lag4!1NTJm_gSetT9M#^fx(#p8ZJV685mLqyM{qsjQZ<1xhqq53BTG$;#u1UoyEk|H>(ZCnvtrC;gz-D15_w;r$=(hYKf+pvqx3pn~_ z06W*;f{orhm~G#r!LCrZ#!D4gn!~76@zIbs|1ufbjpA=Ms&wEZE%xG0JL&8q(?Ujk z8~IQA3-;RINM7MXh@Sr%P|!S2=e%N1iOFsNH%?q zF&n1lj0YI6<)hj1g2%|I%gT5~JP}uadqFKv)M6DC%pgs}qHz7;mxw#-EExA4?9DEN z=J$LEwakM@o*BFrwB_(`Sn9eS9~x{7Iqyu_$!iT*|L?t7Pi19xV(UIUwbq#bHY=X< z7|2b%j`mj{aU~s+xeIL1e@`Z&>2oLS?`3wkHkGN?S2;+ zz4-winZ9@}WkrXdXeit=zPvEjQCwK&f2GiLR3bK4Zsntiddg$;38pZ1o;dLVP)_xl z?7Vwx=|b_y!jJ2pA?|3Xv85drJ)90TEzU6b+-NZPG8S}jCwP+IQb_79oY6CnvastX z?dxnU>AhJ+lD{Ha5}A{NOGbqAn1_`-ra!@aZPgLWrf1o`xTeWkZR?FJ9>^9pdoDoS zEv~I&2h?oVhLCm(m^---v_|xttaR-B zGVq5Ty`)?hm|xCgh7wH3_t(ra3-+coNt2D;vlktSHz{;q`i4IjaL(y~@{d0d9^VI+ zSBud(wLd8F+;1q2ZiW6$!B}ophxF~|0wlI?KxeAHqdn$1sAB3>9I)~&kEwsiW5y87 zUYTpmljwbnTeK!S(M)O|c#bKK4hYI4p z&pjZ$cuGmk?Qhbxy1<}D7RF2;1}En{Ma$!L!0g&D;D*k^w@2`?n*N2W#!Jz-A9d)a zj*!Eqc41&2Gkjj)@w-euv)nqLPPCz9WQl&a`w4~f_jf-X^(XWwW zJ}_gDDp0`690Xx$%Y4xM!USaBzIaK zNV&REo&A4k%Z<&v-x;u@$>hWg-i_~1Ag zdY50up*!F47zKvMcoWRwJGIQ7^+&|#2WheLxh2wB$w^YmQMvHFsS^LY;i~*5KmHAo zZ>vD<+gtGb`W>W~K0*3~LwMW@1Bq#^1?-8ug+}$uMVEn>W=0;52_%^1b6v!ntdEIDwrH^ds;|Jz zIgO}-#`2ibMeX2u=`}wQv@t)x#*3(ry~xwVwvX_0XfUoRaiJ$XzY6+W>fnJJ!ZU&g z^9$RKU6T+O&4nvGCWK((&dq0BNY!P67?E^zNWk2yv#f0gIn%(0&&R>8g4f_w+5w`D3izi(+F_o9oN zZ#WDm)#kp9ci*4jce)j7?|uMTqusc*{ymBh(ZH>Jt*}pw1%C2f9kWxi@mbFgJSH`R z$D|X?pOlr1zuW+^TWK#=X0c46%I3|;>!MR3SENp7##cW1V(NM!n$W91p+J_P2i8Hr zoCEm4&RNhvYv7~fY;nUCa+gr>8@`@8g$FDdjJa>~H;uiDaj-Zs7te6AGCxbjICa0dUL;ca|}zD0^^JX{otrhe1KPP(J9 z(kcZnqOUv8+bQVbW_`AkeQF zRy4}sp{xEt;aE$zzX2Qk1884TBAH;gA`T8MpZMQR(u{uWMxsaHcdY`_XWOujXNIy?Ru))o^jT17*ox2ZnFjVwgV=`FK|Dr2 znUCfz!Hhruf^k9G)bDY+taMZwqMQz+{Ww!GkW{bYh)5E~N$o8hjXsEC@imF5jXb z&vM{;hZXQ&sM|?1ei6=&VKkC0>q8>F!;!=(Al0N^a|bu}0+E3=lA}Sc+zt*CA)KNOY!B z0}gdTh2kmm-_R9V2{^UnhUB_+ zKUi{XCXZ=9!Z(@`!KheU6}Uw2rRI&-Wn)W!h_hYC(91WNqZ%(oSaazy%ChK$eL=F= zSwiIVq|s`gG$HLJAJIIk&UlX=0mF0UHw_7XzPJTyZ_B2q}f~Vff|2eaX zmW#ugMnRGtn^W-*Z5;`>!uhi)3Ue6igFI#g!PK}-XY}nN$+K%+HuvFQ@rS)8D1N>J z!oJht+MR_&%FxbF1f`?fAZsQm-0;B|{c-M}r61&WwkbT>o$3z747<+=j zGrgF;DTk=Z4|Ld`Evis;dbHHnY!?b#UIaRYwGcn5<3E^m&0nB4x}MK0&gxJ@meCco zk53TRyW3Z~Z*CgKK|pE|>;+^e>^)5c%xr?mr+aMQh?1zO={oFIiM8o?LW&bQlwkz7`|9w~ zwD0AkaV40unv?Bb-b$j*1?jM5;tuJee#X=c<;f`b%sbfap@h}ewDZRg1t(j;?Av#E z=&68pPCtd_m80=nQZmtf@KHR``7k;AJb@dI45$0o+2g|-KJplw-8^PF!59y@Qm~^w zjbe7{u-8W%M;jN8lMel8C*hL)XfstDKj|l!8T^H}=bQf@Rc``~Rrkh!n=@x9nKP84 zNs`2U_O+v=(xh4QEX{Li7LtU7(5Mng8XisV`#$HSSyBl}5s{3^7?R$7_Wl3;-}imi zYPFVUEuZ#q_Hga*^}Wc2uo-?ks^RSaK0_>du|0Y32OK{afhQTOBHvY4u>FVQ$TLC@ zzv;}TnAW`%<3}(S5uiI~m@^>O6xUig#maeSm*89g|B2`lvuK-s58bQz|CRAfA?s)|P!2I1h6 z0gPGVdA#kvC{(x15ihiEr5NSy6myVZV6Xb4p)=A&oU0z+zWE~CZuXz6uDm@XV5IBR zaAsV)Fg7&b(|~IMtu<=6@cU<&=Wc)v`~8FS-6ycfa|F`a6pN!jrHiT`jldT91r&35 z3&n&GjN9C@%=-_niHLVcIwt6S;(Q2#RDM zP4i^=&yL)cP$%q^D$6E%u#IBQ5sZ{5AqTup7428iQ~iq-NPo~#%2fF z8fV$qTqBrXI}60+3elpnI$i#*l0MUCxm0SoNrbW{R6~ubHa5OR?lS$mp*_4B+zjhs zr-c@-{apb+&=IKv*K;UQ?W{>62;t;b=qx$Ig5+Mx!OS@ z{6UwWx_+~?yy!ctUh$7n*j58l=iVg5{T95(*O3Ivk6_TA2SMv)n0+a8@%|Dix;bbJ zUv|`v-?h}5Z?ziA$3-r{HmiVQhRLQtCczjydn&#oKT}knrOTI(Jc)8uX0hMi1XB!i zm|#fE#@H>Jx?TH^OQV>oUS*J-vlwsHF%%86vEikj7JP?YUw&7jED{2$#@>0ElaChex_TGn?O!4(<5HOcFhCtTqE3k<;h_tTV2Ybg7 ziSL6iP(NuiUT`6r9TC{d4YO|HylUTZ4}3DX-{l+dxaGGg=8_DPOE3dP(_JeSjYI)= zb@`$nL*PP8K#I}Oy8)xdUlwLf**&}Vmtooo=AB2{Si_7J0yt(@XRiPw#Z5;Ke7`EHo!`ptW=N^_RgPmU-I=(*& zRex25t^aF9-f(GYh}M`Pb@r z%O*|mZ4g1Xtp*73G$Damzz8Q8*u9m;Yz+PG(5tQRv*7vT@wz{kXlt5$DMp=OVir}n zHVo(yZLHJd7ucG@@O!gi^UEIA_<9LEnxTdxZRUW&o1>87yc8<0uK?+4ZM>%G6UChD zSjp{CJcxCF=fP>~;dt}KRLtKM;pgQqDCW#6is?fzC8chn;V~x61d%>}bLMzq-fBX zkJJPx>g9JhxxY7_d!U52X22-S#oTH{OBZfLd8V2mnz06cwU59r<_A$s<4W3^!2~lt zc)uvIU^R2wxeuSdUJ0oqHR~&w^wz<4j^tg3 zjKh=m0i43eCh@`04=Cc?8hlkQ3EwLnhzHeNq?p`g6yrcJJ1(pc<;)3W6mt6Tg?E0l zX;VL-`XydmLexhXrmBdAS6nyv4GOUzz|F4`p6$}1`;CCvc+!CL_f0^*>I0xa+Zx}0 z9f9A548}8N$_z6c7E_FfVD=k$iIygvVAeSGTruQB!ESk6Fjx`S zrniB2Yd*y+FVw-Y*Gp+@>KO+f{DFx z$~E=X3FgRuWY5S9=B6E1l@8W4`s&_)8yfXe$6^PSDXyF1|*%bIZi(+OF%qbl0GT`+o#%!bkzdA9G`&9Z7eOB}2 zCfB{A7863M{K3@UU|jnV>{Ke@#U>K)USCFAbKo#9U3*6jzkZ{EQE)5VId>QjGpvEi z`!drx>**BZLogMeNdcExF^tYt13v0_06a6p=uY7fPPj>DuKWiLfy!9$<*+j?0`)Bw zVEIoUmnwgwnEeBKbB|3QL7~chSn#_)&Weq}f7`miqK}w%+McNtvx;Eu%s=F+opPSZ zQ|ZU&)h$A~`^-?)%pa^UHUj4Ss$SS?@E=%VK!T72Gpno*-K4eWsp0AbloN$dQlyzDF!Ay4# z7VUPw%uGDok01Ril09{1b7wv(d5M?OQo z+gq;Ug)JZQKoeh&vxJv_M&aWzZumm=L|#r;j~6g&rqR}f5zISnMs$HY&lraEBh|4@ zIIOsk9iHhV_5S?^vJX_iGm`Q)^P(KSaOfK}6MwGaIm8Bp*yg+^`JpFDMf~W$PWUG~ z6{eZkVF!OhoHu3?|1ivwV*bc5u>?aZxVmmPI>W5J*pCnHna&keFJ$X`blJ(ZkBFXz zgONaFJg&quWl|+A?&$OKIb0r-3fM}Uk9lv$pEjS1*Zf`t_g6ULq2Jr#V44jdHbaME zv}Bk|1oKh;j`;P0Q_Qp{{rJpn-dw+>EW1njgS42`h^So^1%i!%aPde;{|*T$4a8+R z9I`!vA?9N_x3s>Ui%i>&gM8P3nyoXgNa117l^jlW$#Xh3MKVk(!6=RNlBCt0WO|qM z;}ba%ck^_l^p{zkbU^WD;=45-?j)<>tT`ky$W%cl`U$Q3#z05!2_W58FNM)%(#j`6 zSgUeAB%$$m=DAQfpLJTa`=kk-X)kBevB@BqX}!)$Tn~gX3x4+FC;n1pYn?BPv>WuK zWjP~Z@UbS8w3F!4A9h1(VigqUlXsgFuTk}HeW)8hTB`2r!z6wP#@z?x0m>HRk-b*K z`>~_Zl*_lJ!W4MxO))IN#P+@@S-STmqtn)p@0tA+6)2u&q7_C-^B?ztl!Iw#L2q>| z*yaeBX6Htb%RP-+4=BRriW{iIs0%%HJ%ZbPdZVied+@SAAL7iT3-kUSp}~}PS!-Sr z%!0prB|n!&Fv;Eh_%EN;(SM~3s{Rxu{Su`MAzc^HDK!m>2~Ln<4%@_%6OJ+*2|kZb z)+)k}SBLSsk%w4R9fF7do(d_k`Vif{mtyYCpsmRxm?BdziFRcaW1wNkJI{ILUrnZ&jRC*LMf-&Tu zY`V*-D0~)O`zy~z?wJVr+72*PqJh<)cEJ+&?{sY5t#XAOjq8C=yi5*FX?SsI6!u(` zFCBj6B+d(rLmuZN@rofz6f@qPVtx@!&bpnFhjP(O{SrgI^t>v2_8%_^x9FBm9vMR_ z`o)5fz1qB#C?7VF(ukvekz4h7sI9yPPlhVubtZpd{^A&HSpShJDGJ1D3b#cEkAHzv zW9;b)EpelmE`lk?(Gn${a7Jy1AwO_(ob+PTId&*>UgC0v)V`UL3qrDA?XWKRcJ>Fb z!V_!)WvTQ2X9+TR|=wmO%j*l7UNHssNmBCWg*~6IBo4+M)7iviinp_M?*0)D)C-}(Mkhh!`sC=T%oPM9?WCjl#R5Ok>DfcjlwGRyAwN=v(IyzhjjW{b-U()7gdy*J%bCkMGlreE zEGq=JI#0;?KDGz(Yh^>JWM~x9C&2N7l&R(FXr2FKT|HVR?i#2-;4MS5f2FU z3GEb9+uls8l?qSak3L!83g_|IJLEh@x7=a7Xd8YK-<$RCYk@N+yrP)#KrvPXGiK{G ziOQ*!%*)q?e3yAI;Ewok4mv7qKnRHgX#WCXu}O7rgKJC4k&uLj)OIP;D!*NyRPeZS zc6f_UB*sJ!H8E=ke)>8|R7iH$S(l0^hG8gXD8Y={eozvzaxycZz>uG|^Bwwj?-#3L z{g}zC`UU>`nqb&O8OC961AKeh3?HMFu-m;Rn0ikhueBMAN6iT(x&m_;BflL_{kDYJ zZE1<`K9dPxwz^V`6TwtpnIk!5Z_j*uXUN}MJVW$F$%Mky@BW77k($%q?vkTt!?>H7coeGoQ`C*T%N7>-f{qX#UG6Bp8XNtiD^XhuA% zX3TFW8+TnPID(y6%e@!$%+^DCF1Bmu!nU)5A>OK+&1(hQk zqa^rOmH@f?{J}2I7}prBp`Dg6nqnps%od*{iOok%=0=_&|KY_O_GlZ+mWXswHi_5@ zdVxtfy>RX)61od&h1|DYVDy+gB73yLz5+}9djBAtcXS?ib=^8?h`~ZOE$kE9nqr23 z7s>=Mp-vPtTj;cnZzM168$_R^hWw^Vb+)@_BDZ0fHS$@~1;rQsg0g}N#dw@(1M}hC zP_SJEJCKNB_U~cX;f*>zHsc>>cl9z?k@$$)vA2LTa2|$x-&CTXr^gtISwb-X8Fov~ zUrrL?ONPAsIwkg2hYx4|elHSqHd1|goW1=Yaqj&|bvE9QTB+lhfRS7ti91}rK-)Td z{=U2_@8r;jKT+GChtnQ7_Q76>uyjtBwZ@lVy4wFqh6XYsg*}G+)%I6xbU`rp^6Wme zqW3>wW+`IzDL>$wRS9IjECoS3_%%rd`;&6XX|G(ce@iOF>~rHcJnPTv%h~aEKZw?5 z%wilT?n7I1Nru@*Fz~xaayvyUvudFsf41ZjJUDWSyX-LleR3jI<;gWlaE3+2k4Xu{ z$JBtfFY)H+imQkC?XI|S{(4CDb>d$wGUA^;H{+{+nDJK{0`aVjuN0Fm!|W%RN27}+ z_D!ymmT`vsb>+Z zH!yMzRSk`E?}eY5tbo}+x55U^C9r?E2qLB{;^whskbh6x;(@uUxNNHt zJj@vjdwTl7FXuM&iabsVhue(3i*V$i(a1L{Sz0jFUbJdhfXL^FF%w}MkJZ-wrk%Dx z_IV}{j8oTb$?t`Z(jN+je8|#Q(txNv+#R(e(pUFMI`$YfY;ms&-R1^DO7BYal1Q+| z@rWgYm<|@IAm?)J*{h23q zH8kW^1IDxcyqvkUJAoB6P=XuW?NtS+wax|%9~4qd5R%7M1^JLAe*_;|*T&S8<)J&1 z-=l5s^3cN4_vo>AG@kn}h+;ZrW0OuWUvvv3J(8VL>}be8kUPbODNW)w7tEpcG zjj!mJ;V5{>SEK6EFKBg&99|Ld9;9GA2GknWdkp(MdV@QX&VF zAN>Q5;cwvM@o;>;#6TpRZvMZ2;6n`V{pKgdLT&S=H7IsWeug69D=!+-zwQFz94;f-;g(c^_>|V#c=BjGS~t$IefB*TnHzg z0>9Qwm|T8_R46$|WpJC0J%c*s<5FXTo% zg;$NIaJ5k>YS2$ci>Jqeclb|alJO4x^9sW+`8e8X{bZOjf+-2=CH+1tO}coC5wHGC zDtd9rg*oIfg%d=5NtNV{U>GU3Nt|KRP0QiFrA!Iwbn+>D@IHp$=5b8&(?ERMcNZRC zJ{9`>w-Uz8kHwQVCsE9c!L&8C1e5FjSrR@hN&3CQh<{~N4O&qK@aereS3|t*7F<-r zwZv)EDZCk?YT6-~n3-;RN0h{ES)i#JfS;A7q90Ft;~m)}@t5)=puaK^YJ$$<)t%mS zY!=8ctpu~GW~rp$K!Wt+G-JML_B9xMSP2%Vm~n0Yk#uZ^2rbqZkRm9}usBzdW)?dY zc0ugYEC>wWfY&UJLgPn2h1uT3#*N(S9)9SLpPOI87IT+T%=>|~H9Z9LeEe6J<=TPL zi*Jqjpr>!}7@NbODre0JNwUWyRj?Its#9zzMpcK%t__gLFle^)_e>K$=Z7}3%Zwo5x*?ok z&GO1r8Bca8BY7Kb&@WXEe;d<9J54B%KC^8;F4Rdtb5N&u*(_Gewcta zpOBpeN~|eHk6_9?7?I!2(bAPUCcLuMC|2ceEIb_K&V64-ateuGXKH69ttu}_;sy1C z9@hgtL{j>=-%%`&j>4WBuVMNmLu^!TgzdA3;wSI-;SN@fPJu%*j48qVYSMSzk)wL#`kk6C5sWmUUAvRlylHe#m{$8EpeP?nE4uVTJuk zBH*M|3i#@rK-e*^f{snKC2frj!Fag#l@uEPkm#N?<#~-%?u_UMQu0vbN=Wu<$#r?W zjmY1H`^{KPR%YveP@bzmE`OwC@@Efb$stqDiRho+Sr5jcMnB+wJ~0L!D`uY@JV9G? zX#mC86O8e|2+3rnTarVcP5HY9Zk)Gs2<+Ta!3w#!D?a=M!Q@o9Nefdz$X>mkqew%l zU(MsW4TnB)cbqJ7$tN|OLlR`?{1*;|`tP~ZA5UJWVS-ph@go?|lJojT#@7Y{AD**ToOE zkh;beBk=d|^Dy7Qia)wTg%>c>2GQ1xCzvz#7bQJkbj5Y9X8fwo(wi z!EJO2MBV-iLd-^(0)nN{eccAIn)?pEzZk^Nj&R@`@0eiK-xp!sFi*U8a4=|EjN#K? z4WO8O8D<*6JiZLp3m!pZXDVN9saef_pUrz5wpo$9;%_2r%t{Pd`( z&C#T=j9h=n7#_)9 zU3w54VG@j8q=bcc&kH8ML2w@(I$|-{_nQIVB2RMfXRhGJpBaL8ZtjKN#)aXs&Wmtm zuDLY)N`~h3pyJ?GBSC02hEL=OZ|$>NG0q8 z_uEjBp(kE3m}ABMaoAz*7#LNh0;8A4(C=oq40D)ZqHXWGE{W*N%n2~(N0-^MhQ~&r zn*N?_b;wU71XIRVs9AwQK zyQmIbbrBSEOg1*51oL}jAJ-4zCQMa=Ip4SW5j)plIEo+tQ;G-wLB4;p(I;Z4DLfX( zX38)RHR_Piny;>BQR!|a==pL4Pt6ZzXSSTesn#M%`6>-4TpmU->ul*1h$a|iiIMo! zM04gnYtDze?`H$0dnHrLx3T%rs*p0gk+$Z*T6ugoqJ>JWBwp&^>F^8v?=&-JNGMLs z7{ngYkHFmI-&AKK{6Ap|9F*-h7YOD@N~3t%9BZbl(wtwJSXU^F8dZ};6AlRXA z3xWadolE3wHnN#s3f~={2s3t$1T8bNuaIBoF#a^wnAKZS6dQ&!vK(1Ug|<3Gy|{Sjbq38rwu4@{7L|fVn2AiWymioUsc$*&cwq z4f;s6AROyOMT!=b_`;MAyXZ!6RECid%n%zbNzk_8%o+Xu{MZXbz`r3K*{SI;-o&cV zA*=%mh=Y}oO(eKo3#uVE)jyE+;R8&z$Y=76L)e`Q*WhV#f7lfJv)D9F3C@pdM>hE{ z=oCnoVV)DrNbAGmDti$VtJ9x1HaN}LFEC-&7(`36cUME|U9!)R3GK4~A7r{U!f+x5 zx#_Ns1)=hFH7gvI*&lCg48|*6;v`dt#NeBjw^7`e({Oj+Roa?DQ`%|o2xddlFtKu- z6Ejk?Kfhf*2St~qvpMNT?6x&^&^JvE3lA%T9@@Asi9xSvlHENOzrhe~5=-;@10Cy+ zVeMJ^jH6}@_DNBO&|P-;!dNpp1)j@VQ%o@99A~>UPaMLmH|@_ql&e5P7pAZ(ewmD) zV;y~pxK19mh7;4Qu7mYd4=uE2TIP31QzqA`EOneTFA$$Sn=5f+<8j0TB?vu9JaE)y zDOg(!X=^G8Ci#6ISL+$p%rK4q{Ot4w_U4Vg?3|Aqk$`zNR34ACQzH4d-Ly4pF8l)h zLu&NJV}zA9UNTt^`%VwU>4z=R*9nn$W_}`SoYfakd!j*G)76(^eiF=~hvOgZxo6Cr zEh1~0@;26~&qa3X*CWVBp^iS`b$%pi3uKe_?){TS2hGSM*ODcbFzK%zUf7_EU+0Ek z>=BO?5|86UvtNszwdmkBqHHB!r`$C?is>Mjhfi*b-yP9qre~V-rODRpwWn%qq3bCW zpjHQ3+Z1s5b{R$p4GB^!L1(jVMip2SDev|iZESnm3;J(=2~K0)LfY?3pm0zF|C+;6 zj6|1W6m;d~8u#c+Qa7tJZYRz8?%y@+-n9y>pt;d!%q9c;Qc9>=dc2?OFS`SbOP{L(lD{$;El|M!R! z_FgN?CNk+qTVp{m6K)@spng)(lN2-FW^)rW&8LJ7$!V`a<1aN2f@_Wj zT$+)TVoLrI>!PCb@N>jX$or89-u+L*Ck+j3PAsUS_fN-$gNCyyLAtzWtqMQCp^eKt zSk2{n1>s5e?odpQ5$!ZYFn;dknFjNoyJk0;@+oI+P(yqi+qx+YWw|$j5EpQSwU9nE z7}BCQK_9~@)brl2yaZPD+Kdec$4Xy1-Q^BXOW`!`25_MR=WwTQ?#E>>WE(-GY_ahq zm?7759<8e#>#F(GlyBOkE_E+VW7YHeq0||_An3aqp0UOR>bFgSun0?t>`{ba-7*=R z=i1N&v2A>zFWxf{dVC6VX{|TZ8O>$Z-Q}Jotin(l69GqY09si zkj9RG>dwfGS9&NU$qM0zWziL=a_w-K5#E3v&dou#6-2g3BqRSmN0O6h0{gtP8s(1^ zqn?sSXoFE5%2~S^lYcMmwDU5|B7)hb(o4Kx>RFfO*QWeH*SYNO$X@7M&J?_aS@wXo?_R|Y(b-nZ=(k%?xSn#8&E>+G9031LopgM z%o>8RoO@Xu`e?Ol??zKTe`h-TH~%e@>%NsOj<1J-Nvc?9RteIv9|12zO403eek>G!FB-Vgj2~JWg5I5vMt#;dv0WtpY3ooG9Qn%%BuXn` zQR`5so;ePL6}r9qBe;*fkJ0AW6qB&$Fb>l{icNx&@jK%=crTW%X+g3zEs$U;#Zh9{ zQ{JKj>1O=lls@RzMl00mC&www{6W_=?~-6hC{KpFyH0}MiUiOlx3YjUh4ACd4ZP~M z2{$p^2Cr$I4@p0tflHsiP*buJ*VUxZ);yMN1mOh3EsB2R^WmV#P}iInHCLdTgW7PU z(}`PguL^21N#%>3QbRZu0g_&H}k?+)(BM;YtN`5;`zFP#b4{Km_Uv*sE@(D&i zyo=v0m*dJz#$v_X-ncZ-5xd7Oz+WHF#1EpSw9|rQm^6Y3^`7Zk^Pe1Z`dWYfdWbnX zy~qfv{hYX{o^Rl%+yhak8^A}2)FhNE1;La-SOub73Ss4pyZGkr5h&pa@xEuaLuvUa zY#Fo>Z}>75J58#l7)Nco3fw0cy=@;{hfmdG{_AbQFD*VStz6d5NRBSx1bv!!SvRau zZKI`J^14dt3%h{Pb|?VLqBQIj`Bggoj~b4-SpyNgEnazR369z}3%d=^qnJ4w6vGot z(U?Hj1&#xlUS}^*uF_ns=0(yP%H%FOg6#5h|));UiOT^6idE(*b-6v46i;5L$_0Ym5wM4HLHvmt1zZ^d) zvcpD`Wtd+wOg_QL#f^QqR@0q%US!Fq7HFXhm-Zn3Dv?@oq~=|4Cpi541EDwmfgl+X zS|jK>caaJ|PSs|3cGG3Jy_md+1V4v&&#dusScLt&9bs6%O4^!a7229of*Ci@*wyUM z6z2C-D}GR#tz^A*0*Y?!%?Z-pZ4usoa{J&n`(ED9@TYZm}-I<+1ccp=R1c9kF(-Cv-Q!=`~~QRq=prw zy?%YWKu~mz^CB55yDGt7p^0h-9oCcsvbn=P3rpf!!pcBg383TehTGnXu;!~K?%3Mh zoNyd$P^PVECYbo-!J_AH<}AH}dxm>GQm2607)f2$=RAn$9cZQ>lvBIJTOqyYr&{(%h)`BYN{U@<;I= zX?FNoha)&3cYNn$Eu_tvz(-8!&kL>bmSI%%cVvTn&FpR7QBxB{^zK^hC@FNI6Wx{V%9?rL#df{!WF^mXv$J5W= z0*-g&k4a4_rk@O>Lol|^8^v*pW;5mom9iScU1gA^XpH5HN?9lCnoX zYl-`72iQDM0u@qVnDtlTBlOjIZvF~9!5c$i?o7-Z_`_peMLytd2ko?*vMFFpFjhI5 z5?}ur%ob;B{^-9?teoj%qP% zrgx^~(}(#?NUSG3jnjex3uS!ZumVoEsDtoN9U#O7DhF7=qQ{S2Xl9R9%FIQ7((vz zNO0#7GQHR*wXh3Fviai-gb(~hEmo;0S@jS4>$?{p=if?wRFC7U%YGxZd@VSB^ceka z#>z0x1S2t$lN8_fX6$vW`Tcbqx^-Nik-p7i>IZ3pXU;VwgdYTq@Q^Qf4f*mH(94{k z=+2RIs4ZU!F0S5-=l^)dzWx=BLp#z?eVHB{{jiT>{*#T38^LH)M2RbF<}vU8TJbgC zIMi{*gQ@o}W#ks>!OMVK=rM7G7cg0lGE9-qZ4|Po3pIQRNAuJ*NPVv(_-k!HZhg;r zeD&=Jbo*0Z*!gQS#hA%vnis)9*Vjk8-_K??)>-jWKa`=Xw=<>nyRI|*LXx*`orgwe z%OX$#uWD#(9xA;@^B@0DPxAn)83yD2g-)Dj-y~w&M#{sHm0S2jJ{!5G@^lK!C74V5 zpFC3Z_GY|GtVm6-gY5mApQYu!M=*y)_K@*i7c38{V59T$SjC~5Vk9X>up`t7Uc_9d zzYdN?;5!3;u~+t8#1BMj^rTbXx`JY6cZCYJIm-y9CeT!z<}!ovcx%O1nltP~wGwG% zQah6=4uGpu_QP?K{Vgn=&2N4{=#@_RsSpTxHsNsMnGW9HG8LO;Mq}Np)7Wo133#E) zbGCSw3vS&cvjrXSn_~P3rfqStc&X7O=5>Y@A7K83ojPGOo3~~H(v!OfnfjSj*C}Kc z>#eGWZ=?P|z@;a&jOehW?eNw!0&d?qh2M_SV296)#;?rfxu`pbVCQw&;r38F#q1!M zR%!JQ&mLYb-z6GAX2r`Sp6O>tz3{H*vrYdE&vErxw|>6}C`HVeJc1x-ncIQ!UN z5XMI6v_!Ey?jnz48g)u|ADH3Pb7%3x){E%;@H2S)uq^h>1tl!(2952*NRTWt8sF7c=5KmjgXb}2W*WLsBo-!-4B|*YO6^e_laJ>@ungk z%vs=m)+7P*-ZkW)5RX$ji`ci9d*i21WD4SGKPl!M!5q|5l$=!W$IK?3c6;d=)Rvme zrkrbJ1k7E9ZU`b~r%qvifQ^=61f9(`azs4atc+JJ8i13xL|`W9D(YN!27l4I#eTm$ z44+bx1yg!zDdrl%yn6mdd@5O!8L`}ozhpZfZTfqeeLr{r3e6-b@jGQ0|9M2(JE{gU z*Z!e88->r+a5rTffszbE~G9+XS=WLc92L zai_>)krnSgw~+N6e}bJFv6QJ5|AK&ZJ#gR-c}Vg31JB!PLGXtzxv7LF@2P=VM6psb zZUCO>8Vlxjzu?H7HrUym0pGd?<2{Z~C??|v#bgppW0aAk(ekTE(c6kYQqqsTwtoYg z(Z53EeXtoihs)7mir=$8kbA!ln&I&8(ytn6kblILuQ`fhZW1gkbi%j3M%9+>v) z4@{fZ0K>xMurLLx9P440zAcX5rG)KA-Q;Y?Oyx{l=5UT~SGZr_M&g@~^k{2Db+k3P z1Y^80QSyhqBKptLimyVZ?7(LZT%h{`WUSZ@V_g)naO%7!-wDEgBRs4Kavs4sX@d1o zY==L>yP19XtaJ68wZ<73d~F+~LP$MU8mGJS<;MYknyYV9FW zdDhGpubNFwfNXy#;o^WQ^4Rhd)JdsIm*jd7K2ITs-At9iClhXfNzvrbnc+_?`Jydtke}nlL6{oFoNpzGnEuy*?VAAypQk|7o=ebar;LL~e}i*G z&8@lF45r$e@_WlPc}cD!zs^;O@1J!NFB~lkcUv^kPHQKaciD3!iqZ?>xi>4L@Y{^}v^Do+7&(1;xixyDC3fs_$ylPu?s6N(oc40%{Ksk0u^DKsiVY_Y zhy6F^z^b&7u;WES|5VhICz0%_VX$U zK5NPA+$>~m&i-Y8jbm7$PT~0vs@THs6S}Ht2SqkzsKbUu3;rtL9+VINS_5(4=F^Ou zUnw~oJVWodaY$)#B~tzxhP%AXDCVIIV@@!uuk4bIu~yMwhF zEyD;po5KT$1lzX?E!+JTeY&TB!zbr~wR0pkJ)0m>81nY7=mYzL$2_7dde^k1e19-Sfcz}Upkbm0@*nO zC5JSovEgyg*;MUT*s7t5L&`}gVbns1)3t_>puupnK_0tw=fDV$I4nBcED?VFxC8gG z&g&?w`S1!(8+{yW-QP+vJAcvEhzREGj{wPuzJ^kdWhC-i&Y_Vf{G?mEU$NWzw7`O7 zQW^HrjMC{?qva<|x|Rb!62HSE_v5(4 zO_u4krGa8R2&S%hsYHK|m9#q5itqR-L4%OJ)PJcC=X1N62D-Xd-Gi!CpP=@~eHea- zqZq4{m$2$*G&c0|L1aqKZr^NZ5mb5(9n&0*WU?KMoxy4ve49)s( z%7uXLMi2y-mwS<$b$kB9+)l4_7J&cj*Hrkps zvQAq?Fq=-KiGLrhmc+{q;5S^o4L#aA@WxJ$bMtDZnO*_oOQ>X|S@a8B=8#7(G6jTA z)9MT*mPT{XB(p}i_Pq!GWsSh4(*bJ_K7qgNctbG_^>l1D5zK0n2d-=9-;(V18^AyK zN{Y`fJ_9R;_u+)#y&xH}YO0`b1pYD2^a)SE^yt1M`sb7Q=Mp8@HtQ8^abzL(6~@cd zeDJKy0DMffkYYMyM~*!Nv$McKl&U&SGN@<(uX3y}dv$>!R6O#en5I^FtU#n73W{Cy z#Y4!Go>`%Qjo0LWqEieuA7=vtA83)%FCHvU!bVZ-hSJSCt3XK^#l#X!u4=~^?`VXDMMrM7_XX*pa>gs(yl zyPy{k?w&Ubd(j}IBxxgP&6&)!MD)gu8KrQbRRcF@^v2D;W>Pm}5$&|JZxnNhVBAKk zOXl9N6-BSM;U{^VV|tXu=+^e@tZ=ev&izNdA9hb83(SHxDzaFRqe>%CP3^_3`-WJq z__!W!NWTG>{#oF&fr>bHOFFmy@=#7_jaL=Lq!LWRI!(!)3BjVOGdBF#w_--@n2C(i z#;}>&T4@BzC$JlYxWJOeHt>n>hQD)q;k+wf!6Gh)^GMd@)xGqvN>(uJm|>4^jr#%3 zlZ<(zgc^$ZB%1;m1mm*lh4`v*hNvysh95U-B=c^bC!Eu^m*%alhpf(8xJlHi@m~~i zY;7Bfd;W#ur+-0+by_D7Gns08{s1YKcHpBk=-Q0KJ^J~u%gmMcUS-A$tvMn)4zdLE zV!(BARKE&Q)?FLk=e~|~l$kN)9O=tu4K9MHA8#OWq5_^1p+sFqgpw3lXTE^VdLABs zvf?)rOy!lKc+Y-axbST{R#krpwNFR$`b2*tU_Qz)F9~L=_j&okv`K2QoIc^*Ns1pk9vtqfriYs(%s$_@T zF9dUaQ=oX`5-Y~E(S}!=aD-7_c@X6sH5Tou@Pe!9W*{VD3Yf`nn&{ngnSmwX$^qb( zl_t#?7Avt`vjAV-H%K~w*nkY#xDsMd9cBDimeZJxk!Opy%J zMKBxoCWzlAyE6GjHoUjAPWt2ME#~fqd(6YF%}Dk7BNUYQ|Ho9nqrEXk*Em{)iSl+OxYP)sSi)EvVC=BVtuF(eqLrN6~;X%m^M*EamD ze^=T6j$L66JzU0w?3zJp60ZTNL^b)-)@EF*Y6|(e|Ce{CsM|AI|DxEpoOqkKF8;)Wi#r zRd|PD65AB9UPV1!I%@|?AzPXb`<|zPT4Fe?Gd_v`OTEelwnyTS1@qXms}o@S1=(3( zunaSlV5%eXd_+`0hdY{s;vuU`~9e zYuaRj(OvgN%+Hv_oXoW0kB(7A4tO)&cgTos2Lb7L|% z8$Kj?Ff(b_F!pZDby22bJxwl;>8pSReVUNBCTO5GI`^V+fzTlXaPAMXL2nAfH(pMW zj#Z7t17Fn<)t)h)wXTtl%~07Uy@X)gCfpUbHjQQe-n8LgB$-Nk-aVFP_3n)Xagvb3 z-uYD?3!AhMQWY?rR=u$L<~k@Y9fbF5_Qi75q1eXel2qxyY5eZRQ1o(|9zJ+O78){; z9XWgnX2_oc@mt4{O!q|_e)K=+8v|GS)hYt_FGTEfF zF4RHv^dY#^Qx8|=hU2Z!$ef+2g-f+-!8VN)>g@lSw#MKq?X+zKbGu(J$=2(GnS0ST z{HiPsHes(1n_-m62xIdplGGz0Nf<(>HB0NLO`9z#k1UvKzth`nd^VV3rpabnB*9pIJ}3DW(Jd;pv*CAiMoYbB zy=M<3#Gt%+zhGvpGL9;!p^wG>HRUjOe?4rqmtmSSmg1J~NXQHr!Ed+k&p#Pr$X_(F z;TQQLoZ9Ox-EY!mm;{1(|0G#5wDqmX=-)toXkTTinK#3+-{zs_hF=hqMU?lXm_t=X z31sdi_nfYGAhbpZbj7V&j)Nv4=-J@Jf7@cmzc#Yw6`E}MXGRN156qygc`f@quM$k* zig3xj`)5SKr33kX&lTWh?_qNjF8}F0qfVGFPd2JNMl*<;Ibb?X*J5cgqio58Qcp&ex(;c3c z4dpgk?4$yinc=-~c3>b39~T4W-N8_Qe;2f=^`eFuuW$Ha^U!%r$*FSA`uPX$`Xh?IVO&U zrw>T2yPG2L(zJ%hZYo%i^Q3M#h+im1N{c3x5+BJsQr(Fu(uOw;V#~gv*z=ieBe0X5 z)3OLgy(U$x<7ex7EqEZGu^%(@Ba+z;jW$;w{wK73>4lwB6kvbQNC*s6f|nUTkdRYo zVDT9y4GP5~9Se5h>|>(APuwME=5lCAcP0Az;217XT2EVZLx#yAm`x=y;@83bAMTGB zND9*gF#V>7v3qtau|iZ`=(HIQ#R$K)21At+6bJ9n&TY!nGbL-oDeS*AknLeB(76pf z+MviHYjRGQeuZSR4DqIzv$Er0A;CCF;>GLsY{+!GHIPrceV6qt*uXR=&0>Z9W~?r$ z<7rZgy!HdHHr@7jT*8* z*B#lBql{qspm*ZC*Tk8xKMdp*l(b#luPRILjyT44ov(wv6IAde(^lkl-4Py|HzL)u zJ*c5W3EzEJ2zRoQF*ZNTCLU`>omcLl^g*&$sLgo+cwDs?ZOtrMJgt^sB2H$BwH7Ci zl~=amyZU8`I%5scNw*BPIkyIy?3J;OmNtYbxWUzUHR#x9N$;M5`XMkW4Npyu_`e6H z|AmGOV-MpKJu-dTDcRVx5{%lvJn=-6KQ8WWHvGVe2PKJ@AEF7%?yz_Dt3lpb2`hQ7 zgf-fsFuQFz_-7x5_xqG^rrrlQ8g>(#_}Q@r%a-8>QC9dAaZBjW+vA^Y{y12Cp0>tC z_TBUlOzwq1@pO|-uFnqJ@TEE{(7B30#=%vY>TE_@Dq;sYBJ^LEMI2y~Au3BkF~Uvy zVZ~LfSAyB{Nk`$K?;{i!kpemSesG4o942cAQ_L;dDxlg|UT$s85wWB+-_^3xhJO_y zVJ9EDLV{;bRA-~Sfaq*S6p@$qYAAe@2gXr9=o>**@dvO{y@7LI5F7p)HMrum0u7TC zqT8vNXms}u{M*lkVvfo%dIV#>;EuRJexxXN)gXTGfx~RLJwRK?6smq8!3R?Cq#XPL zn_-)C38ZWOgo@|n5<)KQ!dSTFO+&tw9(bsdIZk!JYQPIB?VYaY*`n0d0L)0ALt zuSynsAKoKc@^KJ<+vp?eTzm>Wf5UKsP1~m@a=5nr8%-z^Tt)=-!_+5AIK3uItBAc;X=95Uj`&Q= zcswa+Czh(0Q;d8m-K6aarr+$-u5pLNqBj=@^EdR1B=ur7SYz%&1u%JP-PGq+c#5!E zP)1v`8I85hS=~fOti0a?n|e;ip%a}cX7y)^aUqzm)$wB& zP5dsB+S>9SC*7G`MQf6H>CXia!)5^!(7%aBpoFIg!5><9@en@Gw3S!!VxQZL{N_G* z6dA+#Go$g8EuQ$D>jIqZFN<~d{zNh32`1vcR_0ho1!juamLEJKmX)slgp5DBbKlIq zL-xl%U`0Z!LTJdXu?#|!enG!Wy|9bzCs_CVB0jgan(=D=1KoqW;QD|;cv$;HEM7ko zJ7}6?a_E$E{zx&?2q_RYP5e zE2th?IC2QSgZ~dxXC78l^!@+ld7eiqbQ{f~y63DVG7rg=d7kHtWsF26GK5MJ6(STu z_ukV9p=8JqMH&c+NRlXi`|R`md_F(V<1f$S^{jpO*?a9ZyjNUJKJ0g^VwVLr!KFo| zP&>pKOTPBPYg4t@2VUFhq6LeXAika}$ZwpqJjg5+r4aPJ4Qa_2&cip#^JhuBrsq zATG~;_@BHd^HtGSZ#ytM{PD?reOz?Zgf|*>KTlY+q2d-;N-$G~a=xmGU>lLEnSe2$W7Mczz;5gP~gAl56NR6XGbddXAK=fxp-nPJKINz$j*^b$YMD1zBPa=5JOQ+K9# znma$xYd4pb(nq1waU2&~7Y_+#;s3>0j1%9Uvp+<_ud{EyF%q3$JUx$#+uyEpAR#>$EV1z{e%qP#;g~95e zINDL+CcnYVG+Bx>205|svUXxXS5-Lv1K5t%`>1pKrJDXWX9%X};G?n`0lk=@^(2|7 z9L0tgw8|Z#`^kED(V;>!g$@71{66vrHat4ZK7Lrs8YZN((fj|gea|hzpO$wO{Iz}P z`rsVP4Ke`x;}I0IRSXbk6HLZ*D_L`&KFkAxX+P1OHQj8%hWmAr+U0A5mT4ASyF{H@ zBZ!;|+TAYS&a*~0KCz));#s2|>Tr(;Wds$#e|CYjhtYV zwk2N+dEbk9zuKM8xVw;*DCuy=4qlh>)68JV`-iMhWFah?@V*f+FBjiquiyE>_8zsL zy}Vo-G`DTRn`6!MEWRGc4EJl&751hOT73^~R}GbPY7{NH%0&8`vnDm;d3pPYy;Q%fezFtu$+Q{4nq2V|C?}Ya35R9PjuNKB zLU+DTA0@7)cs$oL_#<;*&2cC{mJUK=jGzxKd^dt%#uhaaQr&nO4t_WZdA3Dh_bnRB zowg~mHXKB@Fpo=ceF8W5{uEOoo@wt0W)I3`MOhu09plJh^HY_LvP|}| zIEa`Ag4xoezs$A5o@ry<`SAq|i~oVJp@q1>Vj@5*gu6%HSHYfU zb+BwuM+o=W3i02!p#SZ0zH|E?!O`KIU-QSWq+Q*&W zlfIKn^IFR7yOYTXCGkRNNQgtjI5H@J^hOE6dqqFeZA@wi;wL*J%i7|VlsLTch-bZ= z58#P2H@MBI{V-KYOcNQG)6Y}ILRo40UNgCDx+$~H&z;vSJ0;DD8pZvapw0>H3ifZr z@Pi-@Y*SEA%Xx%3g+gd(ufHaKKCh3hL^&z+@)cHR*&z%pUC-IZDq(bS9$hrkmlUH% zFrWYYmEFU}I1o>V0jtPxZc|AP_Kc>+D!#IRk> zN3dLMg5Dj>aO(R=Ouzq~-BGXyD=c1d!x}oEiS`?cX)B=^H-eGoD#>qLdLw;h?9RX0 zUdLq~_Tr|5UT1_%q0oXQ#B5Zylfg}7r$ssa1wk`K_-&%RO)xmj5Sd?L!15Q^tYtS@ zua5DsW@|?@ydw(G9(h7By$L30p_5$eVX1V0iaS5rI*a?e&6xA((Tx>y(t-kvrwA`2mA<3prd zLs!0l;Aw>rrCCb_&xP4UBSY=+)_{LdpWlsly4j64o#@U#bav(K$lTmhl}9KB#P4P* z!Cdw@ESH%qmTHV}xC=NyUb9We#CK~0&lTTh|sxE0Mq;15;#Ak zKYV-A0g4AtqE$mbUEcvW$p&k#zkz3GA~~xh2PQpzJX7_)FK6A-7mI5|YeGfOCX`?{ zlsn2DQ?~alNOt8PKawc?4u0Tt%p+JKi!11=Z;Nt=-AQ_Mpp(@>d;0baCDHT&KAo_= zvw^}+=9|1#`i5Hg%#mJb;&KfO9Y#&2-tf2=vpb*-r8 zM(hb-Ci(fT=%O86rA@;RHUr+kr8oxlNati! zR3PiN+8)%v5iIMF^%>d)?Z%2P>2G4#?j*t7Ka(s!5{~i&7gyd!Z@ywf(n4j4nCx|ak!jPNJSoOY~T60Zw z2hS7C&$1NxhWN#D6Ej!dWY#u?#^~K#(swOZ2-^vY$|uSKpy(5f`-J8uK#ef$jDmr1a4Y7@nHiq35g!HgYoM6S-o$X~0t^0W3# zVuw9`$n94i#Vn3%fPzq>2+t6ysfh)UvG*(#1*cF<&CwSS^jw1LKmqa$HQDt#>PR|Iuy#QC1iM_$qI#$eV<=#$}t zqa#YdWtKk%ubG5qvF_~MKx>eG>wtsne^G04#hvzyU<`guk-J-*m;WR?%{Z?YJb&WM z23KS#1dK3&If0Z_H508{*KZo=wyTn2`glKw^IB$jv@H%|KOBRJXD*R%tUG3Rb;s0vWk+-YwJ2EG*E*sUHdKS414Z>$BIvsc*EvtbG$M<7Uq3$i)N%XRVjQ*w-! z)j-8vatEz=3cGb2aPi+nn95v*ejoL5eVz?|2{pv&mHlwhN_&c_6|MP5F!9F^`MRwb zEcYJc${&D-u(-PpoPVvt2|LZWOpl};%E12snet1b>FJr(^yn0qZ4PCTE(VFiBvmxoD_v@+OWb!TK^DJ4Mr#O+qerQ@pFp9FQ^=6?y1pVt7_cE|cWc}qfJMg&;YS@QAqg_X6Xbi^b6gLLb6Vh3&@+lL7PGi* z1d~4?K$f#`qAdBmE8o>xgJa(6z}b$wxbgzBp@a3&B;Xa~PcTBqp4wP`x&~CqTAbjg>0dWM zVWwA7t10^Px+rK6kBQR5s6N$@^zk2eF=s&D=XvK~%8t7*E$t%={A-SjIveHPdElET zTx$hlQJ)RL%n0$6MLgD!7XNkSuLL|}gWH?f+q+n*2`TI}p$1C7!5qzB=wZ!~_wd0> zpJqI!^e)L;wCPu#s>eQf(QpVHNw?A0BNANIyFO3J@GHd(YoeY_XM$n(=KDAvA1qyI z?8bLjs%Ae2hOl|F-YbGXyr)HdLJicv1WO!zo%~KE?_vC9EgDj7)U@UspLONW90-RW z*CSxSfRB*v+Z8AEaOHnq7K169L`+wLxxXgHSL4)1>DUf#{EEM|Y~k=!c6+2u;kToN zc6$9D{}p^MSfPHB0X7uAhnp)~!OvI$1+Sg?R9A){|LHK)rG>+styQr0NOv3>)Q^|V zb>W3Y`zw}@_9K`awOrq+1EQtJ-Q9Q-V{Pt3PjgZYnXSkjeG#03AA<_Xdrg8c@tfv0cHBU`kup z`=*4(NmF{d@pJV@aXW*KGNBiK$lWf5L(dDRNJaM-Fn(i=k?#!9HyDfP$f7e5Ba1?xU;K22*7e)-J%-eJN68&v9{Gz|j2!a`3Vd-n|D^c2qU>?Rh zbDy`wGP82jnG+|vLud0vL~rObcn-9|{p|*rU0Ds`w#(tQr5>EO(qa5lrf@%dwLsE{ zF!(*}3XJZ@V05VlH(~NaUt!T!{Gpf$1fyKt(RV;by42Cdjkk@z$z18slRdWa1Jf_> z1sguh9s<+qVN9b9rVJrk_oJ&I)z1lpk>V@o*|Hg9<%&ONNStl%I0!S&gaJ(C6~K>Dh9TBbY|}DL zxH3A9y>8J0t$(fHVOlawT`>kPZb)X=O;Vw!z%nJ;w6um`Uf;Rr^N4#XogpWm=hO&p zYE~qxdM1Kh`Q|oz=FofA=FKNqFw!39c^V=6=M^lJYZ3SGJiDh=6T$XQIhldD{Ba^1=cz_9YsKEEEd*mR@L;ZU>St-{0pfCW4CC^gwzI2KNcVSmJ*(yT zn~geE2bK@*aYa`na+8*W-ZwK4hHd>P`;@G0iPPhBAh38l`2Czj`=x|`6SlyJcDiW0 z2}Y^rxU83@IukvYI8eQsxEDviu!cu2u-^jQKy8?m$QXTuw3!{~qD?n>3E`g?!exeBOCV<56m;3r0S}B@K`{wp3)TUGY1229mq%DKZv9+&uc;ho zV6OuoZe*|-;d^0N?GX@UL0|Omh~sMv$s4p3Oi035D1(y}`eDn!1Tb^-AZm(7+5K6Q zfZsh6tCGz@Wuut%$`p6nF@kxZ=_>bl?ZNbGcj5mUKV!Q@J!b>Ymaz%*?nCIoLJ;)R zP6s(q%+2x7A-CUSILSSP$7&~F}IY#(x)`(l+62Z*ZZ<8%3pUoVZc!_QEd^mg0zU7KYd-?=j@CtziF{G|aedz@^jO&?>eoe!pSE z=Ct`hTF^!;`aBM-9K_~wAJLjzf^jQj6@Y+|qa@$vGu!rv$u)?6{PbD9q zh?Ifo+dAPiI|Gc6K7hZG&5&c&2J?(Jpu$5Bd&LaHDcud2+LeZ2E#HBc_gsbLM4d#i z=Egs|({2;Yj9v@me|@(xD|K9Wr}+z*z=rSa`25E>9Fv3ogB|2gMWa1jWE~1){ zj&(|SNo6C35CJ-O*#JzQQmgo_u!cjXJF)lM7$_j)ECtL(aYH{On8G`w*IMqNB1kye2Fr+?Ykp7!eylJ=+aQum zk;ijkY8DVyABm%W9)_dyMeS~9ai_f`n2N$4a_^8>#$}g;*S)%fy<3*XhA+Orh7M|i zj5N}cO^RK-Zg$3zCHi>5tO&ll`~~CVN;q^2jwS< zk{LrU2|x3NecqLfN36&0<+PSVShSi(qHB}ujBB?U;Lofg+J)!8UKNv<9>&kR%&<0e zWS-Tvn|bL$E_vfRu4hj+{bapOPE$;nc&+^;m{s!?a-%2d%w2m4U$j&w@0DQ{^V6@C z$=?1AbQXRD6(R=Yuipj7ej>wy-WAbU=jK&vq{;sfK5x@P^ZGA&56CxH`RaR~hjewG zLvRzj?!tA7i4!qOR?14RN7o&MZ`xP_|Neq9Zlbq=E8itjL3-jT2A9>DjV(}VXpS(g_)uM ze6xNguRfK^TyAmZ|0eWjKV?L6HUVR4WyIB|j#Q-3qI>i95|p#F!Dx5T`S8uPrASy?f65RedXv zHo9^lGa^{Q>wHrG88S|vp;NHRrLRDxAqi?fsNl|XDrj!714HXBK)tsuZ&oVh)3CjK6k;;pWfjFyh+Vyue6pzBN^ipRnsn-q1)M;&a7k)HiWM zyAaIR{!eAzY4MEC3TIwby+1tatE5==)t?nAQ-pEvyN3*fxer6&$Nr^o%)$%yuT;hh zrT^gOiERj`iLmqYLB)`}-rPyo8Qie8XVRK`kKtuk4-`%TGx786NiaG7)wu%<5}2H! z&bof`a3=1D>gOa}vY^%v+zb&;8)klN>!R`e|asBd_FiY`; z^MlELF$+URP`d8oOm(+|KHSG`yum_D#hrFTVO81 z^dB@%ZZ`8Qv$DH0-}*sMvAsHysT$QoE-1j{-u(o8{!q}18VtAly1~G~8z^S>hQAPe z?I`ZPB$ke_y`ynW#c&+)b2ZNFdJqQL8&S*%@w-`0Fo~%XKoA++t@kV3S}D3@w2-;U)0X z`WhXxBXoN0CDoBiljG1o=s64}1B83oypk>{FaphI%Fs}{50Zn$RKx;t(Y6yz$L#~; z{!`B}R-_U#WbG~~TPtCCi%4$rTXJ)fGff!3yV&vv42ru)=Mh}iATpukl2*w(fSKoC zz&Mv+Ryy+4Hta-y(CU=c9-}rhQ?AG4F^&feP`42{@e)#>k74DpS2qv3b z=x_6WOdFiG*^K4&QBa^zM)O^lz-qM<#@F}4#F9!VT{DbgLPX37f-(J&p8I>*NoESc zDA@yd$7KnpbU|4m)N(kW!)QHmuQc45(k!{(pTI+TPbLTM*`^v?MV8%H`|S%f{B{>}mRur9?M7BN={X2zif zvK`@x%mh-a{>(Xxeeo+yu_)M&)4BQ;qB6;>h%5~%*=lf)94w@PS!l$xzNUn~#?Hev zl?R|{?Kj|-UVufBU2*PkSG;=g3S1~tp_uC;h9ekJEWfSQckm5d!%h#sXc#D`P1atSpMc=j_ zM;Qkl34h_!W!5x0QPFt07bi?t5avcX9@58@FX~v@s{*|%FNf~RHJrq z>i?9mr*1oR*<*-}!%5u}$wnnk)SyYPG$P}AH<8R33m6E;+yY4h({3m}WrH_2w}Z#E zYrwyIOfhNVhJH^l&-%Rc-S_GM(=SlM4}zUChxwDZf%^kF&vaD`Q&K|DBx9^5LpFMD zB-2YtSV)*8n`x|#iBolOP@Dx+`+LBn%xLI#+5qF4D~K{_9-Ll&hhiecQ{WrH4Apq# zYg`w@FsmheR+<@?89S7_e^$y>cOd!!M25P5l_|QiI<)e>gyhl${WSfjI#~Lr9R@q= z!yR?vWv-2Z+D;l|cn}Z07hZ)u>0)$np?Kf?CYXR*cYSA1+|8`mFX7*hd(9c7ZQ`_? z`*F+8YN61PfAN_)x}MZUq4B>tM<16N>Y_e*2x^{efG%gvASZ^`@?8wiikG@V(olUtZkcm`G2~c)C8uoYg>W66EUE)d07X*2GAXxeW`{$4Od7 zXk~s5yndy!D>8K0ff-StBYz8z;$}d@uZvK7Y&XR;ih4Fy1Y$-0tI= z(lBdFtSHq-$D{VRlYF8nwnVGT&ldOpCYW2M=(OA%PCL(J|CY5Y+G?{NiL`b_OBEA(1mi2F0`acj6SX8Ds^sN?qk#rzJ|0+*vV z*p!c6-04Ifj>Y6dK%W~5qGb*>XKX0uhp5*%onW>rgRf=tGij5m3*Qlyxh&;7+_)}b zjDEB=j(KN@+P&@R7MMk(Sa!|tfbka$G5@A1-ubBqe!t$bJ(J@UXBU>i`+NDYDr5pz z`<#p$f2mI~e?+~`g#;7OyTGSu*%j&iW(ohR?YUxv!y|5CX({7hZjH@7jj%4sj&A6k zYc=rH+YY$i$`DgLOz}_lZ+39sx9rpCU5Y~+-ouY0x1ja;a?UWK9^g?2idiTsTm}=& zsoq&WQ~n;5HoTSaU0Z^gKG_P+=|TmQ-`NJ0=NaK$O*`C7E`$9f)G%^*N4z$|09Vg7 z!47usS$)gDtc%`v#g#?xpr`LsSU7$GcfM~6v^^2qvHLpEEwG7TR9x=)?3un&s`pgF zw~zIgr@c7OZON>rn7D;T*se{Yw&%zp&uieAxg9YwTpw>_8RIAW2DZPAIV3;LlKYbu z`pEca;MqTla|&0&zd0hNmxzfVn5rM(W2M_qdMZ!CzfF3r@c4R`+woR~{f{;IKdsR; zOaH%^X>vV`d~8I78UCH}4#KaOz=NS2o z3Dv67e`h6pVP2Wyo8@tC?0y3_tL*=Nn>$v>gz5bkBdGR{|7wVvjBR1umLWs~SBbr( zr-$zzy?{m~p1VkH*3louG|@vRx@ZXkW^zGpd{~> zz9GE`)OYFr7bD0U?)+|mZcc8nQe!fVVglJ_P4bNyzJdd)wcNW4+Q@i{N){u#P)sVp zjJ@hB^T^Wny&Njx?fYmd+2KJf(?iY|+EqDUNi}J~&g%1%g@Nvr+b7$>iJ@^CdjvouZhc zeuQ&UQDzk$R_N+Qj!D)WTc>K{Dn^#ilpTflL6A)9#E1-q>!YD!ffxa>j;oPJ9bGnp%j z(cdJPcYpWED!r;@p1$O}d3H#?cHdD>!=aoJj!t20^~OIYIA@k7KDeol{zE&UP|l;A zqJv)#N#P?y5-MgTtl^*Ts5|@%j4u7iExTZinODbBYo>^pVuFFR!?KSz9OX@J65ey< zGexfK5ce$T4)b8E1-36WK<1+{7VOZ#{8-YHTW61gI!{52Hg1*pLExKcxX`tc9nhmU zUNLHfM4eCEFES5jOSss76DVRz3FfQe3E9w%qvT%J5?%quirAOiIM2p9CbP~Qn|%zh zRc3_yPZBxm_3Ai&r#;4$s$=UuEj+3=9yT@}hV$JlVDRBSm_!Pg=JQ{;oj2{#W7Q;T zjlPJfBA6ml9*`LnB44CQcG}!~3Y-?fb=JAdIIc8DVcdHU&XBlyYIt?JI)bA;s!vnL z!V8-C^~qc)ArFtWLKW>u*fu5HrC_SXiOg(AkY)DG(^)$qsz4cs?>9@M6j96_54Tu5Ze z?A#`Zh*i$3wCIQ_V?}F>#OVq@2*&)@580X2lk&<2XI^*LV@2fLVcgPX;mnvxX7u(f zsL@B)yQ7yMAl_^(ARdL;^Z4f>B z4BVSG5L|2rU>Ec6aI&qH8-2wV&kY(+f19aY>35@LLmHU38Ovwv$(P4h5{#R=%vk2Z zO&+mF8b@Z@2$<>xdZ=tAViq;pqEML<_nc(Zt+#?%=X9`k@FoKu{qVGRGyF*X%suk6 z$I^L|DW<9$#h4Jxm1a|U+rDDC<{Q#n{`|GPWPXccr2xilAYk9)U z=W;88nflyau`QEV%na=(4>2;OJ588~*<7naH}udcwwP6`inD&G;@G~sz@E*33k5?U z*%i_3&v)3>n;e}f)_COqwm^eujWfYa{$V5k`r)Ye$(nncp;JRP2_K?0}ZHo#0 zZoHgCjBpAtuC|!@UKPijRmDzQqF~;jGcdw_AWS352K}cu!teL@Ib#DW+;dKJ2b;Uo zMe9y5*QM5Suc&G{|IwNM7cTW}*BquWiuG13dt-v?5e69ZO@}U;aHe^_u|b8U8VXVM zgk90FsyYo=2Y)yn!Qk?>U%_Fbf;;=r6ulSCq`!?;Pm1v&m`@X|NDr$%Afy-{ma4^mnRF6v0 zjTG|D*_y}|4>rMoy8m--Ma)2g$r*1dU)1zo{-E8NPwVE-JexUBezWQr#RwOH{#kO@ zY*5AMy&7m9YJ)-xmhh4u_GTAo4UUJH9W2BYd103wbr47T5%2yYPS-H85pzf{YRxEu zd61|lpI7!l-i5rRqqYuY-u3S!BeJK8S?5i#f4m{q?$$xCSE`uuoxF91*q|TXl)Px*&n?5Tkek3I2)3h{2-Lpk9tIieNP|%R>`e+pN)WpE}0eRzXQ85*GR#4ZVJNL3$rg?0)w>{OL88 zvx*}6(b=0Q=81@zO)wvK{E~IEd@n!fEa79FNggLxlgX&KNHNXZMT{UZQJA8M40#a< zqH{vnv>5jFBx zy~t~gjbsMCSjv<-#Z!#q9}%-_C5e@N*2Idf)+kI}6fkeq_CRtTIdH7{!u#HiXkPXf zX1jM)w21u6ZD|*hKalN?pqM{>sWsaO=5*6_ zS>Myh4 zVnHv6pJ|TCzBORu7s zm}4x(93mLWktkV@2e;+tr%L#rS9UNXJycj7D^rRIOEtlrFLW@=QVWegXrXdnE1dUN z#C$O%6M$bMq>^#sbvk5F_o!-c`aPSSNHUAln-5dWW2Bhl1k*HXw(P`>8}i865`KyH zA!cc_CCkiHQZ&vYujMYLC=7ajaYqa7t+nyX6H63S;%S=b^kL{R!VAW2bb@&YRIw?y z3O0_3WIK@I>4ENIl%umav-k|b%(m<)%NU#~*IFRqt*#woK32J~neHd#BZ+o^f21j$ z!>+oIIIJVI@%eH~^q;AN?Iij)w|_hYN2AB)Z;ZaA@3ncKV%{FvM20CSnl9$O&eFT#-AfZJ&JfVhO*` zaX)jyVh9^>PD{qL8{?vmW_UGO7wgEv6_D<`v*{KXlcr0L&NWj{!qnr2;IqISMisw< z7PA-NdQ=@2y)1^jW2dM!7DFiJ4#8YKI3c&I%U1a&f>}3j3!~I0knR5VqHmA;#u&2L z427xk#y3RFK|c!`8WJvo_@Af1b4@F|53FEN;BzP}e+89pmauJl0j!-XV(tv3n8yV3 z2-n}R?J!k-fGk>(;TlGiWxL)uC{mmRyyQNTTrVOW;a)LSX^{V%+VSVJKWD6W6hs_p` zb?lH6+oV@V8KY~x8Fe}4btgUnS+v4|=D0sepI*|2?b)#8z)SXLlsT*p$RnDo<Wl9B~|sk3}|}Q@8VUM9#Ft;3^Rh}Ls!6}^K&>nEC@oc(CHH1lGl@d`W(sT-v1~a zxyT69dYYp?S+H4#h7=R>-jqh5;z{ez4L$`G3m$^4&Q|C;CIJ@5 zikOfw6r*CRthD};lCNIpp1JEMk^825p;YP{$-dv(B=uGoFzW}kG&6pblC-pc{Pq=EC@z(lBI76#QSy~E#di#qkTUPh-R;T*JSh=5%b`W zKGx8gUeXI?WQnx&mMT3@DRQqJp@k0yMg^KTC;uv z#W)bmXx`TM&)jdm`-c)=VAMw6_zk;QvtSjbwb6iDv#5swuJATS{fAn(>bWs$pCYG& zx&{WnsRXyZL)k?JL||@nBpg&OhLoZNINz`nOmfdtYc@`#7&n4>y2Z)&N8e7;7Sayl z(mG1&KXnJ2Tcg8NtPwGF8w@Zy#~785Y2m~mW3<;a!H@tA{C4p@q;_&+gZi7o&uP2h zmv%9HDoTaT*&$H(D2rnD2T@FKf|=9O#g|<^Qu>~i@Jic0`&wGW1;e%Z!7@eqrciS6aZI2=B{)mq7xo9(x?pjc;JPq4dlfGQJ*yfWt znPOOixmV%f`+4s==@K6a-@u~$=d4gRaDKJaI+g?=pO|6mE%I8MXM(jI$R)kr2;bJ5 z(AV1i9w?W;7LTJ8p9&$aVLzmat)S9}f6f=Zi289^-9`3bIs@6xs zACuK8<_=uJ9(q(FRrk=RXPP=GQdS%x`gPAVQHZL)BAZ&sc-Z`GhZlx}+3B0z;pdlC z5Pkd>=p4HOI*AiuFDb)PB7ZharG5_-V5a7^3=iQ_LEsi6i2PyYB1C`avJq>9Gp@mgYlFS~fU59}4f! zh}MjqMKMze=78xYpI!T|O0Bw)owg`hakqLg+jDAy^g$0joTFie`Ywi8LP8KXCTQZ& zu7+q$P6EXyOnFWuKc-{p&JJiu8uy$PBt@*XL5qN`lGzv-L)w$TDdkR|&t`&`%LeieGZv z_DJIcNE!TUa=1)0#P!37Pf(_Tg`p%)FpM0Zt(w?qtdC=dEoV*F20&uda@ZKk!EQ4J zg#7e`#0lppX0?b3C71wxN$&MwpQN26627Xhj^fR(;jGl5yL9Jg9qQRQt~SKF8K(5% zp>Jz|{o}|(-b4$Zl6b-E%>C@>6Qkh%ktNWsp@5+;m%Xozpl?3)?0WAFliW z>)w4FJT_Se5{Da*|5X7e#@NFEQ}J4xJD+0q5=@ruqud5iV^TUv_|I8G6^nj)vd>)R zOA8#xD=pXrUCHSzV1!3uBe^-pR*`Rs#B98q&2Z?6z3kIxlcDi(Fidg33`>*txOhB%u#}Q{Ln&{=%CBIbCmFg$72<%YwXyMdUK^&&$V%$gt&wxX0t2K6iZ%_ zkOPU@PHHtn^_yBaWT7R_t4L*&FHZ-i(++SMngtoxbHJ^O4V;~SlKwWKizwzK!RV$0 z$<_`sW-fP>@cok?E7nIFut)EuO4G=5NO0A?UWk~2v+7t$GEt4@=6KeKL<>(@;W)Qk zcFBfi@Oj`47*>`A2VP`@{HQ7n{3iNodzMhld4d^{vsc#rwFQ%AC*cpvo+~)5e~i!k zB58b(Hu~>3M&_G{5dvLh-ul?w)f}(-Y2z(dJ8WD2l-<5&6|){Qgf106<%xpP9i4XOdb2%lTgttbG)BUd}PgYQCiU{UdUa@S`-%d=7p@hGg`dYrH*I6duj54$Nl@=Mb zYlLIQ84=A5Q;e@x`!DACOKntS+u``T&)DcCD?ry}4-7w+2?@6|;d`|@WHpIBg_l-R z%rk=NKmL*I!%t`Cx3+}mmLBq{{kV=fH_n7&^pA)bVW-92`yZyFQ5(dn<|& zG9J?+jOce0dH8>r+D`u5A#K;gS!H4u;S8p_E-60 zILySu?uty%?{Nn9sB6RP!EyAr*}j%yz7vdRMy0G`s|RC7Y6nliT9=amOT9JLpI3z&M;AhEZUT&3dkMa6PJp^@hOp&lG{xku zrMvZ|H>kMdou9JnI}`i z6-ti7eP@!!N@1rB%_gBCl3Eq6wN*VyktNBn3!kTu$X6R|gO}>{!ANHj9NC--zj7`> zQOiLXYGVvNOT@UqqD>TIL@+xqsLM_KyD}4q*3hF8EBP-6J=r&HaSI3;4`T=7{?(Y^ zGHW#yPH5qoH<`mo_l2NglmVHaFTu1?`(Q*LGw4<-22-wXrWhN7IdoiG z?$_qYw7wxKioN&AS2~%YEp&8!cqXi2i`gD;q2m%h4~?PP{yqb*_oo|$m=Wfpj-=fEv8vp6@o zC&ZL)p%{gT=}IswvbE){i#(WjrOtd68D2m3!B=^AX`FN|IUa?uog>Ld3x1j~?%nk$ zNlk1LF~7(iwB|ua=;c2irfXzFzr&=&s%$%$+VzFq8^u29i=ot-egspnR7>9bgBvsO z8PQUWwvbl7V-(>&j5KMLHg>TyMAvX*^zJKSdKD25w1*kG5;UyiLGW-@ z4t!Y1!M``_Ah_!QxHf7NwI*pJ#rP47POQ4TxXgw5^u(DzTzp7+`R_c1(#v$;Ou05X zsv6SDloT5hCc3JM{^rEGf5d?rr;8td>tW|!u5deNI8;m`r3m&4IAXaD{=OOvlb?l9 z%o%YDj3Ah0vsL8BhdDEw2&U&zg|xU^f`Wh4Rd%C6#PlF;dK}5&2$=CR4bl7osZ=4> zyb9OCU9&quWa3arxF>^1?L1iSvltwmC&H+?n<=Jw8?|Nv!JK*eTQ+kZql@Fnh|$1*PN4n(!NZYQmNH%vBMyhG3rAJeD2kVaXVi1~HAzW0}nCZ;ELR&GI<%ZTtr# zyw(J3I!-sj;g5(@MSh!o&wc&Kpwh+v| z$9XcxnI;ThMTDD23}&X!Xi-?XYbesTix_`p6I?_N90AkgtoV!)Fc0)T!6G#`n7_sm z*va=`Z(AwccSfk35ly}!@w?I9Nin+#W)57CS^DWSD({Inu-Pc)RiZjKc!jZIXbA}i zDI21InbBZGF~V!jGtdO>Nk!4=;2H=R;troDn?npf2LI49_!%k%mCFaAZ*LJZHG*Oe z5KQ^9B-z$_P3BX*GoQJ4Ad~t;mD7%MR1{k2(a%%BOd^+oa0-lc7T=!2ndZ8z0;ET~ zfl;;zxNDZc{_mvGJf{~F7RN&wsah4DQNMRl%rS!Lwsx<~IzfdA{O-(e4d}_3ger6G zT_uW&P5;A;JSAeLts=XQH>M}F?!Xt&DtCo7r}QA%p#&BWE&~Uz?vVB|0fLBoC}6fm zQcOC*3@+Iwt7`czJ@bobsRp?)#(%#l`n_;d2(Pssqr^qKO8f!g=$sWrUex5TcCHQ{ zdin&CPkTb{I2AZN=mm^ws)Co(Tw(UaG>BIhzneW#6myASmL$%T4bJ-})&A$q*IpRO zyxIOmaeR)eqP0~I3m1!+v&4xKE`nupV=}yj#0AJV^>%9^EHdu_#{WLC+52C@)iH0u zU$-+1jXe#~-$ZL3MpH~K!RTKbEE`t)UK*oL;%TuHnCLx!6@zDVRAl*+MC48plSEuX z;aUr6AmML4W9kd2rRRf*dpD9-t7W5myo6k}I{0?e3Fd2M!k8Um@E&$k%x!`>_MnUG z<<-~H)w&XX*|q*m@%_Jw0iz8R#_RQIV&%D-3C3$1(Mx)V11Y~MH$uU)*_^I`lliVN zy|#pXxc4QPY^o!T=bfQI^)eU_5q*IManT+UOh{~d?xe^kQgveqfBn{CCbYO!@jJ*^ zVSiSi`U1i!aFDp`g3BS)r2lrSNW4x39E=t(=@&5+Q$sM>u^V$wmnoz< zHWEHy-yCMrigrcCjVieiOlkjPh{8o6#M5?eR>Qa@By@b3X%G zH6+}gLODnipIjo4zgUNwn#$&p; zXg>+YP&@jDqu*I+Ie8R52J}q2Rp=YHd)RYYgvc^0Ew68IuKD1B?dDcT6&yu@FzzA`Hh;yf4Uali( z^uEaclhuIkkQR7OrqBk56+=%a5mP5(IuJ|sM$uhc%Qv1U z!_Uo(>BD0I2@eSwb^#-lDAu}b;qmHZkRNh@wbReDAI;yv_qJw8O)-aos~*9XrD8UU zkEM&|LNLQ_?(@m_T`M&si?;T9gjB7hNOAp-iM078@yR@mandq!o)L^tnercu5VJXL zehQ}CvxbygJewR|1EZ5ky}%H2Fim&_8~VhP>ps8UT~?Ie-A^(9i3%uKZrI)QGd|9)S{L8mpirhYLDP~f$F^xb8m}+MYT=ZC6w9Fo4%8y+N zXjWPSGwUJyl4wFiS2RNEVG}5R{0QvEh}P^mOfi!QX0gj5pAo^`rFP~L{_9UxzVTgz z;?A+Z6eEO&tS6Jx+1L=j1ZkjUv4}aVq=^GvYLs?1J0ozx4s2aJ}d zH+m?V^0g^ubF>Mq8WJ!-ggc=fgb za!-f}$f6{6|_Mu>F^N2hQK z?A)$_iDS}X7@6hyHtY)x}6n3h3Tz4xCok}46G zrb>K3b z(6xmi-7m@xjh{p7pM@~9uqkv-Rzu!ZvDh3Cm_3Mj@+Kz=yOpwDpJf_vkESs}o=TQ& zUq?aPT5}UjKAK_44rkj%g`pG+P&JA$7P3fa=FHHQ2HSK#gO zU6Pu8!IGK~#C+d4A$m2Rm{Mf=8FC$U!}r|d<-6E!%bEG zn7yS^#B8iYQJi+Ky@Be$kpvj~*%~^pXn^VM$55*G7%r5yfU=6y*p)=6(LW+#Vi8mH zp%yp)Y0GM&ajchVgP4hvWr~ePpV^_lrmFj+>Z+_)no4n6TC|~xLUpRGkqs_zQ8JX= zst;b1tRX7*0o?DB4?T)nLHV3x(0{=;Y0z8*CJ{03EgbpYT{3n6vm6zdo5mDv?yF#q z`Rq(xj5=NGsv1l)RZ(zDZF7cU{QPZnCwCWOm9(a3cHP(k%nNjW z(luu2v>-)`xSNd5H-nDVm8!TGa0eyKnR{4T#c-W4kAFRZhusbDv%)EvtXc#NVZ zK+S_{sbU!B))15LPyqSY8-XwD2m=n^fviRukd>x@$$|d(;G@7yJuYEBBIa?@Uf!?A zQ1%?(SoyW6dd$1mhZMp2`&eA1C=-!IaUrT844tGeZW5TY>OyE$SPu%ay1}LDcc9_r z6v)XP29M2sp#{F1OQ*H7CnU@d#Jp*8jBhlU#9k!IG%~L|^`ZBN6ie^zW>?dGW9ae) zRSKzu_b5wX794&DaZjuuqKX{UiZpm*mI9~W4uDHn)SHljh&T?ajKbG-$a2AK=Az6UcH3`Iap!nD4o22#3Iu0)|*SoK7;&@3>c6JT($3yv~VxfkL#iWKZP^-g*8l(8{aJ_R~nD(t7 z*hSt3U(XmgKWqj#9hd}@yhNPlDlm-^GrlsOzh1V5g~iG=RT}Y_rJv&!w{9(Fl(W%d zsB@CXV7%pp`828&KI>qh`nKv9tQ%1SR(2l=BP!xx*UVVZ_{@MV%}2t`b3)BP_IkXoh*xEQ8h^)y9cwxut7cIY?e96k?5HR*0IupBG3?t^;cy4UfYY!nuk;ph*{)u+!3@bwG=wwB!Mgv*q zaDn-b-{#sHfuUR{RSIeMG<8A?sl5UGTsaZoNEEzKa!7Ps3Qfj4!{fCAbNP&fQ6Z+R z&I2A*}9p3qzdliPf*$ivOwgXdtfjM+R!puQT z9%S=}1-IGWOES&a;#8-=vOGoC;IDGZL({j>uWu@q@CYLnB*W^ds^V+r7H=^_xaG5Q z!p<2`Fzqy!zb`}8PeEXm&=MTS3yj`H3FD5KsDeyB>qI(pz9`dd9DkK1IOi*j>`LX^ z;WuV`LS5B;^bAr7&-!sa$^B4dY^sWX_fA=}&LoJadKSL-jesG6J7BO&3z%I+L^k~| zNtjiLS?`;{Zw$D{1!)GMx4~4wh9S zA&T#VWE(qx#s{U1V6IRTgqW8LZ}Jaai`dQcGR@)IpI9xU425c0oRbIEo$1>U=1fcU z2;lD7V3CQc6I$WO%Q5YisVXrnUHQ3UJRH~_4B;!Uz@Ywzp=_u%)Ndm&i2`!~F$?-f z@+reUG9SbYDs7+$SevAny2X^!ea{L#tkq!1adnazwxTvv)f;7^QY;miOIUPiP&Hop zZs-^|S-uZUpGCk1uMn`=Z3Pv3M6uXcU``-rPFfhh=~KoIBWBnrTScqFn~JAZbE4-4 z2{m-(_xd(8R$!c_Ume2`e0zvaYmjcL8k>Gm>0db>WKZ`(Zp=0CzJ3yxZ?%E_Wg*g_ zEfC-4JYw{A9_8g-brj`@nYOyFV$8|}h0e6yeC~3Ap{VorX*1Q$O@^w9kH)HgXj3F- zN_4Xts=RHdl!v;Gh38#&g5L@bUpXFmx*-CC*F=Za?F_D8kSYcMnd1gh!#u6|&*rykj?v?4gFEzGomL zp(#XK2{q@gN|+mnX*N87FMEIvF8tpdTYZO}U9VPzwCbQP?u-BWk9AcuF;vgYM>8Lu z2#V2cIqbT*s<|iHdCl zJnD$CA{SQy-#+220!}KN{Q9fM^+szI#sc?S*HGntHdCEziU*HPc*`r#Ty=A|p(?jS zEmioY6G~&95uo9Lpm#17BW1kQ;23 z>j}ky4=(Cat&Aj}4IQH%;M-l~Re!NWVA2u{RXebOWAQbaIJ=p{Uab4~5U{>q%$Neq)SP zaXIFy+^2@BhxvFg8F);|u+znZXIr5>GX`cY3`ftJJ?M-QQy}b`q~;A`79@=3!w#A$ zT%%-~75XVG!+w-vZ=}D3A!{!kaXqk0GM%I!jTdStHPjdFJk9lwD^qxPF!kI9-DR=R zKl>bXNpb)$AAuPVDPc+x;~&_Y4^J>x^uk!6y6*#4p3p}zF@5jf7&4BL8oIhj7{~kO zl51$%H4{~q^L}MeukMhJZ6#)|)mRc(A)jup@=-@%OiC*H}HA+8d)sSnbjiHIELBbJbS!#E9*)W{jANvRF8gWKyzXVB8r#`e)vR)la$du(u%>GeOlcMegRh^1f@|&I z!7yQlRf=z8g_xX-dc5IjOGPw>>JL9Sv+%y{S<5Fv4IOdGIQG9VCb_u()H|g7tA7_* zt{((oBm~*dETW7lW24FfznwOlt7Lc2~l=1IouJhdI!Nlhnt|}VQ{cXM+kNigSJFq+9Ad`--s7^ zSt(AX%QS5Y667l!+~lnqZ;>#R7a-#psiBK8^uM81;L9>2RkLmeDo6PhWy%{zaNV#S zzCXDQ8(*J=;-rqiHi|*(7bSfgC&aXAug7PHSt)EXF_{w5jd?FQ6X~TtTunlZSLTi#4pnY=>;T!-cfhjfBna|7 z1@R*kaKuYEy0QgkFk+JS>F{PZtrRt|kUuANOjN7z^*rNfG^cHiGEn4C(_(0arj0;9 z)JT=oNndp}jw`EFv_?nQUXVXefYuXELd#}7;X;^LI&TZiSj5a-^()$Jg_UAGVst)s zp6dQ#wX)%l77*aSA8h+3<8ANb zFmPxusQe+8&c5RBISnz5npEX|s#qyLVTFC(QeVCgU&_vidnTulgVJ{7PkVvRI?CMA z?n$u#so6WIs%ld0TgvEc8B}x)hK904P~{y474HXae1)17;_tZtF|%h^=QDd+Dw6Tr ztVlS;osWmB7vPI+WPs6PXj>x;#RA>1l>xc!(xY@#X)amHqup9yf3-v4Rh|eYTY{m} z&4F;XxoB@#S1rx7Wr&ftt;;RjH&h(Wz(W482YjMlk$T^jO^lo=lZ__X z5djoo&S9UMXASQvop41SclkIx9FErB#(N;Y?-)2yE+U%+F%rfbF%$M%@}X}m6kF3| z8lx$vcv*-^Os~H#N*J;z5+-fCz)%3yyp~Wi$`?9122Df!rbmUZn+r-hgr7Wi5_TFNK<2h ze_N<|Ht831FfCI)4r&JTUY>_hQ7O>NW(&NzIt7|Kh!epLfjNzs^hN!+gHs(vBpz|? zast(PO$Wy;vT2|oCuBuWp@u?rngR+vQjGnj= zh9ymduj>S6g7`L<5R(}-hJS8VOYt2e8z=ic>XJb{V+Kw!SI{wv)X)^5R>z;e2#X?} z)@aa7#{Y!uiQkpZmNE#Kei8hhXMmo`dKkEN1_XT-dFTh%r756BjMsD*ZuHGmVT4iV zl54}%{&>A(^I8MhkVl-HT#Y71xz8`Z6(S1f% zoR|gmt0~9>C8?q6IyxZde{B<+2gv3Z98O|>%&j0v!~37nUVg3X)$C}CMP6ev~D}XoE`fCczJD@ z7}gjp12ix(A`6oAr^DibOTjW*sBwvxFlC6*bqwSeC;wulTk%A2Y`fZF`s|o?EuXU( z!|IY6!cdljFtt0@klfvbslBxr207J(Q!8ztWX?@!Gv*E~u^k7+k5_=xf7}mo2@Lbjxj`-S- zq5&8tG=Zdq8*r^O3p#p^hCBOL!6pacgxr@XVN4LCxwMz}KUvD!ZIo$F>wi(3jUE$I zP19M%E&%HMo>XbTWc+8^7o1}aitpXI;kgt;hC~ZEC)Yxt+hP_xz z)AMZvAKS&l^InhFVOtz9`amgn5E*7$1F&%>uhwLdQlaFx5E&{HF~E<7sPP@;BkLc`Yz4 z5ToDZFt;E6ibb!LX?FKFR}bCVImY73MLF5vXd|#*j@ugM(oi(-AStryt=PpFd}3*I@Gg&INTVKV^*f z_ecptyC+4Re`3gRNtk=O?_i#;1!TXm1WUan2?gL?R+8Wq3UZ`0v)bvHn&UVMR^Is2GD^yeP;|i~m(jcbY{I1*$n_^JNL3ca| zL#H(@hT^n6*nB=}nk6j1)f67aB*Xst8Gt5t_!7JpY{G?_&jK?XF>@+;&tRyNsCl z>J8+suk+PL#sQqvPyj^-55mydQ&BF|%nmS8?cDJeJc8@P;8>gn?~@?CWd>ZUHW*qL zuYp<5#Y{6xmA=hH#Dso5%tNwsSrATvIu8!BSaT}Peb8-o;MttCT3dgObO$Q znCy`|d4KsGc5;JE^StR+Hfquc^{L^Fr9ty~fP+>;sL^6*(CCN@^0)A&uoi63w}3r0 z6QG+(HcYJ?27_|f0*e*j=DffJA|`jqHhxN#&PMrRR^5ID8yLmQnl;cZOjxZx3Cupk{5-UUZ=ION zwrrAVK5yH@d>Y!S69b+}gGLy-w?^Maiy<|H>FZkrFM657hiMIA!sd9e3C)H+_eVfS z?1|g|s3_qz%$5f27-9z9^y9@hQ`u$QZw9^aV^01F+&4Hu!qC~1vK;qQ1V;P!q%22J zyCNuhPzwSQtYG%%Td=%a4%~7c4-RX*;m0f6Ev+sFBti7XzY?6@yKoY8Pwx zdOQX!9CG3K_Gu8d#2Yl-L_ur#NEpg;Y{v}L z%u0dLTH+~f*FW+VjJjd~jyEje;@TMC2eM!(UinSKzvufU;^0y1uB0XzF?KH|^Piq+ ztP(M*k~w%h=)-i{+egzXKp0AN(I!nvNQwp0g3MHenWlUN^KKi$kYDxTRzWoQU(AN$ zAa{@ldBNBbBDk$BFgb{E@Epef8ko)^5Hn$9FLwH~57Wte(~Xu+N)1ukjxe|F4W)Yo zw5^fVsz>cNkTy~Wa$4KK(*qp#ZO?{%)0V;ErK@35h&T~^6qv_|iFx0f5A1%2^+Qbi zR%@AYolEFav5+w27uazAw;Bqdnq3f>UC&>^tFkK4F4P*<>P13*j~tklwgS9MykPt% zf$1kOMTmJetP9`cpTRP5rg`@9WvuEGrqg}7e8Yy{YA8;lL8EYx0w_{* z`x?N^`B8B4ayC3!;065bD%h?Nn4fvlxA}yam8EU?ynswr6)~;K9GPbRVzw_UMcSk( zJ6OCOjhB4|M!$*(2OW19s@}%Fhg0xbnS9F{#<*VvrEfOWa$F5|%a+3qjj;3Fyf0zO z5tFsnp66f6Vm~ z?1k14Klc)>*qi~brR$+0$rF4ginAxnmoNs6ut8H@Yu>Y84r`2y%`LEy4;#6g-O8*k z#c6aAlhjactwUq15#Yrby0JnSKbK-CQG8Mk>S+UNycRckWfq)`@`2ht-C@89abR!# zK*H2Q%)M6@eB8-g_7U-=OZUi4^tdsv*ewOuJ zTP&v=lK;j;9To=2FMf{X)&^P2w0un7D(b(D~F$<@NAJFu#5{ zEdP-Xe^qV9a$Y`##l>yd#>ENMNLuXGK zG&mY4!A0@DLA+d9_aI=i2-2^iV*>d`{oH(N)MYFk~xkQ&cbHB^l*2{m+Y&84Nl zoR9wsCrY0vEnH-&)p6o1+!t8iO8qf3d}&nRIh5mr<)b9VhjhX_ci2} zdvz2+kMtRxq_u-a*24JGRi~GvAXs=ql=rpX}odTIHx51cNlfWiIV1^4d^AIy2+MXx2c+0AK zVPq4StH#dF%&e0U>lFA~jTS@2Vp4N^wV|p_YB@gXlB>KM)f#?`35DSwli)m7vX|W+ z4IQGyw^=AKOA+(LtQGIQq?oN)A=A9LS3~_K>OPyXw}o`m>)&b!L#ZJew48c6s@Ki3 zltwe#Lg%}ouv#7uC2Mv+)0@v^9unU#l}8dg231TZYM$tYCF$$z|qU zO)jqd{%5fvHMFKtK23{x5v!{*#+0f{h9gv)916WwBtWxs+rje0Xb3VE809kwvk5WN zCwAwTa!Xh*4|EOP2vIlQcbz@;vHUL#g&etQCQ?3))C}*atJ-Rvt=#g`5w6!h3r5Y7 z!Q)~Oh9HBWV|OuV)TC_DJ)pb_R!x{1nj zn;5jf)m2mr24*NL^E!cEr?arlG#>Jbf?)ddAu#Elz{CkmFk-H@8N*+``N9(2Fn}_P zQcsFK!AxRpn0-&|#)BIHtcwxV_eNeyjlgrRTKt>$kG?Ked$s;CqV zbCg$Bbc2Qc&cd;Ww_u7>5QG;GhAR1Dv9S=CaKz+KozFY>`p)te$uu@Suc^!Z#5UO>OjY5N65gDk{x@=lCj<9CpQ=g;QH@Lc4|AAa$QJ?D{08K#0IZBW7>S zCA{&%AIx^4OcS}Y3AY*kPQI#+N=gv_iJ^lB4H{u6{Ia=b5F1NgMxL&A&1I zUQ|^b^t-EUh5ggY=7vFQlbbNI@iqvw?h74y2{pR}CLJ-U7uNCls&bY%SEgwg;HG}? z)r?s%EP-zYP1-d0)JvCR1e0dd3QQKR8DKu6PoS|gPzmk zpkGoT*qAy44;Hp-{}le}5Y~-$dd?OncV?Xz);|87VM2jWJGpw3}a9qodH9il;SASGCvr6LR%Nr8ETyLni{lP+ovmXqwP; zC|ogGU-f)Up)%uu0*N>hv#B_Wju%B67muHWu=mJlYDa2ljw3dxe@) zFQq{*5jE9(OSc8B-2V$> z9gEi$bbezln(C>JcKEIg+SD5k-4BD1LpPvKb3gbV(H**O78AN@k)*}}F+Q6P^0V!9 z6-~#;GcG)i<)WTRDcbu%`k?NF?|fP>_-1%ul|x8eN{ zf0!`1JAAhh-^TQ{glUhM&+Z5LMwzan`Y3b_z52{QuGVo1(sz+Clz}1)1yGc>qd1K= z0!pTAABPsjsGrKhj21a(rw?!gTU|w+5tvn< z+9^6!uaUf03v+3OCJY_e|Bczu4{ZtetEz?vmnc7uSHiN#=ip0CG{oxp!LZJ~;PYGY zZ3^E=YWg5%oW(xwT1Qv0ewa)%WAre-w(%9YLlZp-L)k&XP;g7RPKu!^7NA5|mo|E; zpweH;MO6WoEeVHJmbYNneLvX$svkJl5*Wv~5@sl3q62pG7oT+$pN7aZ&6`YR)pHW% z?Ghf!TTiSeB_a2J5t!Q8t(PzqKoKU>v#M%`V~KLBl^hI`&VzbSBGf6^1YkZ0R+foD zTQ1a$M@+)w9emy`9Yxe&^m6QM%9eyTS9>=$WuADUuij~q8lo~0<)O7r8NQ&Gz$8US z{C=9Us&biVl$Luw9>siKm#`=&H++!^kizW^gP#6za#CfGA-2pB&W6MB_U zvj{O?er(~Y7nRI+piFZ$Jyh-hS9o|&4>^_av=}-Rl9z)T&CtPvFvd2zs$7pR%Cqge zfZf_laA`#{9M0MRw@ZdYM1Yvk2|~>Z#N-=q;)&V6*y{n9es~_u0-n@R+r?W+_EEx6 zu9Gkxqea^sGQ$$4#Xi=B)?!qZ*|lw=i{uR-jAsgwGtO;9wQZ|b=THFRL7!U{Fa zpxPR#nG^8~5_gv=Zz)@V?f$FKDJ%`<9rcBW$>TB8Auuh(gx-Ugbs=ti*tVZ+JYw8F z2C|b&W~-;#7DSV^muduO@QRNXLwNx$=4G35s1{JFthTxZB#gZX#skt|ThTh`Vm%Ya zz7rS^feAs3MfzMm%<2aVN6hutz^WN+SBJc~6HO&N!cg-5PYk6WNX?M^@344ZsdCb; z)-bfrMYvHT4NkA~g=TqEp#K4ZnI|xzh{@eIjk`pYF~FIIP3f3H^^NLXiU6r817XND zq{V2HDTF!m=m*?LuT++FZvy$PBB0;0bZDQq4ldQ20o`VaRiLN9TtSTaz45$5&2P*I z|2Hk7S27!AsJiL)WKNaBYRd$MayImBw5cIV-dhd+0<%YcRkj@H0E6-_L67KkC_3*A zC)dx1$|CXiyep;SS^mq7V29b%WPgHs>ofw5FRVXeTN7nm%a`H&btHG z5BflOorPdKSqvHo%tOQ^ckaQzpZvh;<3`|JHHo<|i%{1}cKaK1aha&%k{U`vQm&KK ztiAOCp4Bf?e(G!oYtLSR*RI$x;r<$^uv-A@7YQ|+-$@%mA!0ld6#R2xF{?Ek^J(`$ ze(z(Dy5pm}oGOK+hDvy(hA`Bch4RpZ`9AJFOm{0&mT$3w#JSgCaF0yLY2XEMZI;4` zP6AV-Si*cnOj9=}eyZ{`#ffys>F44&WyVc$ynbCh1B>$J1Po^KBe%TM@#cFn7UG*xA%gKgbk#5j^l`FPr z5o(4AObx`es?nYwz-|eFhzYak#QjR#$QUO*VeG? z#x;od$%cq2p1>x%!u%HkBNJ1=0x?fdw&QH;OJnw*C6U3lZ6BD{IVy5Ri@`LRP zSSOqU{TIFFHPhVGPcIb9>Hdv&roF8AU18T^y1TrAHVbtiyq^us_Kkpr=BQ@sGC00t z36v?tnieS3v_cG@+JUdic+N8L?>TKmJpcCDS{=Npk#x<6_8XeeS~XNyAq-g*702H} z*d1Ls5N8ef-Vw0#Tn>!!b_Jb8cbIrZVD^b`(-|?96Fc(SVb544MmDOgr99G3rhfOj zJFAT?jrQVs?N*&&L$v-eujiSG&cF;)8+=uVr>5(e1 zwbBY+{)hsXDLK%1t2-FZbBDv#1V;Cxq-G>yrrWEyJ7#Wc^u_Y()OP%}%v9~3vGpGq zm%@KyN<55I`bNc&J*6s~?qm(kCPqTb$P5^9#2v=ob%V=SL^Z0Zz)VKWyn-H_CdRZ1U@466l#=66fal!_7Ltr){ z=4p$u+|nnXrFX*%W$sq$w5lD{%E9aZ9<=}4w=qz@he=LG&>0(Ol|PM!v){6zW9Brt z`OOvfO%WJxfeAv4+x98^L*#wt*hQwvPO77>p?b?FR@v}3hQ19|ap~Jou~<6=#yY=; z*$<3h-Y+Z2ydDFv?+zS_bA>y1+~Dp`G1E%L6gYqw)r=Y3qw#%qyd##r=QdQIPTvu2 zr#JI&45=Xu9X$TTWZ;7uwYd@0>}d^~j;bM`G!w4PnGd%gy204F0y9WpP9SEU*Bq|# z$YaCX;|<9N^?2xoCwxJxdH)lWR`^>@_wr(xcB~q-ZDI|p_o|`AoGd6GHy)MNj~Ty_8NLG$-Q zXUd}Y@FLh4dMvd8-(xW_BqI~ngwBQ&U0mVEN`VOxm>Y<3KJCuOZM@4`-_W=^76Svyw11w~0;qPc^j%h&3&t z`Uhy_X9&%^TS32dv0#&v0m`qlp!F>`FfA0A;a?=oQ^cHXv6`3E&1ITq7BTy zEnmUjNSibr3jc3vew}y^?h}n6aiR=nh2ytrnF+g!XTj~WZcyqd?4zf@N|-l@Y2&rMi_xmd?(-hf=2eHQ1-8)6GZuP!XF#&iEckiO9j;Fh zn41Dq2QgmBYk2mhY?jpoOA%f2%C&3 z@K+|d!YsJ;dLAs-2+R|Ku|ka5vDLibXf_*&n8@?z`ELxx0)(NHbW~C?$h-}q$4*;VwmS;sxC%VXafieW?$8^=3hnkyn$YbK z(?518pEog^9Yc(H*cdkU^a7rdWc&{`w0lyn^G{4_n_|e*HG~M24HUgmLwbG&H2!NY zYe3HLG1W*rctWA>i6+x#gyBwts;Xl-y5KvCvaYfd6H$qpq@ zKdCDCq|2bZNDb>+Wk7M8IgsbN05WpL|0cgoQqv1DcP}mFZ=Pl`OT_ebsFbhT9L%RK zeC7}%PP?(V~jq4RfFm^(zMnfhJA3?|HX zS1!-YVp|(wO}hNL9B*KB+cfH&bnwusp&0t#nB6~%p=ASom^9B89;&0D*4T8|t8|By z!uhb~l=wDl1ZFH^UfC|-bK_?DTr&lxj=)SqOxo3%++c7Pn}nDi4eQ7^_TSCD zbNnPVex?5#LwV@&Rf?gzrw$|@v;oUy9ESO1zK|(GF6ifO_(aGqUAPiw1&8f9j5?VCl?OcG z)I>LYuv=gb3CuFYylXa=53HZXLToT?xAm&iW7%Q3&Yc00=T?iMBQ9a6;W?!rs1z|} z=zI9-R|RUGu!aT3Q4oRm2%5chhe2)JAmFKpIs*m98!C z2d!k914nkrRlW9i3%Z3qn-F|U1WI7msnL4X33K??d(hqXL-~4+HKdP;2IKLW zaDCxYsHRyADP6>%T^Cbe7h*o?4C6WpSSo#)IA9JAT@1~N@uKPIxu7@~Dj~7!wjhIoED&A&sHk(x+FJjsz z$}ODpoWi#!OKOs;*OgqVT8#Eq1Yva5A0asRgK|(E8(3l*1@4oxVA7*i&>>_o7)=sK z+-(9AkC+D!mAu1(Y&OvxkGL;Zu(Guqog&@RBn=X*RMqn8`Z?kxuGnZRTqrphomH^Nw8N4AIgqf8$zdvQE*^wHZ0Ox4&A^!;Ibk!2B;Y(;K~qKK2#LCD_@j9v*SOpm$LA%>!=Y^Axey1m@09X-z9Y%<|Wa zUznN0uGYoicBZmh-<9c3k#!^g3q$`KN~uQO6jNZxsbcu6?7Pw?x&cgm9tEdcX9K=! z02Yhfq1k_KdQBCW_lWsq-H|`G%3ktf+pD;ng@8of*Hd7kW((HDML(?-c@+AeHMFLQ>IzG zI9u_nS(g|cjxCKaL9Dg*Qo5V|Hzx~B|F(~=zf}m;ot`O2T{Z&?eg!sHzXxx7`@*9~ z>tMN)xQko2Lc&zB#~b;*PDSh9yTcZm$TViV4l&(o!_);^_Wg~aVzCxOccaKYN|q5X z^FpZY@>1Eg7e4jc_zKK%$b)LO8(`x`AE@ji?yzqXYD^IGsok0A>$}pKXEpQ-oVgt1 z;N-}ydJg^@L%vSRs*{>OF`CVn0DCDXlT|;))V@h)MSkAX7={6DBuE{U(Z#C2{!LdyVgqBq*n+CMRP$LR5 z%W`1pKu;K1xD>w46{|q8z}O)sFH*q|4Y^7gY*oR@Gtm7YAsriG?9YGvWSscep%l0Zi#A78@Ud z>4=yglU=#ztPIwn(q1!glo9i4-j=aRlm5S$FK8bfbzL7`>}?A7HsisgeGXKG<&b>Q z4QywM1aZG#(o9n#=9vE|9(p2!4Xd!%ggscJ$QyXU>9oliIhBd%+t8r7{AaQGQ_Zid z#Ss4dm$E?54)3Z(!^LHH!MZUTm7jZJ`(xp=nItfM5fgjA6(8FwgEd1;tIzutQx^tC zd6({$s!{*1LF;zpH9YHIs{FFJA$X3DgvTxKL+1^6VQHB+G*yVdXKJOSW;kMG4Xg3y zL+>z0#LR!%hV6^3!$V|SqDjsF3v(v;4YZ2>u57T!3d)?LU>G(C-m%gP=HcZF-JinC zu|OxFhfXM;h?q&MjrlRFbT*jO+~1?Vecewzw$}RpubRnI-T~uPpuUYQ*r%#tYvx@r zxwRB-k68t^K8pz*CZ@nF#LRkX&nN4pvDjbsnt5RjV?O6NsXMj`{l8+OE{U180MmB1 z9!B858T;3`#lm^ZyP!MD4R)(nz!zJwLN5>-fh%G`AB+Ba}*3m&6R)Q1iqV!`9kJy>{U30w|c3lHtY z6z~_AeTXR?)0MB*Nnu`kh>2RyT(3rQqh$xBZv{P_!Jjlu8k{{{&|PRRTHe_vP7+7d`j@{hOB3`}8Z zQ#;Vu+yI|0xv+KDdF;XYbG~Ymc)i5=1O=|9=@TwQ{R_Y<>VJ2 z47JUnZH?5B$%1SNglRvh7;L&s`kYM+;0cVy0f4 z$(Kz@VkdAyj~%gFUbY#y?~GZJSDjp{)C7ny)N4qKp_WF)7!LM$q7O~RSwp9ltEKKfOMriR!l>6`{4zukpUkEH+)J;C_3 z!1#z2x(G3@ok#PbuM%1OPkT+_@q2t_KzDU~`hmZl_tZ;Oiy;pb*?Fkl)ac-kFy*u! z^c-aemp8`2z|nW1vE?!-f4CHsEyNTUrz>p)pAZwee*%9MmdG?^_L?~!rRr4GVLr`q z&)?2_!jPSZ)Mzo(Jj<-G7;arM21lFb@OkHTXf*dOB<)xXr7c%L=mnvspTLwOW*e3w z;zuR2qhIVbDTeN9Ry9@LYswMHdH>|3XxT~_>I_RZIJ!qbn2p~*fZKK>z?Yjr-tY!Y z?wSopYb=3xnTzob+ke!EK{JryZK9!z_=gFJtl1}f&6ANUu|Az5uT^?R!cc=I>d~de zXs;_!W3!ScA7QM_7zTH0j4MD4G+CAl_ZlsO_NzQ#;|8H-kC+0r5EGfakat?2$X>p; z*91-J&k_yqN00m%Dmm}zSvTqoOAk7c8tpxTqm>4#d6l2R##;{#G-v`_&uhTY;4UaP zEQeZC+@bYRv2?x^|C@%0Dcd}k8(m3cr{CIZbaKj>(r+g7{Zp|j2)C~R)_rwc2GVz7K}dJgLd-O;9AE6HmgPHySq@+6fsfDr}MSg{O3rKy(Xul zuYAN$?BILDTQc>1$-?eD*guU-eT2~({0Z}nl|W>)9vG%J1&gw17})k6%)Ph<_Gd4J z)0X1z=`1j95YzSiBpx{}iG{wj*Nn6*k@Le&OdYXWazauoFzRzl7DejXOTF#LJ4h|` zmbLu^J+>ObH46uTn=!C!aW1TVv=*{9F9Z7mq2_`Zw62KRZZ?s3YLd(pFYK}IIf0w? zuf__j=SZGgYNSaIZ)!2rWrPfugz!WfZ#e6kn;uS2r|8!K| zEHFI~bG&RSZ?Y$uO?igjW`>OSt-Xd7bsNg4As}I>w;fq~Ne%T(A^Rvb)t<5FD|~2F z4Xny!kdzVwJx#OV(uQ>~v+H6QX(%@7h5|DXF&FDk=TjS`FsrBbni~ym_|T6(<=$6+ z%Bj)JmujL@AGQCWrgPM(kD8ef#$kOaWZc$+%fFg~PQw^zus#RMYpewq^92xGA-+w% zSUN`|MtATmKCd{1nLM%AoGvU^v+iHzs+k?+)HX-k5KxPuMl;k!k$OVr4#Zxn`wgJ- zOIxUT69t6>a=|yn8=U>;LH-^wp*_SDn2H$F#nXA4b*U`+vAw2$`9U6=<-$S?EI2g* zqE~+D?bR;kqElZ@CK}BUCS}zZnD?bBblT7wLgq!m^6FXeDQ+FOSHOL3T`bJaV!G&D~hT0oaLqO`zLv3^D;msq?W$^r2xpI0& zE68sW30t1#z?NO>!MwvP2q+OV%}ijHBE~Ok0^b*z##Z8>h2P%K(yv~Y>nPZN+ivyKk)u^K;-UVNJb@%KE1 znC=k^x$os{mj23K^DL+_UlAO_F4=WboA$w{!-EBe`an^?PHF`f!-bmXJAT3#zY^v0 zD=oq9*Hw7g@D406^oNJ5#>3lc;)tsem~g}xw_eEaDsx%PYkQ6BqX2oO=K(f!w3F07 zO^cDbS|LW;*o@Sy3;GUs{4125(;XpV7O@Xne{lRAZcrcF?YCHud8Zmi~7jUa@ zcUd3WZ~DaWp6`O#v4M4^-gf?1g&JzsIM)h$reQ-s7kuxVFuD`VVcL@t<+`oyp>6&p zXnZ3Hj^}QM=XZwzJ1;Ol#sB6OVv1_I^O_s;*!y?(8W$f^^}b=(nfuY&|G-eQM(U+{ zue-5oW)p$w*W)M5S^Gv|Icf0h*cR}?Rt9=XF=+L~OiM>h>Zuj{Lfd>+ zA2;bm*E@2T3Ab5d#R)#BF81EQcX4S#Q)4q~KuZ|6Q34ZNwF2soFH?FQZv*ed5GzuUdvZhdC0CJrYP8#R~dVWsU|kz{eED_{#OD+ZQ2Nv z>0qq#z_-|G(7Md51P{XxN{^y8Fv33^09$qsuv#~n(Ta6)MWUhf)^|mLiK^n5z{EYmvR+nw+(j`V`2p3O zeWx@qae|-q@WzT=GNc3rg39G zPca3mBjz~x@HB^)Z0Q?&&AZVHd3=YLY~S{t%yEyQ^lUY$G0YX1i#w{T_Ul;IWwXzHLgI?r(4$8MD!Huy&;5Nhw z9#n{#)>dF_5c9gPFF%l6#FB97?B(t)pOJr@C3ZW^_G5}cF{GY~)YLV^MsruOpPgrQ zm12az>}pm;HL%%BW%U;wVEw+oz~T69==)|nSQvDHLB;|zM+}++V%pr>!0R4enWnLSPvE5S*RTpQ}Q+-Ln_MdhFb8;%)(qCX9P3Yp;RaNJXJXTJ(>jq7q zgu$nkw_)s#?O@uV6TJRU)KHv$bB1kq{*AHj zCNM{x@xu8Ap{C|*ebt>aFO@+vmEdi07N(iqfY%51fL@>@9GfRj1ib}@A?DG^Exg?J zJ^S*&UNd}xuYzSil9wNN!u;D9s;;ias|lAdni(!I)mm0p4LU3^_hR%^jb5ZGTNHMM zO+8M7an=oZVYe4lzO7-~TM?%{5EHr&VhW75@bU1Gx#ZbvP9<$(kuU19z+E@lhI+p- z&F2eDMOih~uxkS2)yF{9v~9k!@O~Gl(f==K5_lUnxb25+iZ;;bhWIv%s!D&)p@@kz z^ydpxKCu@$_L`Zu7RZAO-ZFQi3#_(|p=#7_p{A{`zAT_$_G#2~J`axFpn!M~w3aU*3817nYrg+uHg)JZMM}%UA4So-Yhk zd=K_ejWAJ7I3X}4@fcUX7MRIN`l|3D*~+(@JHncPV-WK^9%@fH2-Blmfk{V!8Kozw znSq$2rR({bS!L`|I&NzVo~ygg{y#*Wc~nkO_s5$xk4R}$Pe?LmsC&;oG8Uo%WfqcI zW)aO4iHKxQp=j24pXce(gh-PNQB)E|6hc(LbMJlM-`iT2wd#-0+UK5OpMCcJ?nbJ3 ze-PzE)W%s1`)wXw<1y{YN_dTo9=AO2yjH+*{WYlR-V}(q9S7bg3SmIfWyq}<0VQks z%UV%9bal|I#Cx*P{iNoQhVNTvle@8dD9{Gjb8m^+ihnJtrgsojqRlFB-vUGBDSYQ(sM z)W(?qVXCTmOyfZ%ym2URjh?3>j(k;v4qH!#?i2AaS*`?%wp@Zv<&j`4GYL)jk+UJSGylo=SM@L>`kmO$mQ7 zs6h|sAh@k{1E`tz;o8&7;7$5RoIJ_Tv|=7}f?!@)MKXRLrReX)0!dlmE2_&rgL;-e zf?DDAKTN%xE>?R=>Ii3&cGdHF%)VcWcw2Zm+BL-vR=8Y;7gHNMRro>k z;W6h3CNJRxvwFM?y`qR*3Ug|xHBPSIiQen38tB=L-Pt=IcYbK5feeoeX_*ODTm`5&AQG(=a|DZ_+YfiOKk4*GXRK+V4jv}F4s4s(LX zR1-|r`cUTFB1Kw_e4DXb8YvTJC2IftGKQ|?F|{`T!(1jk2|Ba%xCR^b^LwFaLqB~q zMjNa~2Ey)XM?ovui^K$IWc|sW!?^Q%+8ctI78AleKBPp46%uQW{Cd2Kn7b8a^{YVazG;AdOFAY=)rGAnOl3ZAUtwpH9w|&Tm*?EUtg9;Ax?x>)pQGe(@Ylol zFU#W{i63EWWs-2KXC2DDF&FmeIKlpNBjD89D3P6sI)|CTW4;m0su6+AdyxvA`9L6{ zj(7>1wvVUf{{;&5j>&OX+=y?=nB6+rE3W8^0(THxA0Uqxm?|{+ zuY(^dQ^E9ji|_|CjJIY0XH5^mh->_rmQ+8jADc~1*CHAr*R7ujeN|eihr#cJ(hV}4!eumRV&A@m*N65PCC}Xm#_7o7 z<3}^0+-!`PPOYK$H@!r16Q+aR{NeCo+y{{hd8cMEzmz$QI>Ds$Y-YYqRHN@z3M473 zqbLR4@50rmVud54rE#9F7M|Zilz2$^fo+Ev@K=^oRGyzMjicA!2bYQ^;>*kSBYKt+ zESf$D9?biON>9X#%>*5sHM>+e%n*VZoV}WntWu@>Y6Oz-$5*J;GaB+oEGrUjwUy%9 zh?oB$bQaHAx7t}~M*}})aAf&7m-X)$9uivs7 zor?L40(Y)~FO2|Cv!ulhnREFG&0{7JOksc{^QKjWKJ`W*8BsBr32F2Z-prjLtbYCj zro|}Z1aB#&39Z4BhQV4Esc)id5!#Lb5ouBHjV@{CvOeo zS)oCz5m&vfCr!Bcmm$5pZ-B6;stpdzRKUvKzu*rk&3=CFJ6KL2=$k6oCFv75>wE++ zX9IDB-BWaYwFclYBXD2v5lLPu6a%Ye5UtZkNURdR@>+JW$`k9njI#2EF=9xO?P#IJ2c3rnw&#M`>E1n7{GptH2eq z#*PNzr%3Te)k)l-wepyi1mhy~XH1$0(KpEbW}M-DQRv1LYRkJOCL{hW2!2W7r58R! zI+1GEUiT5MY;J+K2@3dJVgvZ55%H{n)5PsNo}kkEQZTQ5Im|q3LnQQWi0}2#9LAT& zcoR%*Mg&7%B|&GhfS2aL?3S5U3=51L3TJ-y4)ICN+eOv-x;=`FHY z|IAC+Tk#YAWOazFPQONR*Hz$4^(lDfumZfb)y1c~$-@`~_E0r^3s%Qp_PL4t zUl>BnI!CzoEd)%{9pRJKS#iduH5_IGZ_Ocs5!%EvsUuA2-yZ}L542lU)+vRioQ`FB zyqt!`s8n?i%74C6b+$w=|GUnwSrU6;^9TN4-D2+ z5WoMxYeJ6TF`)!A@mDdk(a(%#$P^fQ+^;|@?xDuGWA!=eAx8#+>z&l+mw*Uc${nUm7S zD27xB+G(gYitDy1W6e_C9$!#q;ura(NwASr2~IALr>DA~v2bIfiOAbJh~DX%0xlcLXMb7%Myu*z=ly%oFg70w2RFjfIq6{L zKMlW#Sp=h3<$>Y;I@q>D4NDnjKy5VzO-CC!j0u0N`*O7L|M!lW6`!G-isvEQ8oj`H;+u$2rtKLD$GtcGi^7$_wYp|cIO zuu60aNXfXu`PCg9CV=+^3JE4bTS@q{VHho!A&{It;!njr%n=3tJ3}`q-v-~Ha%d9g zkrb*Lh?|!TADXj3hOC{owImMELgVL0Ho>VrAyggu24PzU;>%+aK<_ZS9(`R}_acc4 zENG#AhFgjk#jN2lb&DQ@?W!EucB%qojCqXm;OF2tDG^!<#^S&G++ded3hZ0+1LmI4 z#DjlCLWS@Ml=<-A<`9p0M=(o*dzd+kHR(ZT1d`$nmbB-(F=8LLF?99KTkv0u*Ge8E zR>*;_^jg?PC&K;#!?5kk#W0BUmF^@3vxkJ5*yNobDZlasgKuv+Yt(t?wvAx6&m!e; zjY@Q2gg_EGz=Y1tv=ATre3^<M8I3EZ*cv+GQRQH4OU$UCW)B*x)JlP`VWFReeN04_Q`ZiDxe5Tt8!6HO(LUP-F;@S$)UI`Dcoq)p;)(uF)`EWv~}yvg5doK3AK!IV>~ z&UB*mByq~&Y?1z|`!MY48wkAp5FCfU2Ft<%_&`4ePq(+=IU)~~m@9DRYXBO5!O_e(#l)Zs#<|0F6cH@cF|0{yk97)8&(Xy z7<$i)4X{o%ki&HIn~gicY~C%CpVoPhnndz!{ucIAj%Nho@ZWx- zVekm@^_n3t<_TD8z6I@z56E|U21~V@L0MM_=X3pGVW|!p=r{z)_-8@&`EuxS3ZYH3 zH$ZIyk1c;>g%3$Up+|?#4PVK!V+_brj^K4iQ>kAx?d<0PjwUAGGuCvxmogE5OXVIv~eK1N0 z&xYdB2eHYR9 zUl|Z!Q9;rZ9?(PgEQ9=19+S+w9N`3Wb1;*?GEI*vC24RQclwCz-z^ahj8~*>Z#?3x zVb{%4hqu6D*eSqbLWzH{Q2H{Mp9w_ca&Mx%3k=*+BYix+s2~k<7qW}<+TFhVP5Las z{Cp?J3?89FeJ44$2X^cgeLR#ZJi2xsEtB|=!$he*0;2}fmYQH}Ptva*UB(VA}wHv}yhf zu&L!G!q@Yd+XNH2*qu3$If#3ce&(=Aba~qV`px86+Pl6H#0xv`A z8}Xt0+~$Z@=xn5a&rYC~mlt#ECf2EhI8OCoyY?ZVrxoDzu8DJQT{|Dc5UT=Y->nK7 zK@6l`t%ck3@1yx*TNoX{zuz?R&aIGOPSiv)_3^{0vlRl#n4NB-yVg#7oyvjJX;m=M=MVaK&m4AN;-l*OcuXb1oNCHsVopz^n(mQHp{I-J zhqI90G~*&&NL=)|tR`q1O{@}=bBDA)wrzOKVYKTqA!>OSl-ksz!Y~TfYB5l&Q3-D% zW#R8|JvbG~pPn0eOdY{I4k%+%)Lf_?i2{kNL#XKFJteTd6> z14%DSpgX;c!}O3oxLMzNz+Utesn*Pbi$jU_LvaPnn5qiB$8=%zCjQZD5080IFc0J! znfKZ2sKZxD4%D7d(ZAYudiJOd^!OPf2sCbjvgZ;G6Scd9l^ zk?k?bq6vJb@|bY@67bA^$gP{Yw;2$3P9ArS5ThYAi(q(RIxHgRlT`e0=+PDKwON|m${ zCm3oX$-}u{h`bC}!l8Xh5Vn-4TAi?ha~IzrJ!9U1y2N8-EJ>=BZXa{7;1p#aDUj@3 z*2eVdDWJ+r-|V77^8X*hE>EWy#i0MF6f)v?Ovf7~+#pOv=`-CSzTpPEBAe4>?@3T* zkcP$<@R)WUqe?Jmi~ljJl`c{@iF3P&$WDfD`%a%?1dNLTj|rESfNf?2hp8S#8qjQN z;jG!1r;H_s;?Y3Y70~eK63lTS9kS!>Ks+K5HGA<@5&yYK4up`?nA`W zxg;n0BGQ;iZf)eJmbb=)U_Q3~Vk!+%sMW-WPQ0wZ%*}gEf4ulgXz7**8SYISCTjXS z4ih`B1nft*Lf7<6@Um9Lu{%$qO^dfdV*Y9PxaB_lHC+hVuY8eS7T*i+1COyJm}w0^ z8TIu!RA7uilJ_u~`SSM#-M73`=r}SDqJqeT-XeiQl|~K|SY8Y}f3^agtB^ojO(STlk_kPT_-e%;f!zfhGF9=E(+f~~yC+PlI{~MfC7{x=7EpyJ z+HQ86!))a-h+r=Lsbgf#A5wGU1(J>a$RvFw7!3#n4`Dl)?~RA+Qx##A=5r3C!3VnL5KPSbQs#+WB~?i_ zo7AEt+G|89Ej>|($D}sHFw*?oTy1Xv%9g~%6*_~!c>u&eR_m(jmCOc)>NT23%S zmRx6k^fXcBX=G0`e@*mhbCTo{kx!Ie)O#+d&$UIa7SI*wV=_nCS|q8z6d4WiCk>LJOY z;QUSg`H(~^?egD~Nj$8TJJ$AIEQY#UU%*l-561b9$42G?@YhL%Pq#CmqiYDZ?)(lU zUI^ix3Yc9tcKqqNgJAB>xx$Q^{EIRm*2q^V&<{MG(&0~p6uWh{RkebrHo2h<{sc?^ zJOp+Z@U8s{)dmb~O~BYfeFaPlEP$y_b#QH)CdM)C@afJr=$IqTVM=*F&6i-F9zV;7 z{z}oFcLWlX)-CjVCk@o|YCOGERSYg?KS9q^;-~FxheC$=g9(|U!9+gJN?s)*=+qxj>axIBE{eY(aYR*ryjPHR-#1nm) zX^Vw#Tp(^xHk`1lhNDmQuw%ksSbHT3MoDBi%r8EjCyrnOgKy;LU)7@b_zEOW7cbJi z>d)zGv$N?Wav5~I{}akOUqR^R-yr_@oV(w2jp&1=QRPrpJ`NZDm;?*AUxVRtBDlL` z0{#-EiyyQU6Zt7U4%5r$4&Ei0O0U3t-{S*mo6Q1=%m_nD#rOoBS)WW7wpYN?=0DK3 zuK}`y{z2i(Iyk5L3IYUtxcl5h2fQOX3@*JUZw0ZSTSuhPm#U%{i9(%AF$M_BQQsK7eBhqhNuptP6hLWkBvv-KQYsT=`^-<82` zWhtzAUw~us74WJ7-Am#x}$8$1W9|F`xhj zRLOJJXz(Ri&j_ZcxG&$~y&=793b{#-uB6%~=}~i>eCg`E_uykiQW5bFxcX!OKIz*5 zC-;5<+E*Dn?*9b%{Z!m<69PxIvO%MvgM2f6{Gv(Z0XSLnjo>s++05uTI?Xw;E zn-q=d$}z<2v^AmYjwevhiah8|32kutx+2b4+ygc{lyQ&M5AvP9!yXegTrK$uqZU}< zIhNc5*B z&DK|#=1FW!ZB5b-G0Kc#VE?7xp zXYWcF6n_*p^cHZK**vC;U}h(M&eygxqGQbjlBKg!h0l~82))eDQjWdd@WqsL@|h-! zFDPl^xbS|cF6e`*YufmO^FMeiC;1(aPs!cm=U@cp?Qu5ahdvFmsp zsDA__t=64?`kn!O!&D&gf9Fdb-+f4Qd-gXw_IXwBktW_lGE`Wtp@VJI@kP=#ebH6hFuRlQ2dIY=r-wiVegg= zN1TFTa+@ja3f#sG+7=$8Nib8zCXD0XfpnjM)Dawt5PeJdA#&fTEOMsgxZJ_KTotTT zu8a3LDdNrBNTT0reJ&-wv%d;#j?YGp59-n0m;g9&@G1-nUk39c+fiBY3=Sj351Kx~ zLhAJqKnt`t6@V;eXR3V8MFCm_iq?rwjCn< zNdj*dC(wTiPNRmYK5+O)7<|*UgNL8*qG>G6P34PCTw zShFEcSfjyJ;f-8rg1=5w#dWXapf&NdDD{CGLf``SXI;Qz)IU@?W(A7(7y z!SvQ2XMX+YpjOW#d7be}B9nSovBLIv(Wewr1XFK-J=SaE%`=Vh4Xnkrb*qt>V!;?< znd&7FeK8g{lutzUaf`q?2E*pEmuTqZsc1M6*pwna8vMGkCzye^&oGgb8Ysb1fuwq; zpU~`D*&ygae3>$t`yieEOL-KB%FI9cqSQXYw~!?-=;HMonCM)j^C{RAEB)m$BW-w$zhwdxzw#34o!p3?jU_(8ubJ@8 zTmhQLy{0__l{m~H9ezhkCY zYv3Sm&{)j$yJVNPP62<1@gjrdyJ*(*xll#TfMuyhutZHnFMT+I!zA)EZ8yPOmCIvH zHB+g_6!E)&8?S10m|$k*W;4axlBogd0*U*I1nSs<8+MK% zfucpEGID0NF*e<UuJRZhYh_`tyf$DGxTr9$Pi>buhtI zQlzGUbSQI`H^XW~CXBX!2Q6`j8G|8GaB1cah;%;)NA?{8_c}*(iL%O7@R2GbPC~D7modI>tix5|joUs9*S=K3w+y;q z&*Nx1=hz^qnzJ2h1_i;*tVl4@bwa(e2RV!dkGVuJY2Py$3rjKO@_=|YzZ-?ldUB}Y zj9ADDH?May;+mh#e`thjO|`kg7!|S$Xpx$>8^@(_XTA>d3>*z5+jfCJsff6C=OX<2 zFdl80$zyVP%uRx^oms#PNPI+ne@N;*kLe2o2M$3dhcy^>>nvDd$kh}^{4>Othil=GCtFr}mK4iaF1v_Qr@BDa zr~vrW91C7SxiG)T8AT}Z5vUa2>&z#ZE74Dwq+(J>K)#KCYnI&t>1jxQs13~~!;U*R z6tmfO)2=Gp*Uo@&hH4wmoH#g9*(N5?jy*Z{;IU zGJLULF~R(7DPaa%{-ieM2_(}EH7Jd42ejNOgdSunkAL~=V>a9FX!}s?+NOptE+KWE zLyR#KERQ#Y8R1!mDM&|aGe}@_7U_L!#n2zbPv~IFM z@<^mZ9sIQcjhmKCPwSM$9yj!G6|IbWeTHH!u_|6MLmsoo+Jz1|?3ZML^JX$gse?#@ zoB2a-ZZ^3fz6A&8P~>#r7B|zf`9XV0Fw1V|Fe{F!(hn{ZKW)%eyK$Y{(ctOjbabN( zmVY(`r<2y=&Yk*rrbGotjF!WRMn>4rM-GqFu*BLCrKlMlfq<9$z|39bx~g1Y>OkQkbU3g16GjP!HA(vO;@@mupD_yTF{G&O?v1y;%_+T&u$sUG2k0Pjo4seY+h>$UFO#yGsXM$P$ypWMrH=)n( z6G(EY&%&RV_oG?cLn%D6 zc`!CiR^&VzLp>#|R4a{JrW)cBu`I6GWrwvYo}nM~39uNv6JGd=!6W)F6gkaDFDv*6 z)Gi()WksrqG%J{h!U=STqd;vUl5snxfT_c6u*V^^nbVIat4h(~$m38V zw*hJnJcd7da(J-OB&1fH#$mSdyTCw#DHaznAJk{lT?VAaqtKjg-M0Z_>xkU2fD3#hi2OawK zoDR(T3v4wJJJVPUD-K*past>vW0PSW7u(~yi?>na{^JlaWf9ns=;6$g0eD3Qg|@Wa z;V=q3W<0?-_op!>Q&-b9@69FU>(qpSU&o=HbFygPpufP@t+DHd^`Toq0m~fYF<~Uv zQ~1sv%Z-gg2U3p%n7M=Z*88xIY(j;R#z=QMKcR2)gGLdInqw|g{@sgCd}%IGmp&z2 z5;zFexrfqG?tg);!kbT8@7-Ui&-G#NTGS73O$;%cK|IrJI<~kGja0XU!RbK@;kSwe zZY`9!oh2(-K(VLuk%>6EY7ht=} z>#yjCPcDWyYqLE5XFnYqm4>2=3CBS{Z2^?W<%7p>IXtJOigr@wF-|;YA;FAOE@6&t z^P#)S%q9QM|IFWTv78RRb%FXX=G9_lJiUPI0tCZa^E22GmsiN+q06S@EwlHcCf5)+ z;OGXvBXc3@tUUgCB$)o}!(R%4cc7LMjL+x$%$$flbn7E?$%*bPYKLncJwl<9VKEV( z2jT#+GH(9yKa6~(A@(sMqMBlRyxVv+Iu;)Q$A8ZPwYTJP<*WjpWAl_gy?~FZKj7WL zbp&HQI)|y6ae$um#9ZS0){uJUmQ24kZ6)2X_(2;7q?D8z%2~rs0WBFLuKs4yafJI^ z<|68|FRc0opc})&S zXgmhJQQ83^<0nDl>0F3^DTl>3I_Q&{{Gk2dzfBnsV=#+WX+u#wj z{NYqlekzaI>Y|GM@_5Xk5#(^#XvB$`xb3mUa|c_a&+^-0Xv$Qm>B@#qdwHz7;3&PH z;jPi(o!b)xLsgz(wuc4KAAXrj#y)dnu8$Z*Kim6M#Kr|8pOU`bq?F{p7UP z%~E)9k(ge)owuf(p91#?=8(l@=D>|0I%k?dvT~yh6Z_SQ8Wq_p+T`CyGPnnF&TYUm ze$b|W<1wr1mt*BS>UX>QP1Y5fTaHhBBX2sCDxCxjGCgWlR~ zFwp7;N7o8^^BmrqBp&mSU_QS+$56k6=sMzZm=uhn{Cfod1~|nD=|^h^gj&i z3$WkjPoyGFJu(g-S`&dRKCT434a1F;OnB+j4^8jOY45MR*LjP_R1-|S-Wlf0pCJ1D z4&p;^PP6Tb7czTBTon24>IYUch1Ij!bB!Og&K>{5$aqh{t-X;*%4!YNW;j5~7e&-iTuQY%j2=bkIN_#tpwdaE)Y?l4h|oB!KtTn>v28`9Ls5(@!&( za)M~xAd(Eb)l%4}H9*Kj8Hmc|q`0=#ta8#HcOD}xl*Z|kc}&s7@%ZTPI5gU04XF2c zK=sWu@O=CSTqPR+9yMNfV`u<{%MUB zPRAqdwZy9#w*(3=XMwu=HyB<I8G{!Z{|aD}cW1FOZZ@KW^s~I7l>8FoFJ=Nw!JSK#*0qq;Klu zl01gKlNWh?#N7Z#GIdL(L81d!Av)f zW(1Z2bUC>Z?A|boauZvN-VXMo*&6|iVH*fe*sYJ*km}5jGMuZPN*X`9jj+b_<%_6V z-2+;mEQKI)NGDxugF6!zqJkuTc|PDV!wBYp^%+Jo!=LusLJ}??eYR6NI81a~H-=Uk zBF!n0N0Wfp=wncWJx7bKzdSNMC9_k7HqwazIiO=x%;btT} z$j>w{9%Dr?!-Y}I&)CECyj84P!a2JnV<*v+m=wBmz4ZUL+%p}ikF!?Fgo37Nc`_)1d@0xh2^i-ld6ea_-*qJls%%5+hYFPxbYL(k;O$luk&2|Dt4+5^%BQ_TQZ6)54M=SSch z(*jV<`6b}IYaQfOWrKLf8}PLcLW3Xj7!i+gBN+E5$C=@2d+52t1d>^I6DeWJ5>c^h z7X9Ub4A(SBa6$ub+^dJL_Q+wjZtZj-*?2mY@UtDm@koDvv?b3S=ImGwhBNcP_4FGk zUwRgeGULyiH#}w~!DQb*##H+5qPuhi5*^q1l;wf-A`^vVy0=&c`*>*Mk)-@;#SA@s zp-~QRjg-eBr-tGK8YJ93aX4;s2tqR^EP=-0b>M862hT{3uIuYq^mqtA1%&*!@g|tX znqkcAEk3j~xkj0+IAZIm;3x`>J4>r+%HrPX+W1kO26olf!_g1raL9Lg>@aI6ZZT8F znYzRAuRXyiX7hY-*}e%LdWqqO)=SXuj6)f-`7Xb=c+5_MS$;j7d39+!E&6LNxt85+ z>+C#JlzlaTHeDvm75hyiZ#T2w4Z&gOT~GswWTm=!aCT{ zoeTR~YGEgNGr$V`xA{+ljY9-uYj>QHRoq4|=rWh=pQ~ec=guh6y0gyo=$j;%@{<(% z*=b^%Xi^^UCx^415f}ZoKJGnA1Wy28<#le zR=_{3gc8iBq2Wxq{}y_9ySZff;30OVKU77`D?Kh|Grvd+uL#w|qt*_=@(yyuW#=DO z*r$j;-_3DRR|q;~?FO=P%fW7x5KJnnAgMhLO=;k*@%T^w8-jVDa+JxQu$lhUVlL?& zc7l?RkP~$<_o+pT+=JT%b!$n*>%qE93X%se89~6iW1(2T|MB zK$5o*B1KQ3Uit>AO68|OE{};Nn9)0em}a?6v|h8hB!0y{>iGd3QE>DKYU4F>!CR$; z8jgyj=*?*K)|XorYE`@ZaVik4YhzurhzN(fpsVjh&8 z+XP>gg;4mGbe4xZ=;mvFLQmx}xdh{|JD6E~-HUc27mv`3cZHj^KL|~#yM;D6@>u?` zCN8hm!fZwU{2+1&kivgf`(fr&72KaP3}13gL>Vy)L3OVeeDKbMvh!sC>u#ZviTuT5 zFTX<<63n#IVT^J5dRn8yT(VgIyl{)SP%K({p(6`tm;k?@!&1hZ$}DQ5QPb+p${bIHfI zCBnAO3gOD(l!%ovaLCZWs}5`9F>ZtL^`WwuRT&v)It2fmuZn4c`E@)2jrhG7)S|aQ z_qluEmT({3v~Qs01NnoXm)`}R6U?u9(ac`Ub#zUyxg`1bRH5RLc;RkcPZ6tRVY5L4 z%a&_%nknZ$$zWE`hLz2cCs(VnXOBq%GCyG`OQ(0$QmzQ1=yn&>r(! z=R1OFe|Cl$|SiQ?FzmxHnCU^Toj&jee&%|j|3^WhbV4n{o5 zflLoEIL=E)rHgrMX7QLG1heiz1Y;}bNw??=Bq!DyGdpgV2?Hwki56KYV)p5KCegKH zRjs6_$Z*O?pKQO^2)33W%`D9rUY}U!ICQrjKBj znx0~;P1ev><^su*Qaho^`cFcY9Cs0`pH>x5L^PKVAZ#%49`Yeh04C#VWbO525d ztHz30LBRPl)UXec0b?cfoa4z02hmbxUwE?-H zJ4A$PcJuC_5pRt)!F0X5#ymQ>ibf>XDIO#%)W|$5?0Ysq#CG|Wzom-9SVb%HC`o%r zb8Qb;$<~d_)Nx~r5x)2DH7d_?AX$)m;E+c;T#v{ChpTx==+6(@P#$AIFoiNVnNy!v z((fk=B=mwg!n+~sg_GtL3!PPz@t2XRIDyPEwpYYxbuwt=(TisQj#Y)Jw0r^orFheCvHFQkQR z56P;#Dwt6ij78_QvDRrRy#9^`9#pP_1?n2O?WqA?Ij$aQ_)Q1rmFOkg*#j|sp!cnIBSdwt_>nPfW9`~YA=P2 zS8C#)lXNf~*TDY9LvhKvb`*Sxw5^_e2oy^*VTVB?cpNH6rCPjaW6xu32_`EpjuA{* zL93Dkm~+iv?Iw*pCk#(ZqS&`J0kO!?R2S9Zyfsb)bMV|%W~1D4I)r3DJPCbmckk30p{2Pc%|1xp4^+aB#ty-$hfR^=|gaA%5UUt#SfYmk8vlMBl_2v z&{fOmZj#G!L|%${-kmKpvs_3UCaU4*W8zb%1kf#v^ z7yqchVFTW?QRPEJTL@z=M_>NS=unThS|5PZI4*Azr8oNvbFsfbVzfVTU{F zID`HRwR;EQM`Z2nTBnV_lFY|LBRbHB$)n+%ObFb0MZC_@C&28tHvF2yPl1IzW-q}k zI)995cUwZIl6YE75~4NioJE4T{q*P>4Loi70Ni*&9}E7e;l0y);4;}Z(ObR>K|cnlnEB#@I93Zs%o!G~}BZEYDpX#NEANW6zJZgQii^piOBdMkR1 zYB;GU^rJm4YT}4Q1*}A(wrmcRy~7`dh&J@s!drC|aP-rm zcxJ3B)(-d$I)Ov*d>=9c3w3aQv<#fqoJT)&H-aOlPC#J=(Sd5-0{_x!am?z?Vm4)D z20v(L38o;=jcMEGM4xUmm;6nU&<_rFie64XN{@T2g$=XhaLzgdJg8a)f5`m>pNRU4 za|2mRD|PV6DINtb!m|Y*LJYym@jM7#N#F}w4l)H91<`Yg3Rui;9&?3YI)v(spV4gk zPQAIr=(s)|66qv9{4|=LzmYgk>^|0FfZvintoh%%Vdxos{Aij2w{=cB-dDiHDNDlZ zNi*S|eJE{N3&O2Bl9&V|35&7fL#nq4CVk53{C;CZ&!{n%^yv#wp8OWE_>e7K zyIC36z4;1T`wZ}R^0=}s>L*Or9E$tyb_4siwr%`q$>3?$l4V9_a3w1T62fcX?c`ms zXt}jyg^nGEdB%U641zH}b~jJXeFFWSym&NLtf&9kT@$BfpB1ui1UoCM;9~1g%!)EZ z{po@P)uA}nlvIKrYk`)-QzZ$lVRw*$t!abwNkvMtB@4BYE(9Fo&7JZ=IzCbLVVY{+eAnwBA>9NiO~mQbXEp`F>fOf*Dns(PDX@ySrjlSfU+vG2?v|&0`phMyoS9x+87*#fXc4Vb^oIB& z`ml#+*|4GvO&43anKmzEASq3p0K+YH#B~ev>^_{$g^(U)tQ$t;!@nPcp07{ojVBDb z3GK*Z>IeqBp5}Ue{6=|c2_%B%RwSKqM?B+CqbN6N2z>l|53z@I_?us#ulpYAiPRKM z6QViezae86Dbd?nc?65@z{0cYH~|mA1&ya*?2PH?tNL6KnP^h7{Gh!jnDH(X?5u`8 zr)u?xM%OV3IwSu;{QI_<=;ez~XwJ(J#JU`g0pG#Nv=LsByN$O|0&*Wyj3)g}K=&%!9P_S?>}mUEiRme0fQCcc>h_%VwUiC&klk)+?8Y3wS=LfO~~mPmy7DuFN&ut zpAr3jTZfK0A4glsPTW1d1Cqu!@EH9Z^zDlX{Y|=#7GP;OxA{68`KO1MJhs9kJ7eHR zwgR|{&vBSn{Qc%P!B`Ayv%BYgnc75xDXs3q(B~@^;_(U{qBIR+&9p=`l}J#x1$^Q% zh*@ife1C~dGAfZjeF>>8lLHe{Lf?06IF8F7hYxl{gK4iKEE#u-!>IEZnK9B*(Y{KQ zAb$r{G)o|Pv(+8#t=1@Tu1FK*E+jpnBAy^0l5Ckza%^P=z2v@)VoV=+JA6hmqjE6& zPwGw%eE%^K@0dCjPjEU7|Nnb3Xp{K1)v5&3LwDIlMGvPMNbvr6)lKoLh7$3~EA1lh z#nxc%W)9=BwJ=*GJIv}Cd?DA{!r=)5C5x^swNl5pyXhmc?Z`1u!vzm**YEBABw z;20;&ew()UTvw981k=Cqquumtg?0nC3rM1lhVXBFtN36*zDT?0I21NSz=cjtTsQs| zT&bx7)4Tdurr|E!RK5Z)UnjsM*_TlDqZAHDJK*py6fT^;4DPRb18bi1*Qhnk9L9uT z);)Y-_q|WXHkhQrxf_!L`l9C!Ivgo6<-d;T@8)!eClIJ zA5ejQXU#x8r8nW!$ho+D4uw73yx_RA1yp<6alXKUCJtjsFf#Ebl#^#9ljSXtSbood zX=l2{?Waso;O4jBNZN+al-9=2iz;FKwMqa}L(EovvnnHoRzYZQn_9uk*gy#UumUeV zJ_DyFIzpCFJoZ4Vxj|djz+om5%zB?TyYOk9%si5-KKs}lajd!{k_2Q6EtwYZ{QU{) z4YhIXtH)d&!RZ(y%nD{W8dbsHxUu;Bi3PY`lmbr-H{p3Ro$*9-Wr)1F2|rP8=d8J0 z$6*k`Xa&z^ZU_8f2JRu{3hK!Pj<4s5qlFIQjH-50f#1eWfxWH|xRT#pJ;peH{Tt{~ zeFo|ML-99dM?5m;17uYN;XxUI`}#iRH<77vHolj`xIO1EbJ%Yas45J5DI-h@Cz>fS zHR4HU{Dob~DU{6h&k&W-0&KRO!m1Lk5c3n!dtj9;>^IlKHSe)_U4S=sU6%n0{eJl6 zP9mUjH&}Gt*B?7i9?T8ewki(eLNH##b%oZw^1|sM0!fY8B;n@Y$HfQMXVact9T5Ar z86wENvv7PdS0^p+XO4Z3*Fco*bNF&^C=T83j-OmO4&7G*vBJQSINCf}99kZZ(>_~p zm|f)@W;wy!P$^<0PE&=K4hbY-Bj-a!??v&pYq_*%Qx{iLcwcu2zA~zqtHl*`S>W*g z3h3GT0`!yH;S2)&)ItkH<{PlbScD(aQeqF|^VmP#lEVZ);xJwW(+@2+<7O`thL9JJ z3$Cgt-v5kv4tAysJ%4kU*Sqwwem5z-A|<^Zk4It|qG^+4_!{<+#PQ0fhMz%6^hM!CJo%V8hlwraFgplF=F2s^ooQi0De``EqRN+|eF72j|3}rCht>4GVZTZ9B+Y~BR8&MFL!GmpM+ljcp=2iU%{s5ipx6rnkxy&)TXJ(lPYV zOZ%3Hgj`<62HyWH)S(S5>S5bhE9_Tr8?yZG!LBuZar?wFFy`t3+K#|=KWk*>YH~NO z#>zA*9?Nbn>dT$^asuC+))X*nZU~sY6!W|Eqvscsi&D`%YNR>En_W?IkiDI~hICL_ zh}XM%Q0!xdN-K*Y@DK-zLH1~DaSz-KKY^Nk9E@0CgRQf?xw|jgWy>b(bAOKna^l@5 z(S;h+DbQcFOu$4@%+4rP@$>|lw3W)PU7Af8o3IazlKE!B`*rd??EFcgsNphrkIM#r z{;dZO?7od6oTHI*9$E zkxwp2HBjm5JMf|nGJW@M1nn|^@NlCh8r@2u@a1=yQkDhXhWEw2%rGwOYq<=~Ps^?^ z*5+=_NI>@B0|B$;=Eqgx^W?t&8R>lVM%T zP>5Jy1oc!Fx?#mlNOk`OYX=nrhr{sm+3)P6PBrpbtz44xZ$I0k^$5-!lqX<(3It36 z#q@KIDVlQNpOp2o=jQBFl+~UoXZw4o0xu%xJBy#@ECPj5nvgN+F0l+UhhF+Opzz>t zXeptc#{&lA=!F+qi^>pUSumV@_x`{rPL0E)QwIgigDV1tqnH`l7Sg2ey3DRGcHC9f zhwSDjm)Oi1ZRCBVF7lnlj_3Pc;5<{rh=ReDRcD$SYNi+0?r@@Up?RWhq%c7_~P?Ji7O zfSCzMO*J6pM-kB{g~V?g2fN~w@TA&lXp;2Dv?41~pY9CKQ}p2iJ-az+9*f>}E&}F_ z9P^Z7`WMfVI?V0MT-#yCwT~&1JTq@*E5Gd^3F$r1Z(luZa_s>TSvIh9^gEIgFC~Yj z$lz$D3Jxs|rkO-GIPrxA3AOG6mNN`t!tr&)A@VrB3nBt$l6=x$Q_TFB-ck!^!i4zS zakHs|$jUwM*nczjkdk0yTyy?C6^0u@nu`YvI;#ek@+(NMSO$2*bLU$s@HRjbx2`=e ztZ@F{il(%C8a8;W6)-z436s`9G53qpieBkYW3~>o;|}(CP9CRQ%EYvc{i)3qt51Cd z*K1y2_-!rJDER}Y?+$TCi=gDT8b02=kG$0FgdwRz1k5)5o!rDn(db)O6uvmIroXATity65z8{REp0V_?I%0@!{#1Mc090p|sU zz@OqqUW{gSoNt2dG8Zr|`3+HyDtNpq44i9o@yHapeDwEu0rQ7qBF2C7yj#47S=lV& z%1&Fcx3v1n%%>fbj9uRo%?~w!kJ44xN1BAiZ9jz~@ETGGe7So=XeaaW7DMYe4~g9p zb39}cM-nP(NYuM5TyAMCOqzYRfKhd&9g?48Jey;qnahnLZcSbau{G+)rbq3Rge|tk z#vNb5XX-`hx9c?=qjhNB$)Xhtfv>0K8Ys#P>Hfdm!338sOTtg;hWK2y6FBWWw5)h6 zEN(w#2pD~eQMR5WZZnEvvhItx&pvO!sa%^lDjX+Cv}%516UFQ*f_<`&@b|`1i12q6FZ2kxLRI5RB`Z^@hkKTo)TIk7ab{ia3|9`I1Se2C`rA z2}$_f8%3L2pw)`Lk-NR623mii=d@bkPWy4f7{!a1uq8C~B%8cljQZ#A zH;h_MO??GxXDVQ)=`VO~bC;UT+2M}q4`pjykISCleFRMSade@5R7+FSX`#4XdOj&r z7)@rRfSFD)?6pNjhXXaJStK?@n;%6zHmEP*54X72kN@BO|q@-2Lll|20h#^IF)DEmx!0=UdUew2bJ*~{Guu5khH}

SL;y# zU-w7j`~^nX5|jfMK6J=jW(5kEpo0P?gks{#&K9Q4ILqAE6LE@mNRnG;GG_fP*|Qf- z&?A$sot^6;)%z6;=&dNod32*M1Ai28tM_7V`7bA~+MjycKm@9;)y0!n@_}8U&D~91 zB47^f7clE6=52CHp-R8AOh_LQXWl1Ua`ELQ=Fj5c?3&^KU`=BR7;O6}*iG@6X# zEm(RW9Lw|7@aB=*ARC_|yDPR3Fil|s<^aXihhFjM2uo+u5=Gqfl)c10z|M2pfPB`= zFbs~2=>==Lnn3gS3*lwMs~^VH_65s`4X}9iFk>J`JC8$gP`CBeJ*J8&^-plEe1L*SbA6r(ofn&;VoEN13DJ8p*ePc~!obcwz31NPF~)ueQ6GigM6$Ni(u zi4?=fQ;pBH0biq&WbxEPB=NHjqy|Sq_v#&(9YLK)G%moPO{TDLLy&;kCC3y}OjWRk z=dlInnJ}3hXXW#R-E(&~^CIdt>-uLO3F@UoO@L`jw)QjNdvW>X@@01J;JY^Ue>Iy@ z?-W??zZdJCv9SNu|6jAo*(F??TNEQQnN@Un`FUpOJ3Fp>r;V)O(0tNuPd01gcbTex zM#0!fW$b)jDU8N!ls?*D+XQdSl>b)(+TnfyUK{U2>E#RX{{3#~xh@X#POU-(`m5V4 zV9F_GZ;FNVb8RN$Zeq_(WYyS+qd81?RXm%qb0|~{NPjK6b zgwZrn%!QxQCYYzHgohLg zsFCJWNWT@%9*#1A>vQK|{q`bi)N~Y_Xy;x}7x~_EogDL%V)iMSN~aHrVUC=$=hOzK z$yT;GgZZCJtbx%daQaLY#5Ud0d}S3lzi$_6o$smlBX2;Pwsku0{h*A^&v(HA-<7z< zKNV18I@m;Y!|0rFVbY$+F$x1{X-M^gv`~LDbN!J$7xg1TreZQ5hL#=`N<(}|T`XNJ z8Az%?H?|F2Uelw95G8E9K*bc>rs1M4UCg-iA5?fP#H+!lpyly@aPWj8#-5d1Pxh8$ zG$|(e+8t@l4S%Ndr#)xA{RDe^PhWWOV*>M*?v_Wz(!&*c?&&>*J~t;@X&|j7M*1tF z!Jzw4|7|+nr}+^b=Y~Tcb}lky3t%0sbj-D^rRS{vzw*$El!M2H>y&7H~>`VWRq{#Tcm-P zT7g$TytlW;EXNu!AK3!u+idX0*Dm-_{RBQ%*kjl4Gmtsn7EWkJL2K_9r2In@F?vXq zUK{1!4|C-hM~dm@U?@e_lyOsb;AY+^Ckj5LWY

!Z-f&vIJ(lNT}TMZr7Q#c{%a; zAMl>}0&ccgW1UwtbQ`!z7JOhcTX)}AmSwqHHe1mF7hf?IMl(x}aif@u@*PDguQZvJ zR5&)uRf9ZJ*Mf_-PQ>p^C-8cK-*fGd_qJ<&@Dch9vcp~je?yK=Eqw6niw{>P!#3p} zoM*)~+45+e+9#-DA57kE z{|l8RT6ld{Pn=#|1&3b0fY=mTjatlu!>zoy6)4S00|X}y;H=Ad(xpfG8z7ce1$kC>HtFx&%167 z!Z!&E;H%LB?#X-;Zj`4Mrz!E|Y!jT&qo}tq8g2Qt38a`nV@q+D|6FOFA8jS^I8Bap z8wyp`iG8&2DQS3vAIPtNJ!JK6s7 z%QEp2HLkd>7uLU!R|oIPM-xObL6!Z*!P6^>dRo|X-(Nb4`)4U^~lXiO?tg++z6uYpGJ0$RW^bL|Zfi~_@Uv-rkiy-KL8r@S~BN->{ zp>SLic&z;aY+xW3-rNtOo5}3_qLJkBBoFd#&sU~4(hQwX$=!M0t`}~BO%!8zsfXBi zv5vSX(T?LB$1!`h2Ee@;1;iys5&ho$ftcn#Fh-%7wAdUVr3TG}_kl{J%aCV-XX7;b zM&^DDC$o;*!tA-au=U|S;%;Mz5!tH3Xe9D?+HQ(@C(;ospExT1w%Cr_xT8b5r6m-$ zq(S_T*l|8y{Ui zU?3h#iGZ!uN&jEX=3ImsI?Cj4f#dQUI)!4ET#OU%UEw3qc`D*&=vae=`F7A2og}<= z@Sf*KSoN$wjMtw}BV3)J^i5yz*!mWD*|o{^iFA`51l_Ms#QP?(0?OoUD%QtaqyJG8 z;o4ZO6h@OpF|Fkf#s95bFX=i$s~iQsz^+>iHaD&iK5UDx4jQ}*gE?ojpmkmx=zfnC zd~UbdXydx2?x^9U2xWhULydL^dA`6KCu!*8`BnX}=t*Azb8Ury$)^~-ty+>58zLlu zbmP&#eJs&9F(0<1%qDzu`8~;N*!}Q4Z2tNZ3^b{K_n0!+-B=5gtMstdhv2v2ec`AV zf$hr++44>M;kw#f@T#-LoCosnjh1{gEX8b=YD>;1pOnbFMcmM}rzHL9n)v9mZA4;C zop!RS1y9KM+BPt__6+VVDF=@UweX@BZ7k37Lc{m~5YHS7+eVLJWAo3T+lF{lx20|| z2bG1C`#t zRV6qFzJ_iejWM}-IKJE&0M!-L(ejNxh@8W)S+X7nQj3H01LP~4ogo6If?_6}>=L_e zxi0x_D&kJw9YsDojAc5Xjwi3y>0-s>3W%eHdL~2_h0z?P+oZX#pex%HM{IS%Zeu=> zdr@j&mE!<*+52$ZnuTaK-U?+RIcC)o0aHUUu8Nn%i{=(cCL4*k_rY&v)1FtenAU@g z_0>nE8tMggyB$7hXrb!9XRspg4SaBU1y&*pjI;AV{TGvADh+i`oi!cSdQC>h7$>}+ zNx!->C1KJ|Efz2zDCWW1dE!M|awNO^inyCGDzd=dLG0Gw@vIJ&zVVpE)()5*u8FO- z&!GA42Wofx3i3*<@X@8Qs6Oi;e4f(_D_Po<@oX5vRxLDnS4jP%3WUe=La=~op_roe zHlC}Wrbx;biMUgeq2#OiLRnYME4K2uF?y*#hC=J#@UgoF^5$7?A3h7Cxn5E;-?>@if={Dq^5YQkvZg1S+kWwbB! zo#}Y!k>Ds`o-PtbqvA&8Jj?yW6|zW4%6AdBp~qtQ-sb}Q_DFZxYPxW8JMxq|?FYwWg@KrihC6 zsc+9iMRYz<1BIxN3Z|3c%OTHw1PIv*W} zf`nfXbABQ>uF;J1aBPO6{dzbs+ZI#yeu3U~YTT>#F#@JYju}ib$HE!0`wC9{FW;WK zb;VWovnEv*|5j1fO4CT%x|V_BH)Tv$>;Rujb#P{hIvTbwq1h27@b!@sS9AV_jEgYB z_O`xwzd{@DnH0gtD;H!Jms<*$KMRG?AjNEdyhXgmVx%};of^$#_{y|WVr7P_x>$oJ z8Bl-T0+?G$=w|g@5Ww(hrAs~;(j$l{$SkUo^}g>cW9B;G&t2ZAx91z!Hyr@+{S;R7 zT!C<>HOMhO6l1K{?wR|3lgB^WO+-9AWv9CK$fBdlS(UL1VN7!txj@$hooBv4yySzh z>U3<$CYO}O(6e(jJGo#1$rx#ewN`#umHq+9@ktPL^#qwY?GUR#f1l-;sT8x(OxN>_ zhrTqCT1?#h*}x{8^OMERQ2DPqOnq!FsB<-PtRi4DJ1d{5a8vJnGjQSU**)x)6YhW1HcN zw4DS_=nrMKngT{oj#)x658v)DLi23tk8-NBc@o9?Ok~;BW`s?dQ%^EB#*rTd-B2@x znl<131ZN|S@i>jy(^tGt{3YgObe3qt8u3Z4}TTn|`b*CUyZ8CtdwX z-o!utU(F_B?OS-%XAT;?`w3yn`-J}wR=$EfCP98fZ>5;X_PU}m3+kkeT@IXw<}Ehm zx;MKsIE{%>YbW*F_24v(KjMp!fr_7?&e{?m4e1ZsditpUl`3kin(*oKzh-yn9>_#VbH#95KBL4 zo4MzLaO}*xp17d*G(5_@B4zzy=-gOI5sX+yQ)jek_K99ht6-R_O^up-^ zCWc~Kep^W=9r+=>sML#dw*D&(Em3EEUWZCNnB$PzR19aw>mZ-5Q2ig(r%^437d^u% z=$i_)Z)`6la1-eYeMd|}3DmaFz zj!@-Tv-64Y+|2Lhhz7L0ZNjFdN}&p87tyw zTW`Z{@O7Vr;jAIv3{8R!C%51@$8Pv!O_YXXQJEtv)1QJzljQ2|?^A?HyFoG1*cfT0`WtDRp981UYonw~Lz}Ffa-1wE zc?+wxsP)GNGxSiSM(1DOz`Gund- zQU^LkZd4rh1qwtD;gu8pzD%%3&5gTB>coZE-lB|8=IxZF9NL9nHp!JKOD77LDvG(f z+f;f$|DCj`!=8IMav`*=dm*iiT1;BEH-OVe6&yI#2InNnCru-95c0dV1-llF_n3%i`LXONlPp3xs%gvz{YJV z+m?BXw9>Ny#i1(r+0YL8n4R+6I*_a#g7;M43mPbg7vCXo-ak0vrz30Z+D;Ul zx+Z)1B?d!`kAoc?!xU2KZ0S3zlCelJX*lC zQOx(CC7xf-|B+tVO)=M^$qW6#?8OcA6?lp!kX0*TVrSgRRYJ`d-{nzYEAJdL=m1#`LEUJ2-?{ZGJK#W;kPc~1PJ$kb1uJ%!>} z@_f_<@jBZQ!fT*Dy;Q_-n!EaUI|Fae7QzK1YuqsGB@{v}-0XM@8KK`H+dYW$U17*6 zCEIZK`!DBq9zB8OBmVFHW~6{oA4vP8UA4re)Irw7%$~dV$x2eTJc^0Fo=!Xtc7n!c z1)S}wj-sNopgZIQ@U4ryK8+l&gKj-OgQCG-h+P!I&C53A?rzoLeyIg;?>8l3TBUp^ z?Jma{P>fcIo;d!BBIEMbj+<9Hj7d^DBw1g2otS_64I$nB!h%`#@b=1nXp3D&y`rDM z-)T=lGpZge{``Z}tGi*>_VL`z`Cny8L7Yq{%8qM!oP4P(|u=)U^nI5=Lb9*Jq*@q zD?m(RvQU0VtuKRI=dVy=sg1#7&2Vv)6&aZ849&~+AmdvY@miXQN9UgsFeBv{4~iL^ z6kTY&SAki}inx--sqC$$QIaXsV@Sz8MZEW-6;gVeKt{egWGqi1u4$La+d7)R=G{g^ z>XdM5uo3RJawW@jd%?g&J?M(xOFkbyiBlYQ3m9ejwHZkkn>mVPgMdLoF7qPe*Dvc3ux zC`soLk8MF!ve~g@4B>Gs2{u9V%cJP)v1Xw0OwYZcNZ%5qE}jhi@CBC8_Fr$$u*~ z(T{E8DtTCP}4IQKhF9t9EP>& z$X()cPcqk?#!O zvEpI#1q_ZAz{J(Rz{~OrO!T@ByrS!iSQDow4=}eGEDX=r!i&yIP-9mE4h;_gYUg9etsuO5!VIrB=AvWibOD3?18nPVb+i$3b7>AixVY6OhrunsOa$|TF2TA}+Z zYEwNw2p@&7q>as*SP*_5E!5@-ljhx5z$8;lTFWl+-ziRvxZRfP_&HZLy74DlkzL7@ zj4~B!og&jauzO1zBnJM3+}b*LOXCd=KGH|Ed*RZ`(DR@q(!=-@+i>FO8F;?10b

J+sK7~Odv z1tsL2m$akxh&Gw(c@NG_vcl@cdvVEvQCMr22N%MVG2x(15x?;`-b=vbQp~!ZL&PW6 zPNd<;BJRjhM-smwh#iyf&d%U^Vrm8b^MCF`vh6qEd!u+$Z9!*4W!1Im4(zrAc@U{u z3o(;6;B3PQxb(mcSYkzwFLL(@*QU3FfRR$nkJHX#XOp?iGWr&uE8C+P62FR?wWa7I?kkHyF#lLwc`Lp==iuV<7YPk7sWs+yF`4a%@;W7Sj{*Ah!Dm z*dFnN;Ct`i@)9maMVItQ$Y!?XfB$-!u53 zJQtUj_D;4p$Ix>M+|-g1+3lU>Fm?TUykaHBGx||rdRIl3wdI?P$F#~v^N3!8wN7J&BECubgO%PzDT$>=Ec=CAfN>n>MP*uZ-3!$!Ce?uYJy*sMsNXs zX54~Lc~IcL8qFMsVQFh5h@an<83c$q9up_WR8vgm)G6XQG5eXX&qUn%_RFMmuD0xM z(=j$-8|{F!s20rV=LCO+VW^0_JI{7o8SqxeLpROks@q*S&EXdz)n*OmX%57b-}l0y zE8VyThnWH<#a_5J^%P@pagMn4WDGM($Bt9qy@a+c=CgrWx$Nu}Dne-}B>4>}Eoz3P zwlrUwmWF!n%>?hWKOogJfID`^j;kpv1XW!-Z%5N4YOJZX0Z!#UmNi?s2&0LSkEWesYE~`~yWBd<^xtF0-BeH^ zcM6PTegjI`#)&6DW$!G={Zj{>>l%UY$Ums9iuT(BpknYLxVoT5Mnd+;GB@9ZHD|V9 z_m;kNA-oe--ySF1T2Uq30ypItr9p}cS$5mSpN3yz+Dqs$(Tm|kJzrB+oFrxE`5{bA zHH1#bcM!F+0VbbR7Lv>VJT-?F6-Q{lWWlPgy(-DOTnPV$ZpQXXN9=zn7``{U5Tj9n z!VN8zW3(y8Y(Y+8j7(v#nN$;A&U48AJr!MkgwSy+_}Gk>OnBL>mfvZ{6!TzEqPTQp z3A5J4p8Gn|MG~~>7kjcHh)rodLK>z$ARgW{x+U-f@a{a%hHIgEM>h!Aa+oY_O(MrF zmBDCsIG99i#rg_M)Z5h?I_7IZ=Hf^JlOTUQZ79ai`>6Qf(sJg)ID2lwmkn%hlc(&n zdp0a893o5n-;uX#8ligbd-xKdinX-YvtboomY5wPXD%Nnf267)eM%kTd+)*SgG{l= z;RZQ>P6I~N$a|yO=xK_O;_q!%l~e()^nZMP0mNikrowjqn#_> zLGOUiVV^cn4-Jp>hv!d@lA@$o@|7l*=XG6z$C?N6$5>s=k5>I(Er)+RogIZ6dJx4- zxo0LWfA*TO+i1_V8hvC9`c$$04&B-3hB;)=HG4tP_4affFe}xNZ^sVkm# z+rgprdm-1U8OVe;z=zlKebUM0X`pfwVf%bH9H+Pd^#f$!v@{Ag1a!kK4g*<_PoB6t zUnF1@tOd*%irM_v-gEh~Mh1@BbHfK)iieE3%6MD8Wfm+s2-P2MfM(%W*w_6Hyy~Wo zNn7dh5Iw)qOgRkQBKE^LnyxTlbSf;;*pEH-YT;M*1CyVz44&NCB76wSZ3K)T#hf;X z_DpwcVt&xZ%Cn+JV7AJfRb5jkai*3LynHlpbQ=^>$*ZrVVb1{w#5ZA z^E#*D9`Qh7(!%AV38t6;##9{X^^Q@9pthh9U99s;J!pxa$|$Y*1k;Whp%OJajnA(Y zZUMft_;isX_3gY4)eCom{=QNYerz2?8XrU#WeeOKmc#xUG8QAF+Js3PBFC(v7{B1e z!e{Z%nME(OtkN`|*z_-&vfLs)#;{#WWDT7~;gi zkQopRp11d5@B|0^^@L@cdfVf~82L5|<&(CVV(?TiX=LS1W>&O4SEJw~OUl~=gEI-^ zQ`8B(ar5dOipYm;@wPd9%WuL#8h%3Ce#B^rJG~nrc&-xUH1EgpLFV{A@iyCfwI^EW zmI$MX6bZM$UWyse%}+X5C6DP%)eou9!-?g}-k^~CRm@99&T5z;f8xQ1Z9SN%jO*i_Bt zGjfGJ=kNcJ%+#=j-KJg=ev7-_j&^y!SHr56b+Fn)35Tg$;oN8i47v3H9tBiE|K&$O z|EnIWJS-UR=k14%r#4WZ=!2e*7xv3O&h%Mo&wcav0k^~2pk`u9 z9;he?Ar8Ekss{}>ar!}9vmaT}XdMOIO;k0&*h+Q@kF{4 z@fPbG*u#7rY|rKP?@lf+vIh0Dq2%C2C5*joELeo|Z)jd>#oy3l`zYXz)@m4a{yg-2 zJ`=75T5`pc?#o7`=x~2_dvIsh`eTFM7vb6j$luTf6yrI6qj;KRG1IDJ&*`5)(sW}C z9NkD8VD*)8LZT71)$fL0KdK>7;WfNltA#$-|3T`@*I>4th1Hq!;BVL%PNHqV1yfnW z)$WtHbr!QRu5XioStiGD6ceEkA@;lG&Fpz?$AyixCcVxEf_X={97A0c4Vu2f^p+A3 z#n9Zs>Mx)f`4@cd)j^_R1w4Cs0DK=#=1$aDai+Q!+^Ge~1^WbIR9TCF`7OuXqnHwD zq8Qt3nL)XB-1KrQl6E=-hFv~Ic>grs2a3;OXE$a*?wJHZXOn*K4>bOwp^t;wVEmjD zuyfupF8G-y*ZHwoHm{!n=e=?k4p=C^q4RqS&&^Yci5_uGd|CCEbi{f)?q`D~JMKyd zTvd1}sD^Z|>7rj_A`M3mgIg!(LcQB|+6~zW`|>})rWl%f6`TW~io0>MD;b$luTWY2 z#gnohyQbp3h4L-#C?^5)nxC|;o#Mt5S<)RYcHEsuSJ|*v|AEJmD#27c%v&3u@0tN4 z2aN^=e-n5<#0;vQb_n7m)na?h6_tWx?qb&0KUFN*kszMhzdQ5XV;p*3l#BX|`Usc? ziW&5DfH>;ZB&p|n5jQEXp8ZQ@hOYanN$$2k@ZtmYu-j$=f09KoM)w7=`O1>i>UPkj zbkx55K;e@8+!nHXr-$u1k%$BilJw1NUFPeXb zV%T=J&$MZ9;MI9SpSI|Q8rmFfC0k9bV9ZU9JimU7@a1li^*0#*eK1Cic?qW1bII;C z-$-#&6_KSrAcx0z*ihb%v>qro~QO@rQz$Km-ZQA{=EZu zi-|{-pUBiXy}?ztoLoyiK|D-gnsG{$L|H{HBUbSoeT<^&NxK ze@BJURRwKseIpT-?w~)p zk?2QWA=T4+dh<9?!8WhzhapF%^mbDqHTk_CfI2pa%`RP70WcJO7}%_%!&5%Y;br zIczSZC$)eZ*8yY3=wa-&JurG%DtUN!GP~j?J%2OHhWK^9WmR&Si$py`DmJ7rF|QChGbN2DfPTs_GYr`u#}=+lm|30=sqp0nXIJ{Q7k; z_?;DebQwwhP+Pq@9kh+1a2KAn$`LR#iKAPo@-YW6 zeCbvk82U)SM9W9x#bdZCvF25j^i#6srae(+@`h=M<2GFtCT-2=PGQx_`*QG^Ugk$= z;hu{6bix#H-$5(vHT)R7-2XuGX`L%*-tom3+-!_g-Hn+~zYCbf^6$-fiYX~&#a#`a zl6}QCoS)KHSx|+FY-QMJB69x;UOPI3Ri}S{HB5A&%L^}BOnLDIx`xr>qtpdAFFFU; zSVjC^VuYCEjAhAAs8_ZI-9_^1;3qj|I>i_U_7aDFb&%{xwc&cy70F^!^Vq0@{=_-` z2Tfe2Isu0kctGv-d+uujuMk>crx?X43e=(86?<|;&>7kVq4uh1nc<2T?>k_o@lwoa zmtUJM`EG3<#aK5KdWxG(C4Em(322?Vtf!Bn%(XVA$gAupY!2;&&S_uaEM0c+n%hpQ zv@_Rj1}7y&)Gc?Q&an(+PBlP@i4_i*V2Y1e9em)t7>BHrV>Zh%Ar#Xm=(6XgZ^{yK z)`lCnPZ_KiMX;Wi-ZT8m#`(n`VbUZ@>Zohb0^8}rXrc}kFw$L3@<3A!ste5msyyKM(7x<+Q3@+Hj{_LF1^72vsEpX5CCmfBF8_iTdZHCv! zzCk1vUYMk%!=hXOZb}e{Rz866^F#4mZ7=+%z6WdT?g*o~Dqp7^pcuXRSH!B;jCiWL zE!Rl%I+Ik7vX0hQSci2q-6D;)E7DgeAM3_@4OPUoLh8&mK?zBy4tGn?3~0UlA4EzY z!?=___;jQxdOlo*<8`70Or#tWM=@g#r-*w^Jtsag%$7?%lSaQ=-&l(hn&!Qdp3U@B z!RnsB;fJRd1}1gU2Bu%&xAhnB*7{v>r(oA*DqVbd0Qv;|fXO!cIJmJ9>I;L=HN#85 zG|4CJB*iR^pDym~3KuV0Zp+o(pD0^9G=??peu51%QbWF7A%q&A+p1{es5OchT=oZi zJbnYSm7YqyzeG3gQE<;R9&Bi#KWBOqz}t(kc&ZO>*r+C8KFM!^bc*Tm>w%}m%DH0w zG+XXmwUbQmb1_?YPOLJSN=N#^q)zI6*e?C3KXkL$k_L>3R^kLM+d$sVCt6nn!~+@E&g?Jq^y*H;(Ws`;nb zZ8U#~kKCJWp@=;$>)?e9Ra||E2G-Gy2cJ!}qB#eCjXVeM<1^v#MRWYpk_xXso595Y z9I+~)j^RH93G#PZA;q{q{#WEU_^#(NeGwPiUy*gMf6VIM%45I1q3-Y#HBn=}5;B}F z@~I?zX^2lvGHXr1f} z{kH9dchi*(P%AVlU8}+d;JK>Av*!W>E7>C(e6Z@ImJ_VbY!q5LPx#6tgCzchRK* zQ>5WN?6~_6mD#r&bJ)_uOWErd#>l(GCk3hDu{S-i_(~7#rlgBKc4(keZ#~TWR7_Zt z0pN7W5hBm(qP_iSIQKD2qPM^n^T(YO%63-r6OW%1Bl&)(sB=-6GxH!w8n!wzqvJB7jK0>*ui zfYGEFv)ePI(MxlslY{AwKRZ@4_>{k}&LF%3Y+pA{+b9as@{yuGrmH$*} zHQfkjk2RMk`vqv@N~$gnIB<$g`5gqyKiNX5Pj{SpULS&uN+si+tgyY?IRPUZCQO;#mzee%p|dZaif^Jr?%3T$X2Ni#nhfIl9;uq zunRge#n*e#Xe!#2e6X;a;0$}PyM=J4jisZ}$koQ_Un!@{z)-4w*bv6{(YnEi8x;sM$e8{~Gpt*yER1GYoQ3ds@)+K@Io*0R3|^1` zqPBxj9#5TmdT4>^q!W@d`u0d4c|*V~8ZKabDJC*xqZCwCneFrKxR1ZqvF3{pF|&5} zAff6;!e|D#Dg6)gVwet=OwkrX>N*@3z}{0Q;i~x&NJ_H8_tTX?_RX3s3^&AXqVocV z^%5|F6mv6apY+;rbtajfc$n^f!pz@p&CK0DfVki6Az=8=+Ad{dl$^IfJ+U^90Bz)B z57MkR!R4A$@ZoU+j8ikm=x757dK5-HZE2p7rd-!~V}yVSq8Mgjn6%}KIy1=8j$8S* zzr=L!d5_~MzGU`c0|66BD^X@Pa?ArgEp+LvjW>^~p~}NhFm_FVoux-%N`WEzZKRsc zbitu%=`_lEka;+aM3p?^{o45F@L1)TuYr0yB5<9|0}Q zq^jcUi+4lX<^8auJsLEJsN&uolVQ{2;qboB4wrYO2;ZAqa?Eaux%O~?v^7 z%DC*+G;sXv3r{zQ@cWmm0_KdjFq#O8dF<9#ns`fr2~Va6lG|n%-3hOje3;}Wt}a8`rH?od^6 zLE1G4bg+lT|6PF7KAqr{ISN|)E&?U{Oc)reAuI=Btbj?Om<>6@rD5kjOS5N*INgw& z%#&;fQqVAvgwaRvm9jbB(D(_0wLZlhG*rO>sEre-8o#h&u*~+EhivnST==2f4E?#W zP&FbH=5N@?+&GBBhoD@pPs^g1n3{1?g?-i1Z6M+dZ|5<+{+=UQ2b>A-4}E!-35Iz5 z06x=;9}OQ#!M_EfXp6S}llL-ZvVe0B~IFdyZZQi@6Injno(ogkg8CgLiq{xKHKe+kz%S=_qsmS6=Ic(4Wd zR1)Rurs&qA9pYMFgWIZn7@|QBm%qAk&a^4B-uEG-ha^IJw_ot@Zf|Y{4Orzzvq&zu zte}`)I|HTG`JaoPtBN?Y)#IcOZ_&GC(>ag0=y*t^e$NYNPcA=c-Ci1F$lPyGy*D3j z8192l4;p0^!?n2K8-76Wz57tODHE*S46!{-k?Y*nAlw2XxqP&SVwQ}VAkA7^Tv(|j z;(A@vkffg!!M~r2B$wt;Bl9O=uo-A0GtDXFBVIr3Z-fxDLolzy32Hx2mTkyNmYHdF zg3%8tm{b=+<$Y%y)#s2*eIOAqQaR=W#n^a@rG3*=JT*FPIm^)+q}MQOa9lM*Qrhc1 zxi!%ps&{_?J}%^PNDp*Yt*7R)0Jt)rurcbyJywfd(a{P1{c}L;aw$wb;fcjg(ae`d zYS>19Q>O{HKnule6^o=s*2BeyEw-Fjl!!E_jD_#<$0Zrh50NwnCE!nSFFTtHX{9%& zyav9HKw(M%*%YGLeL-PDOY;SIecnofH#Otu4*- zO%iW-W6Sxh{U|A_8v$hIDG5GYNiqh%A);^ZfX`S-(Cv=9GoHg%8x7!IA#pR%0ryRZ zNX(_5(6&7q46Z+f))ljH`Hwhad_w*fI4{Sj453*On)=e96R*X7mA2gElyB_qP=LK3 z>czg7qsWr<*QC+?E%3oKGk?=wwdM*i)z*Vcv8ze@J#9FDG@L}o>QS%Nco@}}g9D!z z;ra{Vqz7mVqnRYf=u(XAoriRXjlQJ$sV&z`UHaNBCqdT49#RF*E5y<1Gx4aR?Qk^B z=hqu5L>}<~6w*z=_3tTiu}~W%1y?a{Ck?HelmKm!d7u)w@_!;S{@R?BUmH`3N&B@z zI_RmZe0)0s~)af{|*04k8`=K;6cAdQhF3*-}A=R+{XJWFX?1gU7+rH4;|;x07ar&xTh4 zM#y8@ zs{8C~BU1>OGKEZuNajpQrVtV;g+eHWObz#a&XEe0BvaBPq=6!(LG;__obURq^=qwX zE&siqv+sTO+56h>>-{#mN{yn)6nH2@-F2G{Z}n4=W^Ng{zb)ehFvaSoc;jJJ>}PNf zyo_65{lD+fRDKCR`!o%UTr6?OV`6@mcK}{~OvE>GmEg{1GahqX_AKA)3G z?YnKxHcIb>LH|ypw5>B}=hSitjCuoJUR96;W_YocDsFbo0GZV9P+HakPwSKL{Yyqz z-e?Sdxak|Jk(~n5Z(qeT?FQfvG5=xiX?6%(j@bk=Zij>Tpx1rs(j9a5*~*Wg)VZ5V z+VEMNLteMaaMFDF^F91|LDI3wZzF%~26!L)1(h=2pt&p-r|oHlpl9|tGO1GRI^_^} zOWnaIUJ_H20@C$G{wjpctslWGn_!w#;QN4Dk#5c^SucXmtgQvjoEH-}43H zo(xO8BaU1dMk;)%!jW;eK7Vbx`k-oy; z5Z%xKtLck4MY|aim#g5A-t%<3vnEJar{kDy{m^1Rp2tXp^GyiBJo!7*!{%%rrF77o zeZA=~eQ0?bQVdI`>NTH2PCSty46KEH{X_7Vb()xNy$*BN{Q)}TD{QE^fh&stfVsXd zHp*h?&vE52ckB@SYeFHc=(6K6_k`2hE`q5ZJ0 z3v+wlN~m6@jJc_m2&P;sS={%klp392&IW2eLwe_qdbHo6`KM`j?11vtbog$k zgwGMvxkA}Em~&SV#}~H3X8)V`YvBXH$rdbgcmbOiHJg3=`X6(}Z8La2G~_Xhgwjw3 z!JK=yRb2bHm>RvuoP7gB;0d*aUh%~O@xM)L7igMALDZ}&-eMxZbT{b7D&Yo~Z?M%q z885Yr0RN=}*sgD`th=2Hn|-c~vC>X~xHLx|ljz95H(3Ou<lh z25(==9FQ%A_&F1K%o_odM=*Q5R(rH8ETMKgnzLa(hv1OjD3sTx%wxFX{n8>skaJqW z+Z*Pms6x;}6C<@3SYf8UC74*H6w%H<6;xl78Qb1w3XgnV zqWY$z{1k99m&G%Ne?y)dRRFKdK~K$lNPyEo-1_w^NKHD94NV51fA$J+@#PtGdtp49 zT_y(^!R6$%FqX$;379&9aZ!9Bidy=GT2*DnIybyP_G{gtD*m!ad1e7fM#*7cRatnw zO9`?xQqZLSfh2QX1BVcMFf-p1_-*YFWbUjCzE4gdCz6ZTyh#q``DMXR_fb5iRlqb8 z%;76vM0cKdP=zne*h98U&`zsm;MH@0->SRn55Q$@gQ05CAm~1lhGIrr!Cw-x(Hr{> zETzujUCEnJw~RWZSqr^{-1X|6>Lln}AgpQQ1xyFQEGYjWa?X-P<4euhjLQ?y(ylPr zop4GVNiHI}JA&J?PQd*(!DnmGP1%{ig`aR;5f57v@CMmveuwj4Yw-UzPDADqm#fPb z{L^d@D!2a#W_Nd&NU?b!8d+k-j<6^a#T<`>B?bCa?^70*eIza;`VrtFzXNWo%pz`= zmtZituJiu-69RQE;iWMYdiN3I_OYADj2w!e)NaGe(u2TlwHc3jF4UnFN0X1V{vVM^ z-(ZwiWX5jw&_}HY!y!WTg@HgzKv$BDnO^p6XPS-!W23+0s@G5e36uLhdfA77F z9*!9grn$*f*fC3d_^>*jchLzV)0+7;%|XCu5)8UoCbD+2LSNsRv9{KG7>||+ST^q@ z6`D+gQ@1>6mnYY%NyHpjHi5S>u-s~Z|K0C{T{Rc*Yt7q|?_M%+|J7XZ{uzsNMyKI5 zYlcJNMM2AvE65Uz2&U`aZBc=rJu=fYXNPIeXIf0dK-W-N5)w=T&#w_jDpkjP*Y#^S!u5R;jSStQu}enPSdmB&hES zF5R3WS@LK%imlE7pRbOX@gR2h+_|xK$fgG_Ln5niTVlrpjisnM4ki_ zdNxq}(peY%nqtoWr>+MY@57ms)lCxrzDICKqKS=t2Jz_%qdFKEm0b&yi>;4$gK(|8k1_0X`~&1d%p`L*p!XA?_0#AFN6yfi#U;R1ZaFjh zAZ=Nkms4%Gn`@k_%oBj}T7L^+@>jAiz4x%nd8}@Fd_UTQMkq3N-$yOs+7gruT;)ybN2BiVh=j(1j7cOrMbCD?zH<^h&>9m)59E6g+&H<7Z^O5ZGIaxxx3Ng(JD~8Aq2Z&v0KT|GoWuu%(*=~at zp0TAI9v$|=bs{6y|6T+C+bk3?F$5EP?~-Vq&N*rrx%Z6paAve_pJ(>l+@-CKuZ8x< z7vOk+0=`(HfLnWifpYLCaGrVw4!4eixS>f*660scSTt?=m_kd>d zC%Ba04vo>DP;TaODp$pw{&BMiMrsYgtM)SRyv!NPJUJjSC=BOoHe-Y-aGhWrFN_fF zzc7AZWZF9oapAIweo~J@ucW>(`eu6SuFSFD>|uCY7Y1yzT#> zx>gZCte3;wpluJ!K$m2%ppzAiNO@K+n!bN0OhS6tJ+BekUr~5xZx%9jYUVMkgf*>@ zVDw#*M6cdF7EKsNB#Ie7&^_G+Or%o~E#9pP0hcooS5@!dqJ-0}6maFWdT1=T^;kktq1qsoEE+}Wdt+YwM6u8aj+{`7SlGf-3^KI)r)gZ?iiZ0@XtqbGla(K_wOw^j9j4wtjc=7I4h5~1uYjqlAB z`qsFO6o*+W%(O~^VQ>Br6}^1!VI54&vt<9koQbQM;ju^PD=ur`^A`_DCA%1pBg%N_ zI2G)_uMQm1e2}x<3NcqraPu-V>`B4{V{BFNvr;+iesnCZjt|Gtdw21eUncyC;4{HE zH^@`l7LU$78E47fOu2}ZoaQp&g?eC-470dBK)qd1wv8_fqR-V;b~e4X6zabYUCO>@u>{rt3D(i zy&o`_F;CpmQ3f8H74a}`+!-?NehI-JZ?O=8Jz z&-%jL%RWeJyvDh2bYw6mgNxo;4R;zyiV``nr>?K(iz!?MDsQ(h7;Zcd+QVOi^c}!| zoS%TnQ1YaW&NxTuJ&$=Pd_8pu=0ZuPM{rcD`1Bo1c1U>?bGb$yOwxuUPG>V_$^dLZ z>S|w}5bL$?gE6;sa`Mq||5osgF@-y84?;rVJuqAZSQ4EBbM};BdVr9yw5G`Mn{$o^}MIqFb437?3U|byIdyRsagP zI|!PUt|2a}k`u$qRMo(lMsjQTPr&31|H~UUR~S^l_J)D@Mg_p;9j5rdw6EY!TrgWz z$ZhYNNd9T^g?*X}!K5eG=T5q{S^V0@lHFLGioPEVMvBa1w9JnT+BgM%tA2{4Ed|9G z@Po!l;yG#WmXGI21-A+Yyof{Pvj)MoH&@+DdZwbwwa)le?js)4BJ80N!L0P1oiq8s z81cqN3l`ec(5cskF!OdLn%t{^^*1RJXRA8+87y4nb2IJ68)Du_R)(0%86cyGqgbFHyVFl9&;yxaB`t_W3~nknm}CM z20e$76Xb9>5&EUhI}Nc6aU~D7Wpy6AvX&iV*#nd@8~6?5b4J3!hx{|^gDuRgow}4qiFq?}(w0!zSj}6z&SwPXK`p5v7e_aa( zbje^PGtzi*_AL0_ss_&3%wPK`3|LIwB{Bt^PQQR{i@Sgg(Plm69N5}<)~t&`8?)Gc z4Do(Q;RkKF1HVEC6O88Gks|eRHlm$m5B<={ik{xphI$qC;7foMmaI|2R!f#Z{E1u8 zzB?HzOveIe4qQX_WW(w@V3QFE>UPOz+D-m2&-30gXBKT|*3PEzMDOD~##?A$4keg# zc5glWt#^o8+RWIiEtZVGel1FMlLsyf?@W#&E@QPJR5lzuJr~1|(VgfEEzcj=Z{!cg zolAA`<@b@I^`qz0N>3)y9m~3?31jT>LfMr(#zZI$MG(yOV=g)K{w9lx6V2GJGozW~ zzhxoXu@iB=99&eTR8KzYNE`>TA%o!hlw0U{Dbe4OdYTRzg(F_u;R_mS=(T05RMe|QB1GhQ%v1prMKH^2oyC$MiD=1uGqzDboH<}M4ygraq4Ie@1kA}KGQk46ukD#9p5vfqAln*ZMH7Rq+9 z1oPj+RIy@TiKxfUjLi=}$gDE#5jCmAB8#gnV11Q1j}J^k`Ia`IG2uDtj>t!2CMsjD zkHAoWDwdIV#MM)@fE}_EP1qQX)TEVQ@>8PLw|>TBehZjnf_dchS!}+oP-Okrl)dXY zjG1=7OA;S=8bwa|3fvU<5&axxU37q~{I@7L{2SUxq;Q;N>*?UxcuJ%_#v63OHGVzX zxaK%=wpD?Mh4T1Y`4E24T!mWaO@av;DlJ)OdsF0CZc1_rx6*B%&*-SywJ3DxCy2{b z#*Q|B(4_!3km~)5CJomFomVQDi$Drgn~Q7AEdIA)GVnRZ|2vta&%P*H&SRbk6Z!$c zy#Amhfm>msb+=8~&mSb>iq%p~dd>=zNdf|-qg1ip?U_*7aga~*Q7sJtu55SqMh*0R z^2WI*bnvl=d)RINXzZsghCf?JVB)TUpOI!jZp*P>z_0|fWv!y*SiZ3+{gf$--S49d zslynnTO*KWV->_58Ayz?QeZ)U9=HdchgR!MNNQBWAw<9at7jbkVMf%epo6Uz42M9k znGkZO4)y;Ugip>5<1yAk1*(W(R<@`~Uc5Nuk#^FQo%6bw9;;%@L|9nRArC%)aXpE2 z8&3l2{QK#!Sjo^1Ps8bW)Bfn?9_A9@v;94)MNE2Oh43Q*D|!Pnzs*hW`M6<9Co+^b_7Z z(!g9o*_Brw_{LC0{5K;3cUe+cCT1)gu>6c%8dWh%WIo)W84H*if>E!RlGIP_&N=td zlzs5&KL~b+pu0Di(s{NOz)2LFx7Co)6JpUqB=MDD{V?ba=`i|H3MS*6v8U-@h!ai5 z{lugpYDyfWugipUH+8Z2Q8|zKC=6O7!Q?)=EG`_cmW%sLS+&G-@czUn(eyi;Y4@@> zaH3S3|Ewi5eNaAxWO!`rhMwtKIPXmnbQ?L~v#kR#j2nq>7k`Fz(FV9((H5I255#l+ zubZessHe3PjQF05_{6ekk747<>p8<+9R6`4tlsmP?!EjPo`2NgF+O$u*e>fEENJNf zwbMG7vzuD<)Dt@<4#HpW&%_Bo{=ncQ4Sc)I8q4mffc&Y#(%CIw`Uoc2d5*X#*idxh zHWB!rSwpuTuSAXKM>07#UI8ajv7zCiuk{MPdmG@QrS(H6^vhO5kd3#&E@y$9oJhCrePeu7pkQlA4-PGhepjCiLY~m9$!R z7$Z>|f;Y}*nUE@Xvbs=c8XRGQeC4C z*%xIPFVAxL>PoCZ4I1HPgesO%>jR7YuQ2|D88+Bk4#5d5^K^|GJJCS{FWq$jmJ?(8 zxB8yAew-02&Xi+0%sAmHVmQG}yQC!^FjtL=iLzkZi+_RA3N`46ct*Qleg-phwXi`@ z3#_&!Swu_!k(;M4uuMiDr#{YuXZ~ueW(u(KCM03jb0xIiRmRV*&BE)?Ok|_8EqKgU z0W+Flc1{b(eZ0(?di%tJon6z6c3vR9fs}*}k$%9JyW z8cY%CvD67~c5lyTkQ7XXqZZouTJS=g-R{kTqbZO1BVfi7%!?lNoQxQE>PQ#q^eW$v z{C}vxy2QgcerYE`=YMlh}zRWUnmV534L?*dlLtRw5<~Q0y%D zx>pB-mOp+vY$O{q><|CjEEh0S2}bJC;p|KWZ)%X9CF^soglf*qK?>G}^u4TQkVm>J zxaRU=k}S`4uNDzI-Cnyppx5gHPSIDGPfL_o{f9rH^w&ffeM|$p>952$-v44eYYy<3 zRl-%oT!OjuDJ*-FWGR(tZAoMaHzd0UWFd`+0l9LKII!U38wZK zTC%Ilc8lhpd4ZD86Go^G2pu*xOl3=ujF9Hr}@YWnSiR_bkuB5Zl<>Nqf31x<=5RGFFdmjZT&Hr zUj<48%w~f5IsJ?~@;N~1JhNcqllF_|3_Xt&7Cl0?vJcSH*d~;>uob?1Gs5@%24KGx zWu$P@i)Q5RNB!6Y+-6NjmlhHo&fXT3yGIJ|eZ3TSbu2`1EMpamN+?4IPj+X8g$#T!)S{Sh@TZRRlrzfJI|Yx1~(Dg}FODG2k*Kr`!2p>^Iw zG|#UIzU?FRwcJh^>$nszn>-zD9%sU1wh9;dhY6-XK5q0zg(&JCF`C(`bV}knbsWOR z(!e?@LZfdF;@+F*3g(#e7jUmBhK?ul@HDdhe>xlZ_6-(i=Ar5Rt#EeE;{WY*xK&_| zaKj!=Ffs1AIT|NVQP&&H+4!q!Vg-|Ns8LZ19OWlM{?0Mrv-%r+aI)lkJm`ndK=u0+ z@J(O9mxkPGN8>@t|6uLS2=pK6n=;Pu#n-M4#|BdSFo$7;37tSNYm-89b(k~MRZ<|{ zG&+zZ8BRe%?;Aq6$^|H*&+x^R&g0ftDP0+d%zp~&?_YrA|5CwfpBXOMd=y$M`XN7M zE_&7U0u(R%;3+06K)v%CKWOO!CWT-^dsA|0zc^|+`Q9jwm8OpVRz$uhU7-9}1r*)O z<1Ho*=-J`{$5gSM_z6ViJ%Q-#N?0_?2RhATP+nplY-}5f?tjaJ>TljS!rB#yGwuR!K-8(cnahl5rR#O;qr zT3IRa9VDIu`b3SIxk4US^`<~GJ5^FhdOVlC@Wsy^G$7)AnS>j(t-^%PA(#_&cXM6S zlBo5g%-Dv<7nsU#oz&{iQIM0=#n+*^#pdb(dn_qX$6L?m!`Kh4z{y8%Ob6^gLlTR?wZA#)lGEI4!s zPJL#=pp_ELg3C_gabahu+T*5dOvwmjb>SVY+bRXkM4j4OSPRPJWH7SL5y#1E;XTzX z44m;Bwh{;IfG7U=q|HB&E0e?2w8bO`>@g%Iuc8Yj#HXWf3?8}oAE>`E;s?!Fz|<3r;)v$lfpQ_%tilSscH>54E> zdCc8-V6GQ;ugrd&ET@hCJ(^0-yKl;bE&q!w)`fxLtXwFLr+JL4@HD>(#w;*JT)+D$ z)j8FKO*Wawd>+@A`w32lir7Ke3Qqm$A_|`dRDNOS0}M+f)!b7mm=7(S||`V3TIDkf>FKF zBR14pLk;gVW>MAw)Ol+lvm@&$l9Bxgnp^tF9ZotdU#!pT(^4a^L+w?0to!{3)Gi3c z0bl-tPbD!GKDnITv}i8d8>`8tZukP~#Ho~fJueDd4ikbYiLVn^Tlr823XR!s%hJ$- zI|G@!=Ymnrf3Rt=~o74PvIr>1-OOZ^Q5O{=matB{osPll4nM z>|OaTCgU3EWNm8UF;|2GyDh;ydQ>RRo=8y+*Nxc*%TH+2CS@j}y@_fjy0jh}8C+rQ z1r`JHcw5lM>0V%*t$;aw+Jpx|_}h{OBK65+?tfKb_qr*v;TK{UHF9%hpDfG2H=4qr zITMU!^A)icJB(63ZOnGRe}@(hdqMlEDIg!KN?6<^%eTsh;7I6gAc;y23cNV!AQ8xV zsjtILIiI0eYaey_(;<4(oRjpHRRfT(f&zY+Ce33e2=9%EU_Sa>5SOYMQQG0gtbN8d zI_k=4dgPwmXG#7E5UeOP$;GkPLKA9keCu9tSfh6?g`RPbB^P(!~-z$bUs~+%} zA;N^7K``IV+QdyWdqmT&7_%1jgP8Z%ljutk-n9Sqa>4tdE)#L7BpQDh^dsyoN+eM` zdx&z?bMX;;G(-g_{MCYjrQ6ZYrbu+YP!;xhrbEW6>pVtV_z)~07|-eI5~k;asP3sT zTXRv9Ice8L9~(G|uAE*5U&v`}hI1uaw@Q!qeo#FB4<$ZP$MJvOg6EN=IP-`iuB{sk z4_^f!R((H;a?t>l-50@0H;u<+3z!uIb5+q=qH;Dvbfwjpz0h4t-&>-?HeY&0l z*N7QAS`M~PAc=A2FHww&9!N(H!Wnhtu&9{0C580=?^eq3vJhNr`0FB^dL|U_KML>7 zdV=wrVJE?{dqwHSCTyQank2i^kh%Xpj4pC0fuY)iFkUke7RAg5tDQq2e_1dDtt8(a z+frCD^8i-e*ui7ISRTiHYxMBzdoFkta~k?~3IZ5K;k34$VDhfoNItmhh|EdjyXVhC zsQolzb}!va$FD4grgvJ{|NKR0h8qy776Dx4Rw+~mdl7?^y2K4Q-l7!df0;-=2*<#8 z`DJ)8xE3Yc($+4@yiB0F%S$Ce!??0L9DxsGU{qgtxz@YTg|C`K1^ ziI^ejwUF0-1EP!H!*LRZrc4q{2YwE~`cjYJEzz{Ckl%`W6vl%`%p~+Fh_nE^zvMBB z!s~gAV6Ht^mz;OJkz-qC!s@RaEcUew6L~LlVwxY90M|{#>7nyfK0?v@Lf&^Uu1}u? z0z83rwsUZRNj4P7p25dsCgR0Sr{JEn2$BcifZUfd{OkEmz?>x*haaWlVQ|RpuB|C+ ze=`hPr_V(@3KSU41<%1X#*ja-hg7z}!Gvn)AOBX}@6d8Q!*=5ju;)fae^;o+q4~|s`V%UYkguX{GPNN+}hr)tI+s)0`eX}Y0 zaNaNUs%;#@y*G;u%y>-vi*6`-TElnbTN+v6nw?J|YoY_*XL1S-jW)+E*D4`65##-; zGw>L_2$)?H$4`On!c3zH=EB4!9(4UR(ZXmm_MiE9x?qPrn8=J^!kJPi=rrdsmDzuJ z!*lt>HrR1=2sT(%0%`A@@GvSIh7UEw`-xWI=9$s>-!dOu^~ej>emKZusszkag3&nV zlJn+!m8kW%8T-NClqua`fL0d&q%*rq;n8bLJl6Fa>|QO6BUQ+?s%k5|(Hh2=hJwp? zz|jkhs6EjTcNtW|jLZ6X&Cbzyk%t4?zyBD&Ro^cRS~J ztq*>YwRG~F7myxcjk!Z1SAi@aBT7BHAGB{rL*PtGnzyXy>Kq67FG?$ z)31-ho>%TL`j!V7De`ww_av_ZXvGE!J7%ADo+>33&_5u(|IzERq|_Drg8bn@_^i zG!Tq*A(g9o%$E9@Me1os5>U2H6Iwj=FkO`K1l9zZ;L2O=AbWx&%-6N?rJ-dbta0+G zJWzO}#P+03W(}sj0Z~+p zo2IG4a0Q||Wfsz$>74XR4eX3Nh@wsf`vsGez~#@-Ia~*~lh9yEzaE>`yMT>;p9`DP zBcQt2otSC+k)zgP)+*ne$6OXLy#(V_^x0#3%490?r#V{}*NCRP-GDM|zf0`;&XMFE zVxt?<0i2CNYH2%!5B>=2%l?3c?|v{Froh_xPiC3&Y?$D^AM~v-{&aE)t{pLsjZl~7 zF^ur_loLrytv+rkDn2!riXwMwZqN3i%GDFl*}gK#=Ygw0^W$UiC%!@(7pUV^%Q~Pi zznV{Ao|NYb39s)l`y32dz3SUw^eh5?{=isv9cjq0R%Rh6nx6u4!e?zD!6fU>7p>X7 zkQ%3A!M1fBLCN8j)OG)*qNT-#5U+b2+O>Yca)m*d^SMq5P!6h$9Xp8eBWAQQtSU}Hg9bj;Xdiim$B5w-)4&bznYD=@ZNY4jO)|= zqCeMkD3jM_Y^kX}Eqkz*{`aO11z5X)oVOk6!TAg`Ta0k$8buuPv<$ir&W05-Gx!}% z-4#!K=0gt*K2EZ7derf`E3SBvoex3X#AFeW`YWu^vk9i(Y>P-^oD_BJh#4C_C6=BX zP(+u#lY{V^BuY2oAaED?FKtb+S|PCvcP5!@F;^jQ+EuWM(#Pc=uEW6+Dg23)ipqa0 z;+)!{xcKG~xH4Rd#{>&&njgU!-*6J$4E!VlCo?wrRSA9N&wKhpw;C*PD}uM{##-WEnrQmjgWUgJ6#$9B+J2P?$?2mWhXWDn+BOO36 zx%rbsV^^~x=clIZ$me}%$SGgiaj+$XZ~sLO=j9MWqL8%gt?=$s8vN5#Ui;3+A>IkG zp$(d=QR&9BAUUfBBhRX1x6#A!y`10hr^b8m{C_?ohDsWnV= zwi{i#SP!^fT#J%Mz6DFi$_DQ}qKQpLzkt-GjS#)E1zZmggQmjM#J>F>Bp0lNk3}R9 zT1gY9kUpI|vz&R%{}qUL5zP9*AKjmSNEWe5rtDn59H!-DnMB8^3vsqNT(VzeR|Rl| zt|z7B7V6q_D6;J2J&1F#2wxp&kLQqhy|W9?!Jf%aV0J()ESYm10$vsKgC-JY+ChT( z>hPa9sUlUBCpKY2W^7=FpB;=G%49+ERu1?6YT^B%xi%lpmxJpm@$|CZ9kv~;o&`uJJM_;6P&-gr1<~$SjanLWSG~oc1 z<>v`6`-uH#BvGR-dJoTC9I#vNU>?&DK%DwWCA}kJEM7Om3Ljct2`gqT0qV{JsM7oZ z1rsYlAx(}SG#6p%j3=0iv}5Avon@jI4aV%+oo^*CHx-}^V`tz3(xY#;lK=ZEkRIrW z$M@^=nC9Pqfs-Y?h@XPz#SO<7qgi$XTvuB2Yxk4~Y0{4s0 z-6!T|2aMTll`tfhbETfk)}d(qKHxGWd&$M{c;}IL+HYd|I*U-VS`!?%lfeOgvtf@@1w2qLgsJQ-Sgb+H52R+}Gjb7L zQ9-P~HWV>$`wdvbQJQRf%ylMo;ZwMKy_Cm{5`LRzf?2Obi;XtE6GfXDvD20s(=M~Z zBraE5sY<)gz;zQj&Qb&Kx$z+LCJMqrRmcZf6?0+2lMk)M^UjaJT?d9RZ{OTwjuW?~ zb4&ZFnf@72qH~wW92b6@4uZKozezmkdWmShh7o&en}`%mIxR{iqr*WI!abPI3~){ zH)0#!sW3m!)X}3$e!8@&S>sb#&iS6LX)nY?W}ltjGyZ9ik5d za+af2j@yxzjy9Y_i{RHd;Ua&UU^JsiFq1Bgk%YC1L?!RBPUR^`wx=$!kS$G8ZWUN!_%bajH{SV4U5;4mY0L68eF zeYB4Gb@~cDR$;QI>RB#MK^KWW?ih` z=7(FChrp8cLL;WLupM;d25k!^$xK`+4oop(uPmrWCvWUyO5TLh?RU%gnvHVJDX{yS z1Q))9!Eo2haD;e7k2;X+ZJZ|7EguKoiAY&rw)&zQma0gRui2!M zF!XTmMnGXgz9%P3;9}kMNpAFbB{4XU(Z)x7yNGL2A|&>mg2?0)`0!JY|47de2F;gX zKEFs1H(6AQebr3ZSN1yrSs;X?On8j-7-O7VSq%m%El~R3S0W=N!Q3+}F`bnIDu1PL zERKbPORVsLhELF8ZijE#y5iJTVo3BcYWSnA`%4soOlm*5!b7lYmgc@16%%{hdWg+ z!PKwvJf>9G*{mZN``9lY-zBc%S7e_S?o|Z4maPZNN!~nWW+Mr%C+^Ah)Njz0{>s}M zR!sgEi9FB3q*hBVD;h4@EF%au(U+DCK@hawi3+X`AVYNpixxl}kK>{X>VD<*y@t9FR+e6>jjLot1m)Km$KoXm!1QQru>F(QRD>_LI9$$ss-wtl$OG8IwU9iR6 zGAR1+LlX1Qfk``SjlDO$f!u(vA z4BB;q*%r6hqx^fFsCBV98}~{Ut|gM*+lw)@=8r5GPZG#DqnY@>Ico zb5{G+Rn(NL1?{>b+F6tcIyZ?`J88a{d{-57p+V6(b@2WeNhjTY5LCo!?BY}2Y=r(B zIIrXj$Bv6|2+1ov9XOrUUarVvt_Y_!F~OAigGgqC0hN(x&c06|Au|n`==?KNdUN1L z-pL}Gv?jPMB@x!MyTI>M6-2eYf&h60vqwB**j5`h__+kqHjV^#{y1#Vy%(F_&}X}< zuk*i+u`rQ6 z_v!&R1uBIp@R?wy#e5e%9x;LfFlXHttDuVymeO_|U(w;i@#yf5K2%ORyoavUtpu}bS(WI+ z1X4_qH)qdBZ$KUF6Z+@LSLmta5t=l;9U0vE3QoI7F2R0T-2AT;7OBXA#(*5;*=z}x z8UG>2-CrT&OAh*SMi<9KY{!~Ym!YS5LIo;7z;qMLoM9hDHqW%ERMw20(UwkaH`HT# z@)aR#V>?m|?nGQMW#nc9{5)>}f0ACLMy&GwR`WF*(<>QxmzO+FmQsaNmBbL>*NXq` zbhtsgFBDT`5J`{QQX~qUC`;`OGGjL=52LHMJfm@+3^>j(h0P5{z=Z}S1sLJ?-xM$x z9maLxUE1f)*KBO?3jC=~3HNnAM=kD3c*?XDIDK|FkK!<8Li2?x!NeL!M7L!dM0G|) zM9zBBKkW+WwW_KRZygR+zjp9P-1})J_~#^LY%r-9ydrBNav#-OBr}{YX zv;^rM>W6~6v+)s`n~<_$2<9-XfYBuwPrq1^XMCw>1iA50%{fb(uR2KUsu)6QXf7B$ zyT-foyfHJ!gJ@N(tXoVJc+a4G>njMpy&vwjb)z9wa`^Z50QA*`tbM!YU@coihz$zi zr$Dse3~NR(JMP4ax)$9RO_*ZJR=&5Ve!QMf->efsrdA_(6+h)YQ;ud@VrmZ&C=<+s z=tkh0FKUJ;qG581FwgfnNDqB1uB?^9TlOx(r&lz<<%@3o(_{-ORXc(??sHv~Cwohz zT4KT;jon6%Sh`QLquUMKDr8CeNFBI0e1M)5;$l625N_UE1m%-RB$9q3Jf86w>19m- z<7G-%>C`DG#0tTC+)b}JKLmepC!sXtqa6LYm28?i!Sd^Pd^^Sgr);N4KY=nVNk{`G*&6Hj zrh@Ik0)EhpgvJ;|Fi{~@xyDUpqIwO|rYm!mIZ%{|_AN1m@yc>IB<%~NCcYuNm!a5@ z2$VyQ5?2`MpS-pHYlVe)OQ8cUc;JA?<7hNiHx*`*9QGw^(x5s`&<(zv?trSbez*lj;8@bC zWtbX?ma3nH8dod4nk+uo_A2nd%|>CS`4G&>sq4jR6V#|G3u89ttZDw;qfSN}fVsT^FQm`vn_<*Wh#4hvP9VZD74pN?a?B1vYyK{+FK$ zMyChxm?c7Q)FOhBKeI@DC)$+yebYogtrl*j+#XWBEZ5%}*#(t@=n z9||VR@t7aK=i>Gg()iOZVz+bCmwh+Ki9P?mompjl8yqh7@R&iu(?k%=%t{?`@L5l) zNn*$<>r6u8x*^DU+)d=OryW9`c0&6G8nn_)`I-%Fc%PT^*p+ocx6ER^WrGZcHx8`x znAL3ie6rOTqseZ<_u%&OFFdA6_-&#H=Hh58@$8vXDXaa4?6iG5Y45%MlmYe-P~8C@Wvg)WcNN?>*qEK^Kbtj7n#87US7M)rK7ixz zD|pOc0TW9wci(x7C)mxV0_GU9Hc4k`-|+`fbod+;vZ@7|iEYk`wOhdX)ms=ls|02j z2ZIA~yw1Gw3#QnGk~nKUE-IN(h_z;&h+6OHf&!+E_};h@t1v0@XCw?-GQr$T*(d&C zHlG?IGGw*P4$?-?4AIcP(!8QeW>zdxm);MnGGb*OTp8n_t^b7mp zXzZvJ@K^07|1?X4HSGbxEby%n|J~DD-_M-l8sN26bD2T;XObqHKJ5;9N3^O!@z3e6JC zpaBCVdv4CA68H{2M}!Wc>ock#x&I&BR+gY$%^DE!wiNjm79pCD7S@%Y;D-OUbfi3(F$86kf{5*dwPMsEm?`1Cs<*C9+x=U#JZ6uhVK{}G!rf$)^B16`o`4+O> zJ(1aJ7RDF4c2J7g=XoT#uQ>x&?puI|M#~I+K<(F6R8L&{aAP|^)7*vE zvyWibs7OmL4~rGGdmFKF1!>gElke$s0}Yr3tKNcsJBg+u4Y931i0RMnN6;YO26HNO zdCWp~8~!}#3u!E~$DS9yk`P-PD67^-vc2Z8>-J+FlPj#y@<411)^~{4WgQo}-Zx_P zgITZ|dxu_7Q%8psy#+1;X>8#q(0otqKqtKiV>cO`G)j-eguDe8Q$O54>oHgyiNF#+ zBhoBm4Bvt*K#N`i(@RYFK~ohl8U(Xk`YOJUFq z2u8l_MD8$$MA6ad#_Ws~A}li0fHPxE7@wX|3}uF z$79vCVgKfNmN6ui&>$)q_Fm_rs5B_0LK-wErNP~(35}E@4Tc7(yU>gVT-UyKbCeQN zX;#QQgfjou-ur%^_w#;!{_3CS{yuB%b?v>@xsLNV77fHUhl;?ka~76P$$=T`NmzQz zM(EG-z$P6FFby*x-Fg_0nIycShZ4-G?cbbVRDYl*lR_7CpAg^KnS+?Yt`av=QgDyc z=IwOD?)UJRR-0~+zGsU2P$@LB9{9_oSlD^O6t`Wu2SY8!VCVRWIBTa5)Snmh&|U&& zG{L;-o$DMww1V`0)92_^-3H^g5oCgJ(9(y=_=*L74r;Tiw3;V{Q<_3{@hTm|YtRy(ZTY>BHB zzd?K=NM7hMlD~`EVA`nz5OkOH9Fi+&k4i2di+FE~-X6s7b{WI{CxV6%w| z>4TQWT=+@X^(J1?bz64;UmZ*zJb;b6Ihk!al?5GZ$HDb^L+~CsAN<&3KI`2voX7kZ z8Wc=0#zXa}fmi+Mj1z;{cJCJ`E?)~BkJV%{=q#`ZZUgzf(wL4=!}e*-ATzQV%t!=p z#gp@}yFic4nKzmB^v{7T>`m^jNr}&U9yXdYg|)NL<1zb%(QG1^!V8nAS=mcyy?+O> z2ec2NkB!Pm#`L2&npD&MdY{AU8Pb@unD9m|d^EC3O+Nh8*$AIQnkA3K!`X}R4`BCf zZz#Sp0>@nS#}olZCNa4a|8aVTH3$*6clIWHbkf3i44=oN#26ugw^d>)tLz5%#;Z5-S z>MQi68>d-1p=3}liT(xxJKOl$7CHx*KTP7 zF4&J=+dlw>dqW_5h!wtRzZi#hUO`s&-F#{2sj#5W5KP1Ke<^XD7u~dO5PK9wA+4?i z=KYyi^gcp@p1ao}PwyVS3y-^yJh!G25~h7bT*T{=EH(J}I2vuy%!74ysxae~6+XCf zF;04N8A+||%w=vg@;TJf+KKcChe7PvcJL?A-Oz)^l`G-)ASpp-jjfvWwaC7hrNUx(sC7YNS}PX zJ@I%;Z7|=Sz^}Aq;dfI(FigrbN;Es0nz+G~{jos{U9w)x%-%N~xKPxL>I&eh>QnO# z@!_Ki{Ae0g8+p%^wQg$Ycg#<;Jp4CoQ#68PH$!|(7h|QD3-OrXY5b&}6Gl@{FriIR z)F$;5D#65*JwjcSgtY$hcKEBf{BfHaW9WaE*+2Ml1;HwlQ!16vj8gW zn!&Y559bzELRD;;FlhpY{OF|Yo5zZl_*GM`4+pYKtB>VP(2qkef~%08Cz!)#P>s`xV;^OD6Xzk1-_Cv9wd^*uP5rAaI@t0juVPf9F* zc}X&@N%8V^2|t>8VWrs<%$LXG@(zP6-PLW(It-sjuiZGz#Xa*3kLe`hykO05;M-+} z-@Z`BU9X7wd7K=!C!4AX8#VBi7iCayV5k z{ZfX#Um;7_{y9#iK2rB#-Q@2e|e13!1>_qaSkHa#zMHuEWQGDV{sRh zMoq>?QdIHV!|9SQ;&&2%Pl;sd;vJI9q6P?^E(rXG2z7zw1e2ydQFQ#UE}g4j%r<0n zOD-Ogp^c_esNhl?a2~{Ie|2Hs;Q)xucje_g+6NVJ*OR}npw1VMU!jj3{TI9JQ&nOb zeyB29)#vG+!cx$DB?$c22$*#Q)8ltWlzdW$4y!R@M<|i=+TGVwF4OHz!r*S5{S+R)6(1QI(B*B=@QxykY{7Vfi zHDX;YhD(fE3YdDGeWD7LdZ6dX;_$9=G}74s!W#;ZR%@$(nm zsCaQ2(i2}p^S=K<6RWPnfNhaHW}aYXa)e-POAN*PQ%k641d|=Ho;e(-Be|7z&c*&J zad$f-hi~ofML(TM%I~Ysh#I5_PQ?DZ%&rM$zgUU4&L<8q$NP~_;-&v7ij^lmh0jzb zkBJvXbBbV=uQm}s`I|_Md}qW4)QXsds9}=ztFMVu$(k%jD2=lN zE^m!9)jrDx;$WTsTN=u)--%_%oyDJRUc;Ahf}H1>u%J^2=ChfBc#YdcYWa5~HYEU% zO40<$?8hU--m|NK3lm;mxebchV{l|wC|Cp?g~AUiIG6bWP4j)Rfp-%OxpfqObg;)c z)+x|@^fF9bR}RfDgp>3Y;pdq_FiLw>#Oar(xeRGEV$FwDp?-<0BxC7trYoWnI4dyD z>ey!aD|kBYGI;B;B#@3Asn(FY=|^+1^!^UeeE15Ki)DeDf*{-DEQ-{B1O2HIe$s{u zqsbSqGP^;57 zIGX5>R|QJr?-k{cfy+R8Up~4y=Qcehm4&&QM|n()Q0rs}#x>SR9GIJ$H*LK!TWJ;x z8jq$k1GYZlG3u-u=8`W8{95=nAMWhAodj;#-1!8{M!93rwR+Ou5re)w(+&{p52@dvP(V7pi1eL1u)p(~h(jAYVDiePktbMoe$E^;Y8HIQYVx-!#We@1~rNN*IuGz`|j z(Ik5y{)IG;IrX*^q?L5|M$DmJlX1!5ez=FMaP9p*sM{%xW8{r+t4boAy(xTe9tsP( znP4`ep`u%3r%~myChUy|#4*W!47>_9;4z#J6c@i66-WH+j<-XkLnn-~8-S6~XV8`Q zz@G;gZn;C@ z7U<-i$irkS!19lgWcuY}5}!A}A*k#H^nUpa)|N(CZOuK2>xE#su1Mn`xHSP;xr+1Yu=CmYb`LrhtNW6j9(o-)Lst4vbIL&z9FVv&iJo=>G3 zKCq$>R+_d$L24%$o7{rsR%YywtC)Q{?~^UvUV5^)_bP{#%1`=DS6N%{Tx0+PC- zK(<4kUFANUt^9EZmKPp^W8^n>vz&BD)|j&HyE^!1Ghet^aUhuMNP!jzq>pofZNj8XRZH1Q$Lp&)l) z4kS8AVb0RXdrdF7D6WT9yJkSqj%rl)`WSuG&XdVr%fQ>ITVTpZO>AH~2frQoTI^VK zm|xKUeLX!1X3gb~E-DsNXqQ4$c6Ct_J^M!<{WNbJ{q4vnbiz~{bl&wtqOul08U?dD zh~1|Q32h0;G{^?|J0^(Bi=IIIm{4dLrj9pN&BQ;5JIuXr9sCiu?7#jSf~mVLP3?U? zjg}LevTwfh&~Em@^g8{~$nY$KRw?~LGXM7T4Q0h0eQ@f24W#vaMdp_dqW;?oa7KIz z`T0MDn6_Z>iB-hLZ8I=XSCM~HCy&Ybum6T%(q3v&Ua8aRt*1>{ljv{sn6_o2eIa|0 z)X73V1uNroAH==Z#_hVKU!4@X?hpHlSWzNs+9eMn+e9=WjL5UT&thT~!7P}mLj|9mMsEu?W!vY@$TRxqlz7s$6NuBPz}h=k_FCDnajn^`zwWazx@fNH*_KVz8qh(;V!&RKW>IO z>5JjxAz3^_arXa%=@y>NPJ%gGqehiH^`LjPn6O(%Y0(8yhee)=d1%U%1yK5N4sca< zE*Cezl^ha@0qu#Gp`@Goor;O{&08kyh8KV6QyX`Pld^kILFHu#yq^MGfZ*HT1Mu%wa^~Dz0lAfT zU}e~CxO@IKIM5!jB%ueIT5Vx7X>I6KoQd=Q4Tr(rsr+YcmayxLB^b+_Dpa)}rdRlz zu)SaZpt*92jQdD4;I!(_^It;k8&XdriI^7#%JP__Cf|Uos@tU{BFWtQqD{Kbq4kwM z^oL7fUo~$$f3q#j{;vp`Ent!e=EO#tO4Gla3dE%cE$P7@2mD|;EiM$_PCgTA)GXnV0C$1jKcDTJ)lr+iA8>qa6a`Nteb&w{7eI!Uv9!boBx);4T9;2`|7;zUy5GpLG%LS zeI>c)MD+YC-}v%F^tx8w3am3i7!7w|zmP|Y`Q}o1U7HbJAN~W%`t0$qtnH92^#hbo z03P*q7p&4w<43bi7|nfxLFfJRRIkx=g496PWke}c=cs^!y>xjmRn9YoGiVy-X~>Tz zwEYvr5lwWN0r65ZcfvE)C}85gh$pOD07^rM=HoDpzfS!O1r@?A?gim3@Q`3!R^7;3 z|Hzfzb=H{GdeBH)%@xtZ)rNo@`JC}u4&pf0zQhP8ekUp-f)P8);CUW>5VXz_ca80V zi<MfKxxHkhA}32NS$`o&t^> z{uw@Bm&4L?q_CF71e|;83oN~4gW6WfG4;_ZFwJs4nC*B9n_fNRF?R)(>NkSX8rwC$s>MilXwRLyRv9nu6#9ZY#EuxMYhdr?!sW67P)*x}CD_`oL^ zZyY1JbcmJQeC9228(P8C-Oqu8)9&(^HbJ6TOEBA>G~{irm__gLGh&U_`iWKhMv|m& zhQ|b!^uqB0HLy8FXe;GL(@7j)I3K7)EeE_}+6Op(T%MKNJe0kf*e_{#`CPJgp9rK^ z3dNK%K|b0>Fj`yGMQv#_=%?03Z1wl|;;5}r;+40P_$tSKBPpCquDNF?>)^MWiD7ed z30T)DVxIzOta;u6d%L}Xx4BmAorKBkiy5};uv1#>8zM0Gzae0%1WX^n4Bf0KIyHVO zt<`MECR7bT8s!6-z}L@FSR09;Bnsj%Cl-8fk!Y%R61-*3z;!z%>^@!^e{^@mRBkB@ z+dq=+elmsC|Kr4p1{t$gs^7qmzs3Bd`3o3g{UudaDJxPxH;Hz?VaPh#o~8@lH;ViE zi&0l0xk~*bg>~q2(0b|v%zXElNI}j37m&`yg}k^+;egLyAa<<|8-K)x4JXQd{Q@aA zY|>k>TJ@R7AmQ2Q5X^c9MUnewSNiflhOE6bEpDCjRJ4V-^BT)`09WX0(^?Pqwy97d zJ_#o}SMeCGo;Jzd1Dic)1e35w663^Qk|ncCBol%XCExKYuu~MoNi&4em=KJzxsGVs zRkE|0WXK+@4QAedt<7~fwE=|=_zklSr16ya;e0&Rx3`|KVaOn`GgZQztCi2@S-6)b zJsv~U#lOronM(n>%wWUe^j2RMzSx!XqmdWBo|Xg?pW`aho{#8w3qy9z$Lq{g-5l|n z2RtzBOlp zF_O*}#Vgp;rhNu1TT{k}M`Ve|M0imJm+K%(TZZ?uS@>2J4yB6Glr_!Bw_ge0P5c9Y zn8jGEZHO%%w4iOlndt1WyU5F{0fo~MFt0>tU91xN)+Q0mzH=`{v6YteDuVevVk&d$ z@(JcvPZq^_bm?7^;d`T`LiJ&c#w)%ziZgEZ``Si)Ru|*qu7P-UdKgFr zpe0yoccE_vgMq`?%x-~mW9MSgGp+yaWP)oi^8dauHWBhi2YeYetWB+*GvwVz6yYz=$+sgzW~}!?dCDH?e#Fv)(bBt`4M^1 zr}4C-)9|6fX0Tl{7AHj}!}A}e{MXZ8SZRR-QyH5jnqJjFZPGMk&oVcW(N`r&@Ucf? zo4iVRGgBVhyvl&o#yrp&dLI0y-UIbSWnKeiH`xt8FqXkt@$aGKwK{oYgu(5sG2llm zc96f8@R1gpFV+&wj>0ri=eQ5lR(nI%`^FEZEA}jN_-+crVYp_$g72TAU^ zx*KZ9UdpOtUVm<&!^$5s&JC5oS?hBj>EirOm^qjzhfjBd_^41%`x@zuhlK0mn}-51 zA_+epBeo%F&qe6dj)M^OOpPCnl+Yd*PA~_YPK!?YKc<3G4cVq4%i&vGr*r+CP$tZ< z5~h+bV^>)%M0Wj!%pVnyF_ly`j;mmqg+F0anGFs!A$G{!GI+$)3e6k4saqF;STIvq&Q~<*6oLJNwXXdOHjoV z4*Y_b?xy(5QyaXqE*UDS`uJxvUBH|pn40bnd0SRW(co&tT7>$ElbTi0mh4Kt%E1*O zxy|i(vZ6Q)7xcW@TpiEMt%P|g_V{LFEj-j8fEDh3fm`lo*nRFOtcK2!@GYSNr7pZ| z(g>!SPRlb5*PvgYFk*d9dod9;H7I(}FD7%yPu{+rI}z+zEQ@7gYI#iIEe%}ot(v$e z)7XauYFN+E#szDe;gBLp%6M&tCy$*9F+PI5VUY0Z%p{n>uk-WnXzSBHg+}bPmNCJpm3)vt1UK0tI!>yop_Y=5W@f_Bc$dLRs z2TbccK^;>P`O{j7Fli!!8LGG`Z{D~e^ot%NcCCyiiYQ%*PKF<6GQ6vyFq?$cdr9H# zriz#|o#SdYoJUtMu{m1x=^Qivnv2BhLjuI^e*$ZZJK+eLL`0a8k_*50NTkT$XJMs1 zC79OcSm#a3#0}2Qm^GPt3th`!j=YMK8Lkc;cR>lq{E)`)o+{zgGp)eY(<;?SvL7il zu5}hk%3pR!LJa~TF{lu>p7{#F!)9acLN#{AB*8XktnlhAA{Z;zJ1#o(Xj*-NG24Bj z4q5dS(x#y?j7|_aWbBv4g_^S18mVA6zcwDjxxsmmcE;H%I;`gQ(X6i8C^)9@3GRG< z2~E?N;L=?a*t^j}%|=;>cr7QGW8YON_n~(5{V-#8w{IHK4=xf(-Z(PREw3Q8q7lCT zBa2%sRPmO_?L3BaOGwpWKx^R;HnfRmE3~8_+oT5?-9%8nYc*c=ie}H=wPLwRTPR?D z5{%P7*3|0Ek@WZz#%#OKWm@%zGjk)nL0nsV6LLx9#9J#_%;n$kEm#9cS%}=Pp#=$W z@VPeokH!er%tIB-t@QAhh$QfQvk`ZD4Q4N#QRXqj1WY5rJo#)&g`KvfA6+nJ2Wgau z&G)ZmuDUskW!@hInV@s9pKSd&Om1@rIP4>;d(sVM>&$w<(=Y>d=4Yk7lHmS1^tX571LGT;S*0 zCBUt;n6;|-sRfB}aqEB+p?>f@OBK!qFQcC4crq_Db)amwJ#JB23>Up3@w(7L@!rly zF5INa3n{-c6N%u`T$wU(8bH51YRr1q#M9rW&0>PTjzh7Ef6?Pp`oIM`sggT1o2ozH zIi(#&ZqNiynbM~An;u&bEp8ru5l!xP#zhvkpkr_dCs>In^_zm6$I6W#jT*r`ylX`H z<*U$9%gD2NJ|2C!wwJkNdjK%&2 zp=PuHBWjK8<}JdxOfQR;-|$@e17EYLOX@*4W3QmiMGDNJrJi_x(?{g<;uP*TyoZu? z$p4=FjTbQH1oK+Uk7^65rs7^2u`$Osp(krkF`NArV9A(zq%`ao@*@|MGhV9UEfc%= zwo*=K(|qh6GB)Z#;W}54%H#>mAXz_L8gLk8Ts%v3omt3sOEZtr5uS|=!K_nRNp+Ux zQ}XMLSf>9zJ?H&P=0Tbn97!Tp$0Rz;udEHKiTOX*9vAtj1->m)fHCX-uhp?z)*(7` zSpac@JBA7mB>!)x!;R*U@J<^?FblWMq25bwP@2+4?9W^$@utmJm_{cAhgMUN9Sjhh z*UV$8(z}S@q8X-p_yXHJ9~|B#ku#1jJ~jA0s?H0ppG@5hdA{#!;P_@fRm4YC%Ims`<0M0alS4cu?SNkk%%pd z#d~dSVSnTh{_9yUV7v)teVixtV#7$PA;5rjKjTezi4U8y_3Iz|@j?EecEgR1|B=?iXxFp}cuNqmW48%~9Q z9y@p{GYIZ=F2E_P>>&KbG5i5L;(K7kWB%(bUP&-FtP@=Zm}*izgY;QF^#loRx?gsa1v?P1iM6MF2cTkXu$5i`+87HN;+yo1`h9#07H7@!kRH?JBZm>gv*y!J#t46yTo z6^=`>(gF);UbPPoe{707C;j0u{~6HkBbWfUl)R9+o2i2v2C((_)6k3sqfotxFVqmB zWFkVOUoXe-iQi->8 z*&5%k=$ZXz+HCMs6hYErGwu5MCBPMkGsSi5J5eNxgsuoycnjPm7+ikVCAIP;HNZ`m9aTJm ziSwF_PB96nfm{!9m<(cQT8N~eocaiEObN`Z>&LBod%z^A7(7X{-v@VVR&s9=+jV&) zyU=$qyUg<@G@1%O&r`yru>|vNMVu3!Uqz{^>arVJj3vuYx}gN47bx;4DMCK$2j`_X zplbOCc;%W4UvA%lsUxJY+4Np0SXd3)duQX#(u3Ib=WJQ2)`9GmW4dhhk8nscGvz1k zvw$fe809sO^Bg92Q$ybCu&a7|B|nBgMZadOMA6mV5G+spw?-U+nR_oo^to6lca8zB z3y;GZ8i8IlmQ@%b_JbVB%Icyg@ea0 zf|+QYEOIQ7rSpAs*vJ2>O01q}Fq?NAM;RI2&c?0K>eL5@tTMDQ z#;|1EThx}V0B#5Sp`iBe^(>e^wv?Pm_Mm|TnGm;6Kx%@UMqql;dU;94p2cS0yX zC`=-IflKkCPrHjKyC!Y6a=#Dyc`2DG%G!@w8=CosvP0huV2S2PNV)%qXq^n9&#wdn`qYu0;tjJ$9grA088PK1gUT)$7LKG9~6tf@g8($_L; z-43B>Qsyr2?1x!hbD;EbD6~0EgK>A)@Gl##+3#*|FpPP80RNWWho`@a#$gZqajlax z_R97|-hcMD z3ym@7V4dbQc)Fw)I_5RQyZwVfr)md2Xp{q2ZytjMtv6toIfm}@ny~#}VFMK^V1^RR z?Tf2K_3p>08DZM&#C}bQTE8>%>Ys;{^FrbRyOrFhk>iw`MKxsBz5vb>lCx=Z*xLfL z3=cwhUli_o90uW!U?_t#q7OU6sl$7;*^>=v zOwx^wD5q3k%wZz_5{$-IUYRm;Cb4WKEm*BqeZWmx*p6)IIC>f%3Ym(Z9~y)8oB^)J z42Gqw0dv*LkH;(#FpdOMGbTYaCHDYjyC-bYAt3=zYIjcJ6kYrYV7CLB-p*TuJG$SK+$A&XNR`Deqq#K$i>1J~6L z<3sa|vBy{kJUdzmH$VFecNQlh@ke0^+!wSQ(+OtOR}Ino(Mi-?XKl89o)7x<{UutE zm@f__cQc%JP=}ZeFC{=m;LVW*`pPJQOD!9*WE6sNex1 zZ)wd*v-#2dr&66qFx7Q|qSxhV)N5aDHt3Wg`qIsao7ea;T$6126&W5AmqB#u9|a8e z7T`?h*hOPt=8R2vo)r-YE9l?{B0Jo7U5}(-b)l|Vfjs7_pt)T_Fn7f^q7Ft(nUf`O zIWC>k5(k^je>s4u$W7vHqR`P}BBMu?d&jk%R3|Cw~}?AU{kYG~uqFhe}? zIq5vQLsI{$bx>l$G9KeCV1fx|{RM4NQRhQy-AQeB^ZY`z^vEwdw#AbP9@+$Yd*w(o zMFX^)Q@|Q=ZN%K92|nDB!JH&s`|t{wP?JuIS}$NqfCje8RKtCh23RrZHaxj_oMHhl*qvdv&xcea3awH!{p(*j&NHs_g=ltBJHM#zwK z_bq3-m=5ucF~?!}K_$GtM*&||9*K3Elf?(03nGhPK|#EmV6K@O<*g3?PIdj(W|`UU zbaL?z+A{Y(<2JpOmna4*wZmXF75;pq5%U{UcBlLJlXRAX3@%vu15~<<+1HwS?72z9V9|9;95guv)(&*RtIq4N305OnDe@;R z{BDjD40TA#W$&3%s&uOk`#0bYVjpc2x2r#63jE$fg$6m#4DI4mes4dO!l7Q|i@JgY zIK6)c&SyrkDF$|IR%IfZlWt9}TF=3;C$n+>HXC-WlRb~wFO234!OXLaaQVk9pIUlF zhizJafqDJ&028*!pUE6`4`ftJAdGDNe)Oo}Hw%f+Z3IavBPOSJN2Y?MtSNh|bOh^X zp$FD&1Hg-{u}Px6p~Bzz0hG@Uz}%ZH@Y%A+`}1_ z=ZC?~>lzfebbxQ48h?eyX$NiYrjsK6Y6$B2B#~kjSP5kTSwY0o;D8l?Xff`sYLKkD z`cOjVOzNb7xkWH+gTB)en@f~byAJ!U+>hGow~z5^+rey*ryzK6I9QN9!D0h-T*DHL z)1cqbw(kqX~u!Hed1Pqd3e|0h3EGszYu& z_iCP{uIuZvck`#BGOw}XZ^5PF`xX_b^ukyuCULG8lGU+1lEKXAR#-b^JQRhTLw`=$ zpwE&)j0|<2o@f||7duH%rR_ePk@#HfT|J!t-E;}h<}ty1_95;!A5T+ZhPv#@zi-em zYldFl{Fh#3aS@eHQ-{g*ra2Vp9zY?x20+BpO$h7Oh@ZWjhs#w0 zkjnQMT=!xhdUsO`xY2kCm{$ZdU`@13zBq>3+o!|M@E4&S1wPEG&yi@s#&c*&Qa|Ea ze%+62U>8SO%th{f5}QFv`e9V{+7QkdEJMfUTox~#=!;8MXVY_wK=XFw8AaW~aj`WUf$w9S#Vy{{QS`N&?eRR6qb0iG7)H ztHl59bht^|Cp0b96HMEc7?+*f$5Tx!bl8@rrOcouS>j>qno&Z$2@H*O;d7%nMVISr zS-f(61DIT04sxv%c{$I$jegjss0H=>or9(KB#Y(_PR6XVGqwp!!5l`)gfH855KPU< z7#HVmJ8G+m4!hO86g};j%$z<=6x)OLLNJOY1^Zu+d_@ymH^^ZA?CG5jp;~7lYmXNW z$zKcykC{T`Ab0GKX47>&$$0vJSoliBfILOONV$_^RAjNs{mF>xV8}l0O9a{{)(}tL zI1b#>#NbyX0vQsw!-WakDUfGF&Yr=(CBWqr7F1`#-S(;UlPo28**Xn3?mN zU5w^Tp!~D6*mCtzw8Fz1;;Wy%!L^2XrWv&m_2d7=aB+xS3zh~cKd3($g?{ZgjfTq` zfqTPLtmR>YY*r-TxsM0ooCZgJ(jtXPGb0#Nk9_Cz)xH!sX|a=Imr1TKuSa`R$3q

$>M0%Qp_c{;gY2P`YSfAqQ|P*y@+Ad8#3W!6nRX2QMUSN2~m}@ zi+4b#LM1&3A0Yf#Gw5uug^h1Z=~3Pzu$?}E>yu;3nUB%sQto+iZW}}Kl(x9P(GoG+ zD5g{X9EpaktKzUJ$3|dpseC~b(XojknN&8qW4#9Y-p&B;+QV=sWIOc#kOWol8i22- zy`_GHkB@$UF?0KHMs9ViPg*)V=dLoh;ow?q*ZU^in=c|}FU1_4K1p(Ju#RHw4VImq zTEo~cenGy5+!F3h{1htSn-v8gt!Bfo3RhTrcMb&Zs26HB#mi}PO#2Ure)67mR^GvG zIJQu7?Wh-XC~h_Cj1!GC|3@+sLoquSnMpDu8sxz)EPKr86BF7wgWNy;jPS}7-Z@Fj zb_9H{?+KMPO=NFBO{fX@43^FfkZnS3!cQn;ZSFi~=YN$_$G}(8l`g;Jdgqtp$QciW z(frSj;55a&c@pbo!xYHL4Tg1c{K1s;c}4bwrU{`z>T{Lw$}bbxl4>Ft&2Tr;NWkG* zsIzZ|3a#!qEzuAakD^FZiZ0|BHW7o5cgUE|i}C4e@l1M}xK6u7G5fb9dOonaCI3By zZgG7tF^e9Qlk8CuVm1-2K)txF1gHDcGn-usvTE%GqM}>_ji%q>+_m1wxf@}S*HL1* zK@&RFH1^F5Xr^0-M*7vI$}Z zipR)TIf2&HBJ#`WI*HNyDD-BJe)=6^rusTdQ(?W)(rjRTDLeT7$D2A;O zF*1rN%FOhvG@mP9eM!NNv$zg^Er&_M`Ec_0spy>4{8I~x-V;b((oRO#WRtAUv$^qh^}Y|EbsTOAyV_ooEumHFEPmE3slKt-MUnC6A(- zVn4p8-4i_KruY_kMlmBGSW;i4F31y8~=J$TO@wf{K zuJI7wI~r~dq;7C@?bdNB4`RPPfKG#!z?3QeP~1x&kGs&rOWUJ3;#nu;F%IH$Q$#Ta z=Wa=&zgA_OkjdGgkRQyFWL>gk+BGR}(8TxR%BYyXa3$?6q)JGG;}2osu@Z1i{tGM4 z)Wff<eNd}fgVkhca%43|xk8~Bq1fD!9d2#+-#<=@(c5B2> zIkDJDI+u-+Po1iULk+*eyd5uKfhv81Dx0WhS20AsD2Dur%D5;0H@w*R2R5spAwvdQ zkqNiQ;m+eeIQsk^JZ3H?UnGdTwJ#JSf3Z!{T;C<*LXw=lSAS35UuU<}*(FI~)?FQw zOzDP$HZ7e}SAxz{z6i$6S(l5zhkp@0c?ba`Uqi<6F8JY-6^6PG#wph0vA*FL`c<|H zqd6pEeo)M%Ef*#ChIP$&yH3tFPAnomTi!`G(KZ<#QL+ilD978v|7dzStU#C2y()%zW|dsdQ9X>6_OvNyzgJ8SABT zw!7>EV>Kg$*-|i9I)onG&HMEkbZkms>mp?VWB2-lP#4&BO$D>(m4W$A67q<(e zsTY+grWAAEN=ag!nVm5>RL%>@0+^gw29o)0L@Zs43oz?}cNxIpZH+6MX)56NWo25HQC@j19%e&bE799Q8RP?1G%t zAX~`us%1<}O1pwj^9fhb8rq8Y0)}6w)o3(<4mD=t8!_h>#=}_oQF!{L2D%sZ#Kv3) zY@jJKZr`54o|_`(e{?pE{Ae_6B+j)K^1xg>hb>->0Tckm&GH=~b9riI6gb;5JQmmgeBe$nQ#QqX@zPu06T zW3Rus%ho!l!JSMqocOIL{tZ`0^P?Nt?k-;h%wln-Nhs#vy;YKEt0nTQ%N6YSEh`l( zLOqzQW0B0e8MFu)_epSoQTI?r%hhyI>)Z}M&cB1lH#KoN=g0+aHsQ+iIk;|Zg%VcPqw9Q_Y;WF4?={1f4wHgL&EF4oM6>oF)3CUmEbnZM1@@ly*-|76A)8;<7qi}qE- zOyn`I10_#>T$A5-WZ3v(Jw@T+M#jbD662&*2X-It3ju#OY zuLc6=w!9m+&a@16uj+%x$8^FiRDk)^tP|I#+)Kbzh?oG185by#oVoa1&QYu5WaB7C zYvW7ClHQ-TF>+`*76W_;x2tytD34S^-km4FJ_eHRUZR~wUAWf|zp^^le?iZ+9$5cT z7gty0Lrm`icDQmU0b?q@I)f-C@tUb*a&?RRu1^yjUL(bjbRC@k;u)Ne9K>c`i(u$A zQ+g|6f+?o2pPFRcTrGv>OqLB(uaI1@&SZj?Br@FnzL2v-N4Pgm0e>JdRtZ-eSH3t^^ zQ3Wulb}(wZFvbntAHd5eO7QE*1)<8(AY#HPCb!aD^5T_^!m^!ZSBy7N^qktCF?u+P z;hUDU0vWmKXTK)i7r(={q@VC+oig$k z;S;B60iW_~pK*zVPWeZgdgj5NK0`2Fl`jroh5D>ka%=HT0W(a*9HW?3bLC#2-TNvI zEaBLCr$@|DH+`o6s2)t%*g}#!}razc+$?Qhq1xFSnyF5FOS_t_oe6XoGVwR)f;|0c)Y?%l$M`4`Dblj;;}r3)Y=EQ)^nTZJMdKLrx!=%6g~G6dCb z0{r0)k2)q~8rV8s`Tc&RyW;jc1UvZxWui zQo_N#$HVt*FVHfZC1AFQ7=~gJ6Lw?->>Z@YOW@d9jc1ABUmNLcxdq|l-Zwq`DHxtN zHh%>^;&pJn9`Z@DPJ3TKnEO7G*mV`tv-2V7s_uh>muq7C;Z;zyEtY&fTOdqMOSN6)Y$(CEKV)OVtswQ zZ{-N<9iG6ggJPj;llXX+Qp{~FiTt#$sp8cxjxB6{qIhaToBdL{De_GILRklmq@ttY z(-rvAP!}Hq%p5>v3i=iBv{Vy6(PD~a!AmH7JP8#udSLqfInZOSF6Jf3g?r;BPUsqn zdC_ZzynV@E`P7vhD@}O8*fkcBt>eZM9uxmc3nzV6!lg^TfX(e+z?W3{PA^`WatZV? zHoO!5FinIp6a8?54b5OfDV&Wpz-K!<1WbT9nr4dm5YtocaPNzJ3>8^ad1g!Z_MSz0 z-0DnRNBx71QZ4+NsERSGzCeG!U*NFb5c$B`{%@+lsW;7I>)Z(?I=ex4?KCu_Ut2r- zUQ|x6ht|0@0;XKVv{B5B^*=MB2N%je*Rkx88RlT}U$!)AMv$;uo5gA3J9@@htlt2| zyMMymNF&_mri#4JZ9#h_xEaxv&W4klc^0kr)=?eomdy>DZZiYD8?^PHDmKn zR_;I(F->=WksP!Ap7Gc5h+xf<8Lo|Y&*~z7u)?p?l>alw^Kq&eytM_4sDTzF+=uyQ z17IrstQqd4U9P?7kg2wo*emCeFdBRDD55XL{Ji){He@p+w^+ciQ*ak!|DcC-=Fc#a zcuf;`Ez-dQpY(8Pm+!y_q^~fh3ne-e8DcBb?gA^$<2G5_b8(0Ia4WPXaIQT}aX__r(Ol~U&21pX z93NdPYnqWM_k1sBJ1>tX-JYAsu2vi&e1@bleQ{*bN}!Ogpq&AQ)HR8p0{Xj@Q2)R= zD5bH7KPtv@k2+C9?Vi@$qyP!$d)NW>){3vr&7vv8Vv14Lckq0{vht&wX%L#JKM7M^ z;pP0|D&d1S=O*jY+pmC2u@|6a4qep#PKN4Q72%?(-oFfXdU0T(-;cYzK%IMEMGuZ| zX>(CC`{P7YF>lRIw3rB?nBR8Yyb>SD@e zO;C{6>$i91dGZYQk3TCPIM7ovzVQ%Axuc7`N;S=J1gLEt2*anT!k|+ILJm7GfJvGD z5PbGtfh}nhnfzX1(p#oc(h;R9ipAFl;+w!H!W76A?LT%?Ou?USUTsXOTys_iJH_OK z;?w*m(ze}^gjc4lv)963SM(w1E^Q7BKWmq8jLQLfM$qPBE_)Rk9i%wzfo?G zCu66VRg-h=LrMIp9O=6V9pu}w4FlUq`;-1Kr}`Z^cT7(B^f(?9wC*Vk?EUb67qkEG zfbz)237C0BJXmoPF*hlu+c*Qst7ks)6$vs{?Rp-3sEHu5E{)O$-E`1szY01&H-%}( zCJMglhP$<4Uh_BbHvI=?;puQsdKaczpTh;;{{Jwv`Z=@F`_nJsq9uq%Giem_d*K3! z^Ko7I$_N>Iw)Y#7y6QdY^|w+wgr3{*X{BlxLx5Dp3khZ47i|_KiZ}L`fdN2rry+*cK=5r2YcGMa}JKai(Qaj8f4VN#K%485h>d*n@qI$m1cgqEo6)gXijh&=K_-X0IrLx{(t=bElkK7`T&$I~f9+ zOhKzf8Nz5PM0cL26l1#3Pm-j)E5q@Gj4k*iWdc2V5byJY86Lyuuor0LLHQQCD==*a zh8Bl|FEoLNk1`tRet~N$f1%sOL2#qjWm2oVQmUkOLOSi@80>HmttbBzXIde}td3EZ zcpS*~Y%Gwmo=eTxg>$-r6R}gouhvFiyWg<%;72$~<6QWf&AsQl7QuBP zvK3dggs4iV59M&OR2BKPz`gNxU^%r8G?&xmdT1pCZBoNQJGJpntumgzp@Tg~nP9-Z z`B=8%yKvDSi;rg=#l()ZkRQd~MrwMNTl)NkO(81%8YC5-02IGTSHll66uSNA(%isbsJW#xe5S9QY}AAig{D}D$fMT{}U+!}Jnt1ddp zYeriJJN)cXa?$Ugq9$b!bJ&J%04XMq8Z+{knza9qtuv3ysq6lK^E^+Q2lEs%*LBWW zn}p1n=XoZ|JP*-Glv#vSQbMKBb@CKekqx*R_SAro~-Qr~LuU1dOG*(RiFx-)sOavV9aN#1F8 z^6$nOG51v3jP{iiicvm-`j$=x=X}drOwL*@)ef#2@J{OVqL_}2zJrnTCuz82Wn&!@ zX}1T4#{Y&mHMTZ#=<}4>lljJ$WSTG>UvnAKx3QNGo92kQ@$i-6X7g2wAv*>2^Pii= zpd=^NH|t%$_arg*Dj{7Xd>)V3*PA5&(Zhsq9=~I1`{}2ljXNjtb zId%BZ(2Xto-$SX| zkX)X<46-qlXJv+?Uys<4DGiUoI1A?zy=zaj%LhrAwz4(75VJN%i?m2?XlAh19QQ5QBB=6#?hrWse9b4Rs=u=VeQnN*Oa6 zF}H1=@ZIeE_!kVSjMQvrdo16qT2kX7lrFa?LlYX{2bR2@_^mI^ET$2txsSer_abw0 z%=S0;q#6rlpPdCeXEU-?=M?m^SpkN29z^MSS;B0Pe>YPR)44*$yXl?gwG^V-%rld1 zls8DFSJ{@WjBq4HICyp?<~ARHGa##d^$4x#>bL|8|D7z!Q?5xabxsEL>}HVenXaC<`nQD1_$FDi0WtHB zZQ}$>3+g79|DHE{l_qlGD z3m58KE+{U}fUJ4Hz~R;@NZ>lbnWttKE-vbJfm+k{hlGhjOpmU^`J#^9g+A8>^?;qW zj1XudSg!O1Ny%r6`$VOIT=FuM@rlQx#W)~c^C@C=@5*A9s`ktV8=md)9$4&OlQ z^d+doqU0Jw8ME3PPliudVVQL`gdFj^F!5f?3$xe7p}@HjIW+M!4Cgz+&L=Jx4Eo4* zorVn(<`81a-S+SUgT@I5PYddGQwzjl*KdiBde$pKEU!uxT{Qea8<;1=8xR5Nw)c9TGzdW2Tgv1Ey;r_QpgE&2Lclr!= z1JePLhMEE0Y01y^r2*+w*zCBi9c(^p3XAj>ixaEr7{MS9j`X%AKGl^lY0@BAysU)v zDp5&M_4o1!BmpsoJ8$su@8$`uRto9}4W5}SoMgM!-(%e;6mt>N^0<@1Iz(SvpTw@# zlXe=dgrxHAsTLbq+q;jrlSk7aT4hOwJ$(zB>A~^ znIP!+3+f&tx{9q|6|kQlJ8=e^_HYs7k4u=7ZhB?|LZ_0HAm)1aGJbj`5xSe>PFvxl3jaEd z3rbC5kMxM)X!k0$#;}zxF&wNzTJ19<5ko(7L@$<$uT*ml0na$s=PG#IsVUKG{{b~R zhC`ccAGw9oG9*l#frPn-m?$?VVe~h9;VAk7bvt{jA})JzC7w0Rg)fQR@fPJ=Job7N zeMQ+RJ#Avy*^D%eF~n3uGG|}Ub0OZZxF1{zXbo*eK9+rhF^(ht`w*c&&wcVtuV;uk z?cgI!Pt+7<-R0HCw=Yz?=5OWN`SPs$piA84^SbbOu{L=gr$xM4Xp$Q2uIu}-E!d~O z`ET$(gh2;uLl>eiYLjupM?iW-4#_y5KqzK_{B7PLruVTBA-h);?^(#J7ni(OwR>=d zo8I?`KzEwW^y!d;iDAomn&eQyZ=iAL*0m9EuyP!DCPb2~s@3Gi@=w6Uw0U*P20>xSkTmP2K_~h|xA|DlBNXRqN7 zHfnVJ@x?}r1B0{e%~cs=hnSXE429!9X3X2syn4v}L#nLP;oKeP&cfIW?<8R} zY7K3bkLq5J3yAVk*p)vP9p1@V9BF&bg#6lwhtYdqGGS?BA}rhm{qRu|)%mw%O-mW$ zj+hP`yoC%O3&w2$uYU5go|#gAke%;kqoUUI=&vhX(qZ$y!PKl;p!pkzi@KzB)8{b# zX$O*g1P`L8x}@)J7eo9=*hdm^LVop-FDnegl_dKBQYg zTjKiY1hmjLAaAtg$$p>YEzlV;_x8zZ2P7*PdMbkPYpvbxH3&x)P?pd=d0TOuz2e_@>dFnACQ>I`M}} zbzn>%RXTT^9s5?s#QwrIxz(S54nLs|6m9u+%yeCTtJ-!`imGsuZok1C&_YN9ckvv_!h9h*@P`AxM+0zR22 zW~?U8Sizk}F^kA+h%xgdhE+!7fZo=Nj1Dt6tgyd*s`5JYsx* zedI0G&6w2hO0~uWGp=}yvuYWu!Cl9E=fFeSQpSS@i0QYXmG=~rhZRG27depj?yq2z z*##IYv?uvr+{mxY6%bslO(swLB4G~7n3;&#-tsc=?2Hijwrn zwfEm8%xoDGgqYF!OZa<%jhNQwm1^S+_Ux6%=B&`Tp6NIW50~k>Bo+NM+T$^3P_3l> zpgTgJ{Eqkl!-x)X(YOLVhaQ8qzn#c#H#aiIW-dG_Yk=(PS_!jB#;iij-W^5CgqEg^ zb&67bB`2P<=c5Gw+bdYw?-`w{CuKZnhW+*G_ds0^PaOlY!}=qf3VsL2wNF6p#Sl<8 zw;&-eok{-Taj?!A<2hU2NSFwD3v5Qrw8`6j{5ESay`q(Br+Mkzv$fW$J>Pb+vaD_gqf*`dtPdA;Vy;+nET5r`n3>%Si8ng7FkFK;Uit)wynJvF7_Z7Ks`C^w>FgUhU5^B6TQk?r~O=+#3EBho9Jx5hsku75*nYO3jA0-!=lv zw1>f&Kj7zXtTu*5kb=qMERZ9&qvgZqC}Pa4w<-D<9an?~Db*&4H(4iZ6V>s?bj1{omehhz)mJ#wG?`m`|0&$AIwxV~$rr&{#O#|fS5dyA zqoU<%rFv3Ml32x8iak#Y!b!o9=!Th*;MW#pHK$8xWlHHl2eSLDDVf(!i##dZ0oO%8 z_%i=9mstK1+QhyAzqYG5RYWC>8=Wd)zQ~vhh#7N#l;YFF+dd&%Q1JXmH1m1$8?oKP z1LFQ6#>79%oLuZ{Md*;anhTnwS-vC5L|^SBUUhY~pT~nvqc#{#MV!e#Eqzukonw#=q|M; zn+EHXR<&9r(8!rYPBSNK(M7DDz8DUVb%jfc!(3WKIkb3QjU&Z+aclSz=)X?J*vbQI z%Mi1taj0Upi?y=wl2UyndMulBu28JcEfi@Z=7k>+G$k`>uK%2s-Kc>UHP!CJ1QV7mpOGrb;}_k!jw-?-0C-MMF@ z)X*PQuM&DR;lc}x;HBkpY0*YoNQ?FgF+Sak6r(3t@#$8)dUeo4c72oW;L zCi*(clElBzBN6RAaePZTx4PmvTWXsNTP$uvxxODaDc}Y?F_f*DAx~ibg_yJR>J`Nf zt9X+jUj6Zf727!Rq&TA5NY&%9C7I)9LtYl!5h`rvU#&;xTyrCunEs|svMYAAgV?k8 zxvKV;ShGz6-0&@h(5%*6YwPQ-*0S&1{E3=?I{{LKL0COzfM#yN0H`l>)Iy9M9tT5)5N zFXO0}bm`l?mZxJ|AVy2|N)dh{k+-k0#C(Vi`R?$4V}k7l zf$6YUod0ZR&e>ND_uR^1)2xBq*e(|#CibL+v2>KajU!@=?mki++HsP<`Hok&yyPU* z*|iYvral!ZhFY`5<^RTvwHyg38F@1E0BTQSs%T z1=)y~#649oxLq)X^FJnYgW6vPe$6v@yfcqu4(5T@t4q?iNpB)ydLm}&{IDK^I(*7-@xV_Fmdh_-G_@_s zj22d;m9`zZdj%sL_+Y0^OF3;UNd8$}lAgW|te3gLm6DxY(wN(jx&1M?Jif){*Iocy zoqP!s&`iRNM9j2AmEwfgHhx$a{5H3DiM_wHWlhW4vNfUjSMS0Zt6{c8^fw@E2VD|A z)0MBu=_c<9xmp_V&O&RcDec?uepSojF?NO4=Q%A z+Q>sQL4De=M$DPrp1otci0$&$oV2pBB%eKO$;BKw)=7`f=rwqox+7AZ1paj#%(p7# zHr76ZMM2MDz@n>M^Wa=?OO?NkQA-Ik7cp7R zUYm>vbs^;iW@LA{4jFSJ2l~YYz~1PuoSEM%F#h!lRxPaL{GVn436R_4+O?4|>kzZf zUPtlAMT7r{ae;^*=fu{FlGwEV)oj%gGty<2xpb}NZ_*<@08!b*NkizbVzR1 z1=#j!B&^IZ1iiW%nCkr+hFTYJdkZpQ$wPV3(%MRx2*kX8l;N|o(|+aV6kZMdYBBfp zY4*uhOs{@5B_7)5WWod+LPJB%%Cw~0)4Q)3j&s!^-d!)l{jsCr_G4X?czp+#Pria3 z>LSkkS2`R{l{d6bI|;J`F>@mnKI;k#a))o^)nD&Kh^CpT?7W+ASce!ar9#i<5(;X1 zRp^q9p<0AC`(<{LF~eIHLO|zvC}(H_J5faVA=a_$76_bGY#NBw|M}gtmoNtrvwri# zbH~1F_}s;$S5wU>vG<`%Y}tn&EG@FA^)MqM<_cnu>XL@0m>PQTOp-NaOzpxuFmcg* zSbNkC11KNiWl0U3vf{a=9!ZdHDjzn_yd=yq#0;qBl%)L`pM*}l+HubgQF(Yj+izAa z`~ABKsk&n-VZwuSNo^(84k9N0rm3`OH#S#*qjDDHr8|JN^;gh>7cj1OGAB+?gvk$N zYesjHFd2xk9eh^l*xgi-WzMU&gawK}J14N?7v5)UubPkv+hq)O2WiHGVyHV9FY1t# zfJzv#cP<>-=mL9ge}}}E&tT7qbncEi0agr^H#E~(!YC0FwpEMo=jyHKQma(EItGe` zU)Qi1yGz-X=%Q2SmM$7i6VdX~zZm+vvCqN~LsB3FEocHeQ-45Tqo=Sq{TLTJ<{(sm zkTZpEWz1#7Y?{@aU+OnQvA0O6&gDq))XUVh9&SOV?q?l zOr<)kMHBJM4wkL2J1Su;E72mfhGL|;&i`Pj%7{nx6Y$+LA6DIM3%gc+2glZr;pxZS zT%+tbn4BTka@2H{FcpYt@?j+Ja5P5o2{Y{1aP0dXEf;pY-gXI-aLGj4&@=AI80vLW zYxvE&MAzy$^dGqp*2a3mgtiSJE=1LfXG^)DHT&Uky8I$&-(A8yK}`O-h5UDqIE4k4 zB{+ZSCJx`9!wf$a=J6ZS@7;qt zQp{!PZbMNBiJP=3YwBZ`v6n8?>=#2r?N%o1-e2}6sMW^K12G$Bbb z^h~4Hl)l2InO3i%WzYHGqV$B*^EJtL-TN>|&2cLncLTX}M#2p9k*xWGn9Ke4^14Tp z70OwtM80f==&#Q*aV{Sjx&>%O*F*6i3_YPKhWgM76hA%bxB%1-+QQgZnxsW9jH++( z;2w|O12)^_^y*z1qY;Nb^q~~KU9S|y`pHVQ&HcgR;wMiOuX^{FFp-lm+<+IsmP@iV z^uD2(rQP(%2J1HvduK6-Kib2muUh1IcscCr^M`G@X&2mXD;FyFS4h?vAtv<5S>Co= ziXvsAQtf-TlNfY`<=w-tDXGv5ZIWI4(T31uFfvrq}QNV(8+5xm}Rzx z(|#D(pIin{|RQIC`T&UUL8(zuYBn9&7% z^!@}zi@8d5(Dnzy6vG*U&Qfi$?vV+p#afM@K6puQ!6>1*CJ9*WN0;10*%~Sy>XF6!%HXNzX?EniT@Y(4Tl0&RFf9?Y^2Bw_;KwT#;Y+$hMUMBMzyu*| zDI?PQwC5HkM02=|p^L`u{|7U`^d(G~y%hZaw1UCax}?p_yU@ZnoSnq&f~9+9ud@&& zOh?4LdUuWAmbzEr7ok-5Qukt*#XE%|71KoBw)hRc7|Wi`BKh0so^mA{hsxH>T8h%t z-&R6>iVJkUt4E#>xdZoYhO@Tsc0>9$c|-g5lrRiphT2@>$ArWxS|3!Zt=Gmg$yUh% z=Mp7aPBfJom@N;Z1N9#aeXT8ZmoaUoJ%fXTf?(?i7g%YaM@a1*h}orN13T>l*LiXe z`$u01(;G3<<_P@OtgQ;~Y^Az#(=;ZHIW1)L*)LiyHzk$T#-!1CTaq(IK5XbHmtcJv z(@N_R^yHB%PfDL@2OR6a;&o?Hg%WO$i&wns8%1xv#uy^@Gcwn*;ZeFy7*Tx29;%IC(|DDQq z^NfRp;qsX_z)!-AMNImXlYE)oM#aIGXiaYmCM-2hP~J=xbMo=mUSKRax0x8CqbD@= zp=mIM?zCe43Ru`=HB>Y=g=f9>Np@rfTy;xi8#Ourn&IcA!zM(wW;$YS7#-uEOk1H? zq0Osp_3D`Em6wDg8;^@4uy?&Q-I#bf+mRD3WQ<=&i~uH@klhDyBID(Ipk1^YE`bpo z$GUZwl1dowxR>p1kpK^e$oI`x`P(c&3=?^PSACqT=;+F;59R8!zhm-*I}hW<0t+)z zu+x}$b@>M~u)iA_7%W?(RaOSWwl4&SfS=s71Ow7z^8;|O3}H=;lHl5VxuWZrj9G!0 zMX$E-3&xC9)OO?5r71(%0r^Ej-rYlDIgT};eFWZv?4$@3T{McJb8)}#)g$roCFB%ec_*1ABV%bkS(jmS` zb~(oMmbSoF#H@JMmw)2kS#fs;CcT${+=P+LV%w;EAjDw#;f}BK6V~nLC<}toK zcVE)RXrP9K*@%&KiaGx9BD7XahB@zf?r4fWQR%#a8?ITb=k0TFJm#8&vFa~j(h$?L zK2#|TyX~_ohF6>2+s68YyNa`miv&6mlVWHvg<^6ZYLIEC-AHgtW9f;T+eU-cl^a9pPrb)OV*EJk6$nnH+>El zXrPN?R^E~^nO86_jWL^9UyO+9a6RIBn1|ZO6JW%u{hTJ|;QB251bLCAY^PRgaNSxc zVa^PaFe=2Dv#Y!{Ur+T}7RRgq^jOB`C0dCZ^&5GI2pLoR(vHNYX_M5G*tdp4niDQ# zaXAL`kJOyS2<<4yI26k%9d(Jzf^V?s{VjIFvP+P!TO?sF43;q05aY|O^!Za|;WKwX zPWiP=U_;!02t&9J3Xg<;Fp;q`X7LX<60pNa@&$IT%7FQAheE#(n>p=N9Wqj5i83)55W!y{T}yaUbYjIEH(P0m>_g z+IO>%O)4&j8wc-7m>x3b1!4w29i*5SW2e*%$0u&LrR)qH7x9@|gDv&=2NSvivr>o& z^>ZhlzYNJrd?co|Mq#b$-Y}|tKW_goEn?PPn=IT|#_Bw|3vt`zqP}JaGejdtpt*{r%-`TR|J~D=e?JTEh6J6|(q?#!-6+zv>^;?dDo_lXNV$qyy zgo*x1OVO!%dWYgBH*Qk#63VL;x+Ze{Ow#epb?DkY5h2nl0`7{B6U3io%7`8ET2HPQdg zJbKb!G;1=F9dkg&(3xI=HZmq5&z)#@#-t?9U~B8UAC?U7318p8WyMwabKPS=N^G~W zA6GwyO*>@F7#U-an2k41D~>b1e7b^HCoRck3>w;tm76B8b?5%E<}W7sK8nlzFpw}8 zEaG8V2!U+KEr@WYTjPvm-1HYV>=+g!*f2x~~EGgQZy3W((Qw*K1(N zI@ucQQ4*#tVsiCz6}jdcd2Ot`kBg3ARNwlFja>)-3q#XH^xNb#_aH^545WD4m#KST zRb5Xg7@fuLbulDu5{-yK(k@12{T964Wov?EOjpD_w^AzBO^oGp40!b#Yc;=$?=2SD z`mzl*|5!uC8Yu?LkjTI|8B^al4hmZJg6uWt*u(_}#Qq^By`nROTK|{OKUm(-mq$z1 z5X4LwcvhixJAuE4S={NdyM)tG{^Ho3t^b9|PnR(>#&{6_jRxdmye>J6*1(*;m}x)E zE^{>@yDl1&HY2-=`iEY^)j0X**=($Y>4%v4Q!*99Vl(-97#AR&4hTc;`-;X8hAoG_owvOUeohYQB!;s##K-~I~1bxI`6FBvl% zF;8ynQ8d3=#c#NSbJ!a-60Tc#ipO<&{|m!*lC7yK_aLoYWlZ|$gD5#M82UGkXD4BK z+?1v!#H#kAxMTM#*nakwgn1@o79r-h?^cDd`89v%wo*NIn7i0H%u0;8utgE?CR;;& zfi8~!U}#R7h98QH;=%Ok2(Ul&nB8h-NwkRxxf1H6+NJdhY8>Q66J*R9#H?+$RocRJ8Wg6l}|t>Mu$Vx2^pujPBtf{KZfQs@Y9V>Av}2 zOvs=F_;q4Dw4Zv1^>w!+@#rIHZvfSj?@yuY7ugr^n;`A97{nN^S18;{^@NBDrTW{8 zIpW-G9dVo85(y)<$NdLGFKH?_MHg*Mq%Ik7@F+NSm=h z!f(ipF-jQ|hnVFvZ4~#yjD@vTN_FAMaIv!aBO&wlZh?NAfdeonjb0~BeOqGvZ7AEA z?0%^)eVd}HBan4=F|@nVz+Rl>NNQL;5>vlOb<_0;v@nw0LDPwnHA#q>E8O?dJ!2vK z!rx7PuT7%f)SJS@kW9%Ms%k|sCy!_n>Zef*E$5-%=79S#2pqN$sw+*oxQT}_lt?=?S_TRh;5!2e~it*=<{ue`Cb*c>e7elR~ zIf9NQDKKQiBFO4s%URENC0ByA$)1C2Rhg5jU}Oi`hmM*gS#usS>r1|Sud{a&+SV)8 z?+48n8|8lzu3gEMFemNghX>V6p+0o?NoWZ zxevi(w;`7hdAg+4a;)(Pz^y;YW1we=+nKWs8k4BWyMQg$dr5 z2F(-JKuBaR64C%x-M8ra*dg9E>Za$U?DlPRqef2|m64!O$lz)#ad%!tX=nMWeCK$rb4^X~0Hs zNSVah8+ni?j0Rcdc33scqXHsNU6u};nyHdCj}X(yI#;REX)km&P5C8FRYqv!_OCS*(|<%d*d5vg!Cpf+JDtYlXytEs<$FwZHSZ4S7|G%8XVWCi zYs7S`d!>AOqLXmbnpa<$@J6gYgQIw(APiJ#|geHX5`3YrJp5^2M?>EoEz(Bj)yXKi*_R ze<2#(!AH+am77QQ6<+0-F|oB4k{}?>d(uVwST9@i7qia(447Djz~ZO{oS@%~q%8jh zGyHQ^#VZOy?>~zcC}TPx=BP(6{&M|5p|c&Y?)puKfrTxEpwImn>JHNTMmJDiwC~1P zu87};9c&}bs)_M)8r>;tjboEzbJxPf%2k-%ZuiNn9xhWJ1!b5 z*jw`I=?S`us5|xizRsJOzdke#sZwhwhF%2JPooJ*t3x@^bLs}jemI+ZQq`0cSN(gMscqbWS<3s4`LCM5I9&cH{PwJ>P^EN(+hWAfJfH~MV{ zR5ktuaA}ns<+wdp!i+|YZZkW+TVjBq`CF-8^wx@*J};X8@k`0j_YI8>(wsCsp(%z6 zY5v8G$jk=ou1mqV`z)?~8Xlck%v_hbQ&nVl9S#qcJ)42^B+OLA6x!?Y-0J{g#TTVo zaW<88SDWCj%wr~GTS$>x8oa018pTj|a0J%fZbFHJ_fyV5>f?F9ZdlB_{I@6%_><2M6@r|*>NCnwIa*Y1y2oNZq$VW^NM#n4NdVyJUV zYX>Q2uIU-btDFPQiEFse7H*`^TupLb5vuCocLN45mZKbjGG-ZKt{%-+cHJ5vjKj$7 za#uI@_t3+Nt?E36zCCI1zUI9Rafp{O)K#aLNDO~pIGha!TTTRj=KwDKyer9Vt3~Fv z*`SJx!^zEM@}jkuzs&~3G(NUY85A}|82Cu3Mjdu`b!c~H(X0dsv({5itWXEa13Qc8 z!-GBwS7OC?v!|Kh^=>NoHXX}Z{&6A%b2zz416AKf6vDNv+tRhBDPy7#(`cQEvUR_~ zg7ZD4`tp#DY|@PuOrd7DgrSKQnkLG0$-#X% z05WWt>iUx#@GM5gtd%$PF2wwC{B*uPW1ygi&h3@L#%$%w2&VPy5QfGDXqt#7z1m<> zi+&sWD5RKR)V?h)&W3^hgW!14P_Dn71DUd0huqBt)#97i;ProAYg=T@A;c^+Nc3*3 zH$Yg2HMdDq99Sdk1B&$6URLlHjXNG|bjk z68i{iu(|x1gD3m0E{f5}KcZmg;|Z;jG4!=Y7mbD=mio(>B8zOOSkeR9CAZ{Ej2n^B z1$yM&wgS;ys{ov5%NQ$pLkozp2vYjI@7+u2QlM0C`e4WCC7owVK3OSfXox0@sWtTN zNilz8HgjoG{TBbWYlFV`pH=4@Pr4x4tS?T)zPm=Rc9G@t-f90#^{T>flqK z5$A}o1TlTZ8%$;7B}U`(5}r0k={@)i1Q#%{X15)8F~gR$S*J(B z6E}#p_isQ_++zvTGf={mASU>xj^YEh-*&vARF`L-XL1@BGv}M0`4?u`-hVI-`!Jq{ zn2PHeuyj2OJ3g6mJ)hc;uS$Jlme*I*^11<+ovI~Ff{eL`m}R%E6)|Bx!dgrdjq16S zvD&wh=_zOkJ-S&CKTPA%WHAjtP-|#(kcRE1e8TqZMrR=5Y&RH1+_~bOHl!OClZmPs zV%*{aaP*L^X}UnN<{4sqzq%+IGu?zr+|Us{`!jLYsCZdEK*Hp-z>E}*t){^gidoy% zU7AovG2v-h&@i(L6h^e?mVUG(?nIYN7^o?}O}YeaI>{JVC}G|qrmsm$#jN;F!hZaD zzQ4Acnf>$(GjY)XfezT97@A?Hp&^Q)0peCqWour$Wkc_M?ZNML8?K#(HR(GXdqNGq z2v;huf`=eumIq0gZ-^Oqq@Ci|yY|8cJZzjlc4V?=WHR$TR!A6HWHDu#4WWT9ilO0d z8d9BbUz=F%I}attyr8$04W~cdij+j@lY23ukh&@#9=Jb~zRg$J8m)K~InC*!(Aw8V z=!i#WRPR8haLo-SHDs?q1H=P+$=1-Y9mUY#eHU9JGUtIdDNV_S&PO{y?;njgRIw)> z_)x5yI#kiKYd)~qGNxF@m>@>iU7=`vu7zOt0%v_2xifA$BGWQywUGZF#hB0RjGcs@_;a?b2{@)>oG57JkXi|EVZID ziz$YtS82v$M4mR$%jQ8H-2o17XwSV>T9V^tdgS{iE7ozp2&3w2Bn%rYZDyznJ`IUq&29+$}s+15?Y-ynw8+0fuU#ROZrNd^8ClhFGjjPKR~c5{O{%da>N zL5We0R7WQ6$yun~`JZniWBSrX8)T*^Ibb2oLClz#tHO-bD26yY`Ou<1`fVtNrXnbY zroPM7Mx-WRn@l*Qf|7bKxOV`!yq#7g;HoYO`us=Ht#J+n^_4Nh7D?6&MNDCmwgUE= z2%6uNYOCH6!m_i4Ow8*`3MuJ@m|U}eFo{oHrKA_NX5Ze6V3*zz%qs?P$J^@mM$6Vv zj3$OoDdzX!%kX_zC*YU$=Z4`a5UoaC+|${->ELYO++<9ijG2iTx533emxk*I&FYlu z1#9YsZ^w@?zq-wkFm%zVH8dNg%V|kPOy+0ne_>YkkTK?M z^Pw=bEA0C^kFy(QMUriFNaDjpVM5E(uzi4hduGU(RfrisFvREKgCBg&Gj!G0SP0oV zQOuI>Cm1Qc`X7v#E?Yy3Vb_i|CiyCDa=-C4C~eXm9-o-P9a&{VdZ%cUg-LP3n|r6= z_XrsiA@8)!i21&T_{2B;%pbt8-LjVFgkt-Zj7jum=6ju)^z)?F(1fJnDD(voQ@2pI zX1d1>Q2F{mf2}#(pUt*p@IEcF$J|)FRD1$kOXQ0nSjKEajJ<7*ch~msc?I4#o)u-n zR5FV(z==iCpD`zm)|`A`EoE`rjFvHxTV>4drPn}bsRG_j+{mqEZOJt32-BI=RruqV z2CM63%s_e3_94dYa!2n!aGd>A@S1)CT#*{F1Y8jJqNnW(S7)zzGbl=!~ zE`;mZECi&4aJTgv5oNI^sp`L3oSBjeJMPGspk)%~EMjIEea!tbxr#SDqf{TbI+vf9 zvx%A5se+*$`P7>K#YC@nmC6$6wbrbx7@}6O@XdWaxA=J@tYSgQ-O8b2+o%-i7gHrI z+7lUb0WqU@dMY&*Rq%Jxa6?CD3pb}tW0-XDznFwHYpE=OT0=4MI3Bs+t~ME2ehVCq zb6{o_%iRiXL|*LCB>mp*635vegUWc>xt+9JvgSHsJfi+(KxEZD-#4nN4yl99g{TFXJLp+)2rql+aZfm?553l>0! z8JoEBF^!1xRZZgc{D8;^I7jL~DZHgCB}_G4v^&YlaqF(}d3%)Vb=#wbH)i{ow09x@ z#Tah0mP$q_#%q=<@oZrtd7YE(Zb9?X9#C7egS(Yvk0P6zWYH>>=zaSr#DvK28xI-t z3Nfu7tCTGR^Z0-r_*%1BECl3-F#|65VW^@qwdOCzHd2e!`nyVXHq`4(>R1Mc5A}fP z2T|Nv9|z)UjM8mqBgG+ejzG}`Ia64@O0uRNG4D29Q|_n``77I$>PNqi3NQH;%%iH- z43(k&UrchC7NJFbUYMt$n1<1}p)8bx?>i&7{WlzlV}mAXAEOrMY&Z&9ljTfdr_~bX z7h;?Y?kg9@b}l5VNB6hk{lO{l(C}HEIpT_>acK;|Fb`?^q6}ocuuP z5yjnT<3JPE>V$o^y5qM!QV|dvby+fGDe^jfC$<5&{5p$tg1^;@YS`k##=)V}+ z>Gc;wDHPiI74ekvS@-P89(;AxOeSgnA1weoR%>bh-shjS-Egw z7T*;yE1qui3GS=OXlxvpORb^x(Ep2B>f|bwT2X8K?%e{{e!U>jH=OHLPK;sa=$X9j--F&f>TD7G}$VTijiKgCmCG>V~xV|3AI`6#XE zqSkbuR1WDcdPA*61Q%TCK)jQ&Qg!ow(V^2(_=+PFX}v(6jA@D(?S~(gN}T)gEn2DW zY(9pGXkMepO4Jc(-&$#sY|Z~-0;1$^^JngDIQE@|KM!|vhNB(HNx(|g{>5VXt|PEN zOUB%hG3^jDBma%EL-Gm!Qw%1(eA_caEVF&wTblhB(|}W!**4fjjyr8$jSHa|YE7Sc zrH~%b6a06Cb9c|#lLzy($e<ui%*Up zhKDFvPZup=t%T``n6hUT%2=;7p4qEZpIY{Wu_%hW+GIro){O zpJn^B|AnCim(&_ssN5$>#$p52u%jslX-8*qm$DqlP;?i`ieBQJ@yTG(RzA~|8zpPzA|~DUkTPj;c)2A#O^}RPf|!cW85JJUrcGK ze65B17Q-Q51~%N7$+Zn|Af2&OqVy>zI$#(00hN5MdCH5n4l$+OMk+hEPv)x;6W@0$ zQH=wY`ssQ!i@_aQqYw;G{+5)Ee4HKrz&T zS}PPmRD=&a>@$XY0rn(hu^wqCEE8(IlOT(ettpg$o;wiJNTsRlHz1img_xPgPBTNU z^z(^%H$oBcL~e}vUkvTPp%ug;${+KSOJM5oE->D@2e&=ef%MhYC#zcJ2>T|a0J}hT zpp-J^AY!&hr{|_0PU4^A7D!PAGmlmc_L;n9nu3=0Zfs^oR{yk;`Ut2s6hrHw15&j~ zMDk4t@@WVD1Nw361MSJF3KS7O)mMCClnm`3%GNxR&$MHRS>LjG?ylj9e13vb-Skux zGql>7u{bzS!hH5IlSYcyU6vQ^YQ3|B$=!;jRbQ?{Qbt#ZGwH_t`e8>#4Z`^mCZ^(r zGsoeYt{mt}mN6NKIUIkn`@Y(vy!{cSdh4P}rnye6A}HgUg!w+qj6BAX;~ z#te+nCO7UD!Oh5y@Z*p-*D2JVc&#xY+Yf$MEPQhea&lyM@QRF4A|@j|-aE_sDE|&m zfr`?LO!qGyjJ?8)DZsL82~%Jtb*xZKlO$)d(%Y0!jP`mIGHclu28`{`={>X~eRdd< z*dg^knT=9m;5K>Ds$|S%#O!lx@IHU>2p@Amss6F*Fr#s2gpb8RD~48gH_SI9Rryw= z(o~nY@mj=Xi?dV`@3&l=)T9)_oi81r+1n1BwqGL>Rc1g2*j1lzl6V}Nb$%$F&>!S2 zP>h(8ly*Mb?jPpQV`I#>%Y{t87amOZa}$PkdhL%iBX`rSNU({FaaiOm^%3-#hy|EA zMX+a56KG}Bl{-^pOZMd$l2HLw3Xg*+@KRfT-*~Q*4x0+Z_+R()xi|bUzk0V)o%L;; zBI8JqBHP26p(XKj7T%1#R#MXvwZ?J`HkV`b1;q?Hd;?Y!Pw>9gg{v`YM1uT{NZW=^ ziu(D-K<|&d1rp_-=M%)ZoF3()Qy9;eqdWMAA6R82b>veF zl{%)aBovdDRs`z~w1iL5y|^X|>`2#pn5fLvWyk0rh4}sQOS(kHyhV)d^+2DD)Pwx& z?Mn6W_gV_ijQ5HaLt9E1+fsadVCygK^r9HrDo;DTiu&TDpLaK5z_cb{Slo+aR5s-E zGb5t2#)56zFB#l3<=5I18S@1(8H3jQgswWkYi&h8E$)=hy~DkjrX`jPZI7dvf*Dq1 z<0u(3r_PBO7MhYSZSk-fRSZ4uH-YnOTXNsd*b$$3#$@{*3)W+7GHlV4t>NVpTH`Rb zW6uinN!QuWn?#~o!d53mMbQ}M+lY?}+T-Ey8sDGT`b*p6Xiwp^3MZ2AO2(L`--P%r z&ERLB4xEXb9T|fnfuXH}*>P+Vs2gN!yhEfdV1$@3=Ww6vHG6nW3D&8D0W+Pd5hDz+PO! zcw5pBtG>$~#j){Dhat{h{@oPFn3jkUo#*;|cH6?AS%ZCR57+T-I}(}Mj*bi!WoXsK zoTOsEG{sO+h8{hgh&V&W+?i1dYf_p*&}%==_P8w>a1r%72JK@{|2PDRljU!-P{wpb zjIs7?pB?u@`TUhA%CIh2(e1%vre$WmV(EUIQ5Ya&;>%=AHw!0nX`PJOxThR4Ke|FE zSjwfmuqLJT#^ja7X;yc~5m>)W{x(Bp41<^+5fgnvsy6Te*iAI)vVqdgH;?IX*O+;X zsv%y3%t=C)B}u5&m88JDzM|w|h8dxh-rFmpwHABEBGc$mFgIFkHR)|1vB1Di=k@Qv=^6RQuXvC%>H|hQp+#J zc$nUW+2Jl=8Sl?&=i88u4~$46zn9I}aS+NfWNVhmm?4O1yUNd}>DWMi+ai2;+_vH? zab)Own#{CK^Rh9q%V~ADqtdlJ}8R3Oh}LY*pj{3 zlAP%-W1Mz6lC@su(xQ$3S_#``Hip?{W4JE(yXpVch6c0i_|{PP?eAz2fGn1`!+coVx0 zeDrKg6ZHwqEiqLwEw$1VIYq{#M#JJ?nD4(FNb(~Y)BDc@sBL5mAA|=dL#9YnN@LoB}gI_umT@LRgUi0@}=F>(ChU%)_>Y$!E7d)Yw$%s8}+(gb#Gvs?cNHh)iP$CY|S3TsAE#k zT}-p#ZKf;LJG(gYRkdfCASVwd^#B%F;D}d>p{?>1QJvkyHu3ypFA2?1OzYj)Oy18C!n;LtyJ{`THk|j7^1CUgn->o2$I4rvTE<*M%-~R4 zW!J1&<)e{G^@ArY$%!mGF4As21%s@>Wtb*7br%&FOYLnehFg(XulIY7?Bx6{=XHXq!2mM^4xuG?dv|?3G?3BY1~ODyKmR+fUJn6dJXYypb4UJpzCg^cA3t+jG}PsK z48o55Upo{eJA-kLvS1#^V-+L{X5?a~or(j0e*OQ*dh4jFx~T0N5b5sj5DXB5+Gour zDkh?c1?r6;24Z0$7NVe{7>L*jDh5gmhjaEmVxy>tqJ)ZAw1gt$5jbSibkPC$NiA0&13K(4%0(04yB(8l)Vq;dru;n z_pWW80@?Fa8(*6B(nMoOz7@aNL4FS9P*0}N*1A*I<7a!DjoV3ls);fudMY@D(W$&b~>Ys*Rf zVL}KBT^I-6PxuS_>Vw?aSP@L`$3^*GbwAuA-N+OWob@c7?ndbZI#aCT*n&S~R*|AV zR%nLROkoYuzc!L9udWOZR;hs)7kO|pOhC#mL>p=vsiS(b4ZRGFh2z`!??#Eo3?mo_ zw!7E*LD7RAP2$ko|52^Yqo`9YZWQYw$?Dl`B9)Sx`V=^2*sBS8xY<-2|JNst!v{Wt z#&8XAIB*zE*s6uo$s^f`C_nUZXe<=z@u8sy{C6{!9h>PB+`co49+4x3%msrAs;@`i zlX_}Sv3>;W7ii&r^7!>rQxTsJmBrGahySf0!4;wt**v@!oTWA3mhpDfLe2u|$!gfE z!51B~*au(3_|^pS7)&thO{TeT$ky_x86jkTKEzb??R>YOkVemApon)I)WS=yt8pSg zy1PjtUkB0aI;)LYw^I2RH4u159pYLd(b5_%Jne=$wzl?1;|5~k^J{(zjNuoXsRT1B zUm5}t8zCVCS=MM_E6E& zmK46eI@5D_HId8zMPdRZ>^)_c= z#AIviUR3NJ2i+R{nl^>+w8aGTcEdQ2TSl4g^9jcB5<`7Rx>qO_;aJF;IIsdutfja* zsT_8AA&bRYx_IPN9Xx8ZG@hwg2@8K}60w;Gbe{+XD*V&HH-uY}#?Cn6A;Dul@R$_@ zb8AST2d)iwuOOY)ZNee z&?+c!RfgFzVJKRnjgQYJMxE(QkOk zRr^UFAk>OjD&bMYe!3d&Pdw8kp7etOC7xuq=<~)1>|k5=!s{V zt3;F^bWOw>*2bPAs!20QDjcnZLq8A3b6mBF?}{#Nlb6C1%-)0UVOhBBuo+bi*2Al7 zwehbxTTpz^0hl$PFIqC;F=q(ozp_0Zg#~Mbizg5z3xj8#^Gj*b1X+pbM36i_Ev1Ve zHITD35j&Jukl1n*`K0RN*5%sx-0FiUCw(8ZnDb-v zi0`yif>D~g&m-vgd7=GuAv5gj63c$KJialF2r>}sFjgg=mDW%2)524( z>2cDNbx9Rq^G^wEdk>>UwfeXvL<^r=dJaAA*$;<0`I(l*Pk}oGvu|U(hobZY;Zbt3 z$*HNL0{&Hq4CWP!wtkhv_wVZB(^lkIxKA0g!e;B=5n0eSJ ztA@BYOb3UrJ%suX>;+?nZ;c+0$tRfAWw9QDlV64V7LmK>KW(Aj>ANB-piC6Hi^#I+ zlcJa+C4A!@ku&&6#LU)f;!SJxF>8S&aDD^ksWKpV6^HDIN~|+k*ZLJw(TAixur!>X zX?FZ#Q$#R|ucJKF@&<%|LWPWoRxW(2bBGjTJQmFwEl28Z^>C>`3EP{hV0U$SJnlC+ zrZ?*2o(cW1;X^6hJud?i!6EdSyy8}dl4K0m3n;-O20}*gb<&D_YhDn{3bz1{vkA(D zvsMe4c7r(48Hu|HMqCrI4$SAf^su->5s&g!!P5fdG3)F%E}SI35{I&1XUo85T`!8B zb`EXTF~Dc!weUJS5nAdU4gV?fiOT=8rj--SZduCX`%2BiMsi_4eR;cRMY>0!x6cj{ z>x-MYP#;eutMim>^87$-4_F2NMfC>w$E-e341W(pC#k~6b?1=WB7MAeiWb%xoPmxV z-Ujo7`3z!penQs}Oi%F$kM?Mt!hM@b(NavdFsM$^L+^p2$a3~zTvDNr4-f-~P-j)V zx>X+gOd=whKb9;fnLyB zTM6RK4&*TJB-(IB7hC5NUC$A35EO;MI#a&zeG?9yHtHHnLCA#=jM` zaQ683D5NM95*G2re$RN!0Kp9UWZ@C4tz3AEblTI#@1oa3?oh24K6uWeWO1&)As$DZ ze8z26!#4&ga>kpxw;1EY_le-_KsDTX-HEpRx{HiPYUArKweSbwXJkDKI^O zJ3uL1mX^|cq3@A-O}emX16ex%GcJ5=9Z%Wp97?%=7=+(77~)Mct z3W=Qw-n^&>7{xE3Zu|~;OeSVq8#M9bGEMx`rVUlg`on2ozBTg?a~Lgxx$WQQPP;V- z8`cULrTr5N-|pB$MV?$m*={69^JpVHrdSSd-Jp&`$%$Wg4q2^ROt6cj8#=aEfyLBn zG)X=ag_GpWYBCGO)!pdWhe=SW#bdVf7!!gio|NhSv;3W~j6^x2SG*LZ{bQ&s|5%E3 zl{eHkCZ%z5c(^LL*6J(aW|A?~d)^eY=Jg@{wa|C(2}0K-s612?XJnEieat_!V1gHH zO5ke>F^{n$nB~SH?wxZAgcnF$;F{H05tcO;yv;aAb(1@cd%7|1C-v&NapYonl3c5Z zyhOoDGc4291wYSyhZQHpD7612x}HdiWH+kfjsAvEbHWuu*FNL6wNpICnP5Dttlg)1 zCJSZAnijonN@04#Ai?5!kExI3oc!lM6a0}>+^w`As+P4%SaB#3(H?1z?UK8|#;6V+ zY`BFkPJ4&K$*Jast2%yDV+g(HM!*>zzBQ-#Dd0gckLQ`V8|3*5PqHg?>1H;RD$ud+ zpdJ;IvzWRm786xIQ<6}5|378CV+$Fd9t&LQ)CKy|KcU9tI(lN!ggh4$GrKlbe07W? zBrLE6g@=5N$8sJsfnbb2>~-I?@n1piR3X#6OV;z(Zf(Ia8)<>=RB1e(HpQ1o%|Ipz z;8#3Q#_6OeW+F+8FM9qLtO6Qf*u;})ZGQtgT(5|gi3C!n%y6*F)PNP;eEm%{kC{O* zABybU*Z%I$pMeQxjJGH;V}jsiU?;`NP_HIRN#wb%lsx18AsH#V-^i0Rc}skA`CkbC z&;bF<526QMoydL_ami{YiI^k3fYFx*6vkH*?dCD_2?p!y=f%JWcQjVW6c_&yopM|x zn7=|^u-ZckTU(gpcSA@f_X)DdZzhs$%_OcSw8Dvl{(?$XH{|VKj6Tixr>726KrVZ? z2{Nog>B(I!XizZCO@TN36bL4mtL;w0KVSBE7?9&&YqT6P{ARK$U2u}&0#*08-j6r0*aWP&-^)ZhVkt_%Zyu?%LKoFjBX^}6!4!^=D*SfD%yX74xe>hjEUs|eN^B+`Qng$9;cKHgZkX8%C+akDW&trsRg}iV zXV~EQ(oX0SsN)p5x9D1kzNBl0hUBz?nq=_?9m$s5R5W)~Du?-Wl*4Q$7`4Gu3xfjE zJ&#%lnUQ!Mv+B%AIZr)|QzQ0!q$2(Ql`QQYBbj30B>5rZB$-p2jXXc+ahSC{CYoRp4h=1Iz9&uD=#c2(xQS?0ayFV_ z94GL4-U(w?nd7KsFCfaDxG+b51*@p%9ELSTwOrze8$}Ih^iFq4SSTgQ&2W~yueFz) zUHb(U?B{cCUmW3D6HhRg&YHV#3`3N9cL7tf;TpPp>n*Bre<@)72o_kGVIz$+u*!S` zT5Afy%jhEPDzV0oU0Oil)fjA?SA+KYn@fIc+e$vn)sReHASFq#H-%TOq^yMe3V2Ks z!8qL8?Rl;305$b(0dbE@M|!Nr9hZH*cvac zu7?TJ#$z9{B9AZsz|^d)V3QNd4 z0^4a49+O2dZQ;(;LN`6Z@f8Kk*VS?;`|xB~I4MNnXHyAnYYp)0;umOdu>q_*cpn`- zcoFHgTjDIT2^3bZ#i~X6a3|#tYT9=P4H|tJB`=ePuZnK)-GTRtFihm8fQVqq7f+`Y z7E*$Uzyc<4hYH#yyAST1I!slQj|nF7R3sJfV42{;i~`2VYBxHk6%XYj zbE&YvmoRavF4oX)MyYC+5J^2otMlp}ETQV&&p=Lt+appCntRY1ep z366ICMAQr=_!CH4^Y#;b?>>ev{I=;j>ws&qlnL&TU_!SkH3MR5DpF8J*}4QvLjgGHpM3>kieVG*bB zL>DbcO7g@IejbGT*5ZoBOE@~!3HHW$aF`$bYt%Qk)6P{;`%?-9MT!N?vY2fs;`4T} z+hQb2j1>YK?yk+e3SsYW!keF$;ghqFYmH-WHOyRd4huD&qsuM=qT&5l@b*|4AmaWf zTIdQdH;&>kbNR>O7J|`S^^S6Beklnk1!|0`9 z(A_g0>{F9KDRUcE*388l?XJ?l!euy2GM{rRb46MzCiA=JO#DaSak79pwmhF6H)1XQ z!(10Rx~2h}mJmp zn*0!1D!Fo)|4AZOAsD%Ta)k*yehKbBC}4)z{b4eh3$!OGb`c&(0rrJmCX#H%n;XHa zo78v4i(!eAEiTTk;xNYJr$O=Q034?@7Wet+LQ1V zcKS35jz2D74xTR%#65p3?$a4W8zo=jrohykR<1Q!&AH&=QV8e0?C{Pxl^o`mSPsU_ zUVxvMy5h$R$KdU`7x3vSW5&ixk;7<&a2N}Msgyb)(jTZ3tZpb^PAeUv&1!q-FaNNZ z#TdtH;drYS=p+k&*sgpy{3ah_#rF6@Vp{2DAA7sWdp4u7~~RwL;J3PAHbpaP3|W{JAj{Yt5>LvmU=; z%Lgs+HvS1WeQ&_Gh5vCA`q%gY`d?LzK#Kedc)2M=Fw9jys%Gg=fktBibH8OIlnmcZ zf4^xhcC=6DHUcf<4q&~B#u8W3GqE`!_%)2f7`e*AQp;7$s^GWad?6WfeSJ9$-TIpe z)IG|un0!BOY$g+o$EOF>MB7@yRx&mQU&GM_^CY@KX&9~5eiuqh4RJvEZ(t3b2JD{0 zkFU9K*~JkjdX&Sh1EUz3B2@`JwGPs+UWL?IWAT#Ld6;$sN$x^f35$`P$zl8mW?bzz zs)Z^SC}{|pZBc(vpPv$=cG{f|w!8zr+jTk2q6TS9uY3c+O8KBlO61}iA3^`+7ffgK z1j%cIR_Okf3&XElVFS0j_(;YI0F{dxVXAE_uu6S1 zNY!KBd@;o6|9~rN$ZO!rE@t=8$&!?P!*Sd@d3^ubM@W%BhF>^g$%Qx>4zt*s!>l8i zfq5gT+P`UnR=GlENA3uJ*-J3ivO1!_wTS}Xfg+WvS|qo&)NZ9egH$x8-vuvB6P;b22I(jM-L94hU<@*;cgDs9ZbVQaMy)OAHstamBwZtQeb@^q@gzubq z1PYfbksEy%h4?DM+e3*+_Z!0L)+Cx67X=3sSKt%>#HajZVGDXBxznbW|xM?h!eENp? zlA#JrK6xKSysU@SVdNQnm=yN-?+IY$3F;bOhmKs6gYBP^(M_7CkHM;YSMbF z7M+3~&ynJ81hqWoHovK;_w7J+`e}*W-*BrhmjCWXi1o8ZDp#UEmFix5VZ;7=SYxqU`Zjn zLc5e50h#^3VCyPP?$K-R-lt$xmjo}}R3Dk*vIAU-dUUY82*{vG@ zkB#9v%}l^yiV3Fd;Z)H`)7t{HR>V+eGhm3;a`aT3FKD>%9sCXxBQ3IYCfw2H0>nb^ zVn7>q9Of9}FmDNFyPlb-XJVFM z4TzYIAu`BlTL;RxM?``L{z4Y1O*_-x4MbWCZ?RIqBW^zj;kO!Cb8`T~$4|sBSB%C# zqr#3TsXmJB7`5xCz#9hy1?G}~!=c+4k)8N0z!biJxTP-P@yZiL*Y?bkY>JM+>7 zVY7N6O6CpRwCRCnUwtkDHN)!#EWYy>hOZ>Dt?pJBu4!OZ#jo%xJrkVvOn{g5OK{}5 zj|e$07qOV5Jf@Cd7Hu;VU0;(e_~$KRWZo}9!H?SL)PjlP%8C7OW^OrHg>->Ww*fA@ zsf<}n9_og7#H0Pt`SIBOvl^DYKx%Qk@4)$b}uf0PD&e-5H4 zb)Hyt&~sS1mKV=@z+>c6q^0hU(hv=ECf`j*Av5xiD>Ib|r0<_{7ZiQzgUY*K;pRXW zjG9L3ZuV(oFS-mGrAU(UHANhAVivZ$tB;dJUt#qjAskmy6D{9jh5tIAhPfB`37y4b zGzdm<;YLw++6lo9Vo9-ORUZ?mgy?0WUP0E5K9Ctp+$=~W@G@B7Ia#`RK;u398A@E1 z)+pgMu5)lev^KUL^h2PfyqnSsx`;;kt%5};9*&MPk$6@($ou39NyjDoMcj;OB?uKT*SbT$7oN3Rw)j zIgxpM;tRbrbT^EfrOILE@}H*-!B_=Wi_V4Z7xYILGSbR^Zi~Jw7ZpCp;z#j z5d?El*g+gIw+IS}UT56phk~VvCXCHw8v5ZwWJa|4_Qu}?f#B=N<$|?RJ{$Lz2Oa!dHK-(e(Y*8^3Q??bbeAXyQ*Kc3R ziuW@m19E1PCFEPv+Lpv&=JB7W7r~U}JrQM29W6K`Bx-Oots&TR1~cm3F%Fa9LfkDA zQ{ab21L)b;0CGGFtXcvqY_?sM)a5!B!(b^>Nz7wc$=7FNBsm8164|>l_-u`s!>r^t zg6RbFc=2&j&nHcR(QNXH`d2O0BQuyo`KQ1l@W z{G=eZE=mjMOXb0H-%remd$N-8b2^zx!)`F%!whl%H9iw^HjkN0FlxS(=t9S1#M zv+}+nyx298S-B?_O)cyJ)~XV#J3*~{G)%Aw1%umpZn)fZ00f5jvM-&-~~+iyBBs z+uda_j`r_BvO7jW>S;yL`1%>KGcD#w59q0B;C9D!809%hFm}%@ac$i;QKn9VKwxN% zr@8X)p5u8;7{SPDHWogeypeLTBuDk(O|e(kUDn?otjaF`i&H^%+}u!*KbQa z2r7sh_HXoa(p}_|bRTsN)S@jn^>DoG6%G@?AE0&;%w5?)QKRuyPm{g*Opw!a+WO-= zy8Z6~6rt0>9o3z;enXLlB%en43QAMzN33eEnLV|2^TbryTaLu9dvPr=R375`IlfBpBbIOi|X( zm_pU+dyKk$6)i7cLZ1)6hr_(mE`jW|M1I(LB8eqfzsr(76|#j@>SKA=mCYA?d_^rK*q{1;uC zL$X)CT;(v0y!pvBg7FKj5M7I3D!MrA9&=&MV`h8gTl&B}In)mIz}7|yU%i7kO=8%D z3t&XWdte36*&t-zn(^3$JX%`M+zKa$S;6y;L#SD-N3#-cu~CS_47hTw$sm||k3r&t zd(Vo>4DK;08>(n;)g(Gvs)H)tQU|P0Vc6ks5d6IZ+AZHh#A|Y;Qc}UiOTI!vra!K= zHNXX{V{y>I`FQ3Ja^AjTi|R5Pp<%%U4r9ifp9l%&$(wGG+2Y%xwyr#8f%*ctKVOGd zR_+ui>HGvXMKOLf@mAIU&AF8-3I73Gz#M${Bc$6o;NrAz@MyaezA;7#C#{+U^8y!u zw1+Jo-_yonw)36#kYFxVoEF`R&k%VQ- zCifenZO38)PWJ(usGL|(2?tM)z@L9~!`M@%cj&Yg9vF8*2Zw$62=`TQGdq{GG7lW2@DP1@yyA%xzLnJlM)&?O z5sl3pMu+b-C4xyC<}NBZ+Use0AfG8Qv_#1-6yWyX3_AE!Ik0A1QO&Ku=5;2X9Du1? zx}ac!27a@-3<8j%#AK(FWZ9%@$UfNx0j;|D&>|wd`PNx-;N_gip6C0wLyT^S6JL~3VgFQB${G3iL35I`1b54WWTb<6JA>5 zFEd6;?hMl8Fk-&bh7ioHRYKvn@@z_-gjD@37NMtPQ}%F3qHoUI4t`5=xKpR}8f6?I zJpgCYn&Hg*d*I)*7+P#f7}NP`l1aZGL8jz8Z29Gcw*)z1`RV_dpyLJH*i`bZaUqz+ zM9*f6atZa_keCTKWTKsuGLYJWU3BDu(ctxA4pgI2xfU4M z+A(=0$LObnC9v&KIjn!-hF5!g;NuG>)6?8kxtPr@zBLrV7#ZhzJ{?;_g@*{4$-@|A zCR&a5t)EXnwfl}zD_kIem~pe2DPHdVKuiCCZ^bTPvG5u)w6#FD-|5o2Rp~JQ%h z_QJDrF;;qTOssj(j5|Yn@r#W&!E{_{1%@jgM0dVk1}#MqES%If!y&+`eK0ic@SEhM-j2k2V5RrrG?tVu-b4Xl(Bw4V}tHHZ# zU|mx`!YxZsdZ-fMpd-jWG7W+Ph2XSdEWUAd0uHq~g3j(y;xMD#xd|OWFvhpHQ%}pA zs9V`22x;If(7EPHr>E@}<$F}36$*7IqQ41lkVNuDvVCjsEXRMsE)(DS7Z3s;lgA)h74_gXEXrw%$VIQnZS{9ZX4ip+k%^-(0tF`raLuB(6* zJA6Q4xCK~X7L&p+oiPNH@8d(sZY7e2bA(Kc{3uc4+o5#*%f%@E zVG$&Hipl3#1Mi5h7n=rGbhR9W_ufKQ_G7qiWe74C5)ftb3c~8M!FISg&YR{&6qY=| zDrGe{1$OeSIYcn0eK%0suO6UYHWe^-VMhf!mfO)?N<}DQStHzB@rk<>I_)LqH2Dfx z`0X7RTLB zs9Ea@7_~dqVqB(E;8-Q(Zfn6^^5yV-m;F~*a@XmX!@S}@=VXt-KFgXMR zNyFSHbR4AyPt9i*?p}>7wXD!H8wK*;|AFEa9T4pF0gjoP;Peg^4wEoX8po4E)yS&h zSmtRLv=ceQ`ndDp->rtt5*_fGOXTWhYR`4rs}UTAW;<=}b&s>!m#On7?=hG5DpL>R z#VBBwIs|02!<$2Ypq-pzE>AMUnt5s*hK<>Y8qQ6D zR)X27ky&Wx^O~}5&SA`ix#F-9=LAQm+(+$enxNlI77GnTP*O`OzextM@Js=)q6{qN zYWO&u;!_V7I)_Te3;iWuws}hyuQHUx)jx%uQ~5NwVLYaXV1~QY7G`<9r`k5;FsTi* z=nsKA1PLn7k??9gIQ*2wJs-}4U(G+DA2h(4_OrxkQH|@gty8AqkoZJ#(djRC=I=^QO;{I8XY zo{-Ii4D6xbuiPMbN;IF(kR`KpxI8|3>oYpn<`3K5#z5VxQpDD+or$Uk`OC|&M`AB9 zX0HX|6O8Ebn>Fb7j?U;^YzBBF}oaLv99G}>SYd>Gk}W^THRN-t^Q9>Y2?4qbyIpc_>GD8jCBM^VO%cw}3q z0`&dMB(Ia-2#)dJ%`k!yk4+L?F8V>?fh^{#_fa~np+sD_vC7j!QURqUiddp{3r+Vm zf&G2&P_&K^*&68JPkBG!pTQ>lAGswwf1n1ksc}eEd=OPzsz9UfF^H1C$hGDuzk7}) z82>MKMUVQ)kwYV!xvYGOzA%ZRS07t1jt_bdtkcrbSx-=;w*|N{Z&2F5&q(#SE*BT@ zl8wL*n%h7pRSUj8-htwb4krfN?JvbLOenam^GW z`zRP`X~5;#%saRYf1zJ+m>=E|*w{80kF>mljeed13vwrtBEKy|x$nlGV4TA*h<1Ly zO3gi$%>@0^rDE4VqkTWjrrWb$16#csZ@3q-9;ZOd_!xL|_9XmCH^ei@j%p^e7~fu- z2H#?~;Q3+kQ15Xam|<^WAoUW&kCx(AXv}|}iwWk|lmtp6WXgvyGg`jv8YbvehMOFUE!aMbLZZHkj{=M}If`2N~~P zq1$!|ux$;$*rf2E=L&*ZbM}}h^Z8n8?7kf4r~7*GY&kpHEJ}kpWBrP|NqY=xf}-nx zKuhU0+$?T`0%BULw&Vji7lh(Fr^}$k?jrn1O#uH?UD&0oh8Fn*f%NdRT&KRlu9Xc6gp+hT|2= z;qIpyIAPEwP`S7V8|{+99Ym0BO^y$?4><+Xp7LpMA$+H8Cm1UDb>WpIhp5zdxlB%f z8Qh$;4UO_BptGJmhteKhF5xmNzYnsOe&SkVOXQAG(`$GgG#f9Iz5ok%kovaVd(bPV zhr`6<@SU~;Fyf#YH#Uim+!Tl-n50E{9<}eUP#u%=7`c^8VDf=vbU>?(_LF}G`;zo< z;=6hhz#o9x=Fbo_p&4w6ihrKfD~R=^u%qiHNVOP*mq^7y@fTklx^5S4zH|nDlB9An z(WG_`;V?%DM&!2LGjPHaYC!ECb8WF1W9E~Lx|WV+JW`&)`XL5fYi3;}55?jd2%zg= zVwMdSYL$U~;!OO#=LB3T^S~3nJ%d5F9Ppsz|M08KNw9GeUm+P|$6?M8OoC0UXJP6W z%CPeuQ-9!tVAjm%=-oCq4#TD>29WgXcfMp7^{It5F5gMGh@|t7v)dTwX;|mkNpK`5 z&0!a^!2gj0UiobW-dNs_a-QdKQ=r_2!=w@nebCCY`H_@BqZh zegW%vP+ZWC7vsbII=h`GD`N~v=9h+_*lTR?Kouw$p zHWR^!&jrlIvyFly#~z@fNA>hgh3CK~k!LxyfUdV9Ufk9M9``=O@YG>kYxXXSWPV;~ zWZeHq;cavFz|-lLxS@0n_F7;n(e`TNFf}};h+qyJvZFN8tOe4+LT0P*CyJ-cQCII> zIxPJ$tgJW04c5P)*IyZ{X|=)?@kdx6Ws7T9k;y*&7o%7@Msj*?3w-$&3^qg$AB(o) z4U>H(=~m_vwl&r~<^{pbyn?8a4UU2r4}=UgsTb|_+9;|n3ZuR93y7rwIW&>;+5%F$ zcJpOBuy;?kHtLRk7HC##OA0&vBxRW`(3=ztUF)pzysoYI!RJL14I?`aqsGs)a)L=# znok{EHd1hvSW?V0^bt&&{#zh#vy%20b{Vdy_i_*UY+S(T!EZ=bses+K(%@x$6mB%A zN;)=8mjwLR0z#jSP_@Gj-<6BRJvLJ%znj!JOd*e{A(+!@!IWQ!i(v7TLMCmxns~Ub zI(nF+L%+4(1zrbUK;q+OSRbH{uN>-xH0~L`4EBQ`Id7Q|IXlThZBk-t8w2b2 z*kbi%Tk+-uJxS#Y^4>sxD;&6))<7^luVzsT6-No`LJAoZ&tm#v#b;_A5t6Oj;RGJp zCqc`zk&6oin0J8(5zlOJItoWMR3JBL3iIU2E2feJgO}Uvg;qNoJR&3#zx#fcY5a4B zi`jVd`^|5Hso5u>tk#ba79kLI5BQBpMFn_3;jRYordr)9c_n5uRg1Lt1jLNOr0m$>&&!&Ndss z<4d9FR`G9mv61-tm;}@lrObVvn|O@EHL`ntUQ5N6juhPLAO*}rwxhZ3 zrQ*LYPN5;cZ=$CY8#1YQjO=`rc=83Y zQI2PqNa1pYG?!#yFzYk=P<8?xh}8$RabZZxyc-rsJHVs|rnsnlGd_G|H30xoM1*du>t9t+=Avi zJ^bI8&BagT4YbP%lCSFED>V`SPs~P{pJ{dk^WSu4T+{MI%^Bow&pW$m;Rvj$KIgV4Eu_*4#a?e(?)nh5??o6GUkFQ zGafvF;GYLT_~rn(>=ocgr-hIYhWKouH>h<=~|Ao$zePQX6w%> zly{qgAjdbKsdC&+N4qlO=mm<U?V^5R63HmXf+IBQQC7kLj3lUHo05 zNsAMmz)_(A5`UJEXzfSXeZw4!y-8*YY0Z@pb-+GI-cCM@qz}kK+x`ydT;mAaXSGAX z79X5jUWoSOSa6@`WPV$lK`@Z3LFJf83tr{rF@ZI@g7BQdR29*8Y9Qr_0Y(*M|NjWz zS6Oo52Nu&q*Mk~~7^a#!;#!gv?Ab(|y4VrVm*=y)D|pO&wl!Xz z1xJ$pQCaeN%;WiaOi-bg_)(TD^pG5mhO$o(ar^^3|6zr{H>+Z`laE0t-3Dh!2pqr- z%Y4_yX^&m;vC&K63rShHnc;%xyt@J0KR@C+t(eCI6HJ7at|-fl)G;UKGT9@yF~PCk z0{`<>TxiH|-WRyC>K(XO+2G-$)Uoi%Bakuc1ebAtU^K}PQnnt2zbJd)x4XAO0m*6| zz1e*`v>st2o83fxT7;ajtr zVBWON6~(m52|hGsGv;5-LPr294-I9qkOfoo0i-4XJ}vb#)GN*_xZs(FC*WfupFnO-bNmo6YDQ zCmE0~hUnC-a&%?UFGw8O07CL4bUAz&p0D$64X-36r3> zUItd)I}g`Wi@>;83?~00)7H*U=y-y$44f+J_^T+;Jd?%j_UaTF$8HzxUn4@nAuVvF zwgqY@eu8J(PPlM`KF*4L#$^q8Z1_X!2bSQ0Uqmu|sWP+5H-;&a9HG6Rd7%u2OlbR? z!i~)zzBNe%vu{L#C`V00@M2^Z)3e)w!80$5RowHDQgAcGuW1LzoGMVo&RjarowQ=; zA3qpRUDgRbqW`dqpD}*Tlr!6Q>q#7Z%9yezdl+GF77Sg)UvYc+)?6T%&b~B}&JzW} z!%vyawyO1Xwbe{I-X|OtjcJ17`G2AEM=6MvhT^O0`q)wQ1XdCy%ZSyT@UABm`*a%P zDKCsAIN3*XQ)z@G)~A=*{P{Md^z&ETc|0bKV0LTeh%%S;Q1S;di7zgNF1eqi$KA@| zUf8{+^}?CYA~5}Fiu-4&;h0PLz?y9tef$k0ANXTm8C6_lFkEuv=@Q8_YahwRQhkY^ z?K=qZyUlglIetycBA9=*c_QUi->HdunamXRJ@l)b$MocA5vnDR#4#%eNXYvFuxbhH zOJTzS;^|4ugrmqqm`&asY~P?t@@*_69sRQ<(=;bZ++EZqDK6D8+x#Af8O38n1mpIn zK;(Fm#MAC(Fwg1fwEu{qbaPiA3fS`lbZ<+M{e2_kRn!p6sS?;;v=LYz4>k^c;#3e; z(KEnKf$hvIPX|fZD>F&Q_}9!{%Qvud1;b%3@SXOUV8#>*MXna<)Q#{A=8}t?;K*j0 z7OG4@i3wk!zDgRuHX06Z7N&yZw3A>UaexYCWn3vk&ecak@y3~Y`1he0=E{jO#wAhA zoL(`SDN`$h9&)WB`+!tFKhs_lOwG+_qPPdgsVz1J#Esu)%CSyli)lV7B%c`p2)~^ynpKXrg8bY_-3} zVJ!Gnppszpzcq<$gF~tHQW=cNJSArE$rgG}j9B2J`U%EOBQ_H?S%@N=@aU`ZpirHG zSn0`Naz4;_vH{0_GQm~n72xZyM08#55E^?<8KQ^W1J&pJ)3-gprhOwA%|lw^niy&7 zm}~~KZD0fw;Nr-f?m8eYBB4~DO(X*K_YT^tW6H&BG!k;r76Wx$`-r^0AKQ#;?+&@4K?+5AzIW&RR9b?TsyyG4H0B zt@J9%QRFJUMB~lCS?whnGUYuIT-CruQY4k?LIl1YY=oo!slwG^`_bH^hf(LVe`V6^} zWaMeQ?_@g2R`XE~d;YsoA(*|FDDmY)iRkpr4CYYNBjoS3o$)BQroCj!K@drTDS3M# z%IqxIcx(cz<%eMsQ5s<{?1z`k#wtO7VfNT#xN3|VzBAWBc6Jo=V09`b^P(hX;M|Z8Frn12vcKK zx!rRLzu1f>nB{gaL_3pR#oHfbF|URtL-t054n+=P*eTF|+K782@O$tJl&qS-GC&Hm zh5yO_6~Xme@_60nbg+&ejqT6r;#u<(!EtN|JTB>i3-S6K<|mIq1fzV^QWR@pFFti4 zo0)R>7F^yL4&UF5VQ!9j&xIdksz1TYia!wV)(*oDNpYp}@xzNiU5bd!tj&k!RkCA22_|;)dymgDa$@C#9LBo~Abe5;Sg)APoJoAo zRj&pRPY$EyJy4$9!R6T)YFluHG1UV^eWbJmoV;bR${AvNbZHX)+KupmwYlK>lwYCG z^E1tlVB8{ZduAp-5iLHJ%ly>Yh)OrAgHcrglhyei+#^Z&q3;W5U7|ZyTz!!T`u06RJR7Shun_I}!(b*L69?kEb;XGy`!Tj32z*8?VR`mB` z9&^^Dl~%7&gv3WviVXxWWc+JiZ0&gloB(Hk0qPWdw77*MLWt=@5}i40&72*vMQS2m~8HXXeU7(we>I zSjO-tu$B~a)4QQIrxQwz$unI}Da6-Fqta`q>9+OSIIrOcSXQgxG9tA3a*{c-H~SmS zj?MoZpw*^Gzr`*s0|a zZ&<+OcML{FbIQ@V%HOn-!E4xJV1n7WKxn1{mzi?sU^|?4u*FxP7_O32Oj_Dd$(n5+ zA0ARN;D%JXA-0dsxUWt4wn1pFweq_YAZ z0ISiJNU|PTbske)a@uqwXMnGU*y~CTV0U9l+}aruZG-#Jdh!a?-Wq~8PZMD8rg@UU zdOHp?nID_O1QYc)#`FH#iPRBCA>((f64>*Cpk%Q$t_^Mh!EP0shd zA!=wmk!;och$fcSqD^55v~X)2#I(PIqQDj~|4NjvNnuQR=np8a_y8|1F9d2qJ+l=J zmFygI8&33|gx1*}_(0k`Y+G+3c|PWL65~l<$XC+T-!f<4bUC zMJ}`0+#WV#X^$kH{sY{=cY-td%iDOgZi7-~W z6ppL=2sS(C1KFL>dJQ*ZY7;}ly^D}=asv!3oq$IOmf^?$hSSsL4M$`KNY(P2bRNO{ znEijqdh@89y72%1Zk{zKDUvA(MUpyaUz-Y8V$EUMo==X}1OwLa_DTF+X~U(f5==j?l*y|4Yg-tR5urjOKe@M3)}RK$TBD zg#Xdyy;P^tC7`Ej$YaWv83Xfc33|2r9PDuz1`C!uVYS-Lc>0>1=pe1nuL3o~L(3_DPvOqeE%0XB2t0A=O8nks7g{Q($73c68>sgLGkrt}6;cpJ{ZS*a2c=4M zdH)a03g!W-B&xe8x*Hj>)lhBHpRaOo%@^EgB6Q!NR!bAua5n)rTqyy~9bPbd;Ye&1 zxb%OwAl$ooER5z0!9+jGqin|bP)~`7T&uNDqSTYctVnu`Y&sO7O1G$v=Gd@s1z#unk=O-K7-Acz08!`pJ%%C zjUd_eF4P~r1KffA!BJz}L{faZZ@(rzpHIQl?HMHhO@m?DlMCa?=PfN} z5Y`Cqhws?DhC6ZOcFLp~5<)TB-t`o{X?+ShlLx^A8)DcPHXToC3WfESO~Moq9-3m5 zjA+e__tf22*uk6>QUcmdP)4jJL;qX|?&CW7HlOalA0YEC38Gx9g{MWn;@dN#U z4j9~LhOd8Z2ETJ<{Al(H56y^RI<|J&`;NThaFk7DAKsI)_pdVOSNm9)8Pf~htqsr; z@*3`q8-`bsaLqeac~GDC8#qaP_z_p!RbhsY1XyGHX9r+Z!B_bGP9Nu(zX#+0gqqEt zf&9A}Mld4jpX?jj!>P!c6!x^plpWmKgmzWU1)ax#c#N6b8yFKbf-j~pkMba$ZR1r# z3lqF?(bq9}k%0k@aPa~~uUrVUCH6W{4U@Ji@DJ^mA&(hLFkz~8;;|8)RLh%W_Cn1J znsg8mo%%eek7)yY(1?X{HADV{ z53p6$5{Kp(@Wm8=n}0lJP1Q>LY>EorJHHnCXU&%HvK?2m;d-Mk{CWZNoJ73N<^i<= zUk@ODce!hri!GMy0a-U{McD^bx~39Jl;rt`wniAuZ0@10$jHuX&Y{XSC$enoX*9{% z73t}HLpqn5p#Enk1b3FeWMyj{XG*r{q(JO&L>Bv#5BI~1%dw+s2TXU%WG&^Dq~#kE z*>hWGvSOPeFe?`f&ld`q#RSuJq$ArQrIbXtB(T%Yi=zB z@aNwc{MC#^f{_E)isia&tYRzWpX zBVarTMy*v@+&BI^_3Tmtt97)i|594+k|;VIqk;39n$ts}j?<_S1Hso{S&Zv@OHf-!X-B;Iqci<&Vu zfsIyM%N(Irql({=h;x8Rw(bKT;xphIqRFQ&eu%scqZ*WWolRzeAAX>&fm4l!NiE`* zODFu8ExkHOTYB3j1&rYdk7*Pzy9nl+-*)lS4+^yEt9aJOriL*a=ZDgcY(N$-ze3;u z5iafWgDM(`>=n zLzS=D1S*E$cx3}T!s`laRM5tzU8`dMWv^u?^`nWjY}{Ii`1>1O`>2Lpqlr6D^(8#K)c_|h z%AmvS*E9CH|1qvh2BT3I0>Hvh(AlI3m+_iV1Y>eQ zU1I-HL|2(7u;&-bOBy$BV4hEnVRU8|f{KeG){4$Uhx(hqi`}1*;e&GYsZsNPFk>@kj~ZT?*v`v9UcCm?pG${u5KQ`W0|-@2NSvK~>`| zY1PD!Nc`^F(NEy4t2%xv-3TKY6MpGz(dIF)31)=omAJFshpHc%#Ac>GMBYzo8TVop zmXnN}-%g6c{~kfvs&_ni~f)%V`)SLpDrMiM*0d}EQ$;ZQuNR2V ztlmN`RZL;^w{8LB=b30?!!)+&=1cxiXqH68%48|z3^PXU6pASp)kPrpavLstaUSL* z2jK#u6)1#q2xt`H;s#H+QLN98CPR2PjRd1sK1Xb6;7^UpOJSWRrh$0Yc{EO4gFQgf zNI4H;qj8Op)zJ)!$3KGV@lL3nY=WbkUjuV039KM{xya48) zrvZ;q&FO|g8_VGTxxp@V;v{I5 zNCpqzDiQapz=`lqhMUk_b?xCp*7;}QTrTx@l>ze8G&J7u?UsDY2A{K#nzXB%fFA=#A zKO3$ipHmG5t9^r2!+t=|lhOFejta1UN0Y$baQ1ty$8CM(Y}!7?w&?S>&~>+J?EV8dO8sPLQW z;7H_1Z1$`K6i^2H-z;Nkwr>NNi(SCe%m{BiuosssbChnKBvd(msPY(!U>0prq(UZn z(eYz5*|MKm$a7yRiqcxf1m`>kF7`mR?k{lm?SqCk09WPM?Mx&->vCYexw6#C+eP}~ zbO}to1t4EUF2Jt(;s;8rr22BBq}*ssRd~!af~mH(rB?fHr|+)HWS4XuL!BP+$ku)s zqk1$E+BJw9eEL5ag-9!DMkCnT)xfbEN+cZUK7=pPk;XlkFZG~4L&$4ln`di=8|(b= zq!n(`sa7UDW``n=nNKi!+g+(1-+lDvz)W^P@kBbWcQ(2j*CeTrxCqfdJ^_c}#7XXc zO>jT%E7-p-g#%=_bNg~PtG8s5^h$F%oKKq$F87AuNz^gCA=pCt<7Wf^ZsZksj61<7 z-djQ07$2c^?_{!T4#=bAX*=mD#%_{D<{q%=Y7}s0jnBvef9AkXQ2qS{O4mn106iWi zmV~oIKgvqKfBymQ`=^1+!l776>li*fJ)iY0@Z>SOUU_-3;9rR~VHzX%yAFGu@Myh8yq zO~5_33tVFQ;as2Jpc7dN+eweX_T!1@(Z>bof{Pr}xbi({DYc+h(tqP>dJ_9Ex6!3D zf&+|-Fq(Y?<3^vS`sw)73MQGXa^QD*q^v2k@Y7`!(Jn>bnP%jAsSB(}XyJb6+aTZh z6I51p@U}TG)@y_E3V-A#lMngt#HikP2wr4y5{FH{g+xBG{3;MFVEhT@d&zw&b*CSl ze=CD+T(^fw`EQQo30{n(7VnVxmvYoXEI>JHmMmf@=UVv@Ubz28`#!%xva(umd1L^J z(Q1R6eOgdL@}#oI_~RNT0xeIM;W2%}6bK=ho{bNw{tdh7(KZ=ui+UjKvGXxgH=9A& z{4X!(nHkvzj}vux4OD&X2e>NNjk;W0(ewyS&}cY@o;~Y?bt*l`kfg@gp7i@aHJg3P z{JXhKFbQUNsmNg)==O+5?8`mg?9QQq%*U)RDE5yo%n0j4S;4<~2bkXL|A=FMG068b zfPKCu{EjB+Xbe^%7sm2&nm|=(;)aI*Yn!7ZJhTXcd5kVmcRE(lOZz`!m&Ffun11Ix zWApemYP+%uYz8mji;#t-dicreJ`(2m9%e`E0NE%05Yu=J8=g?W%ZT^-+Ta#+W4jVA zAG{Zf2V3Ay{k51|1@_AFqlqRM$qqltH_?^WIFioRwY+9phHPOfXKO?EwkRn5FO07a z4s|ua1&%Tp%^`hJy$Rs?Ktg)g^5BirF1Tbd04F>*fKO=+&~E9CU)H+8sm=cUyFtQ) zP9>N{TV1G!fivlq&(qlOgLbId`z)iCJp#BBL4GQ^@S++)^BXbO-Xw=zlitIgj0*lF zJtOEb+OaPN+3)!W5pNZt%dG|mPV>gQu{xxF4&-Z{%>srYn2-M)sU=UH=|`QZ?B#iZ zs3CiRc+rVrU{>9OyK^hRle8u*Bhkm!z4CZf^?NYOA^U=3|3KPdhsJijKqeuraQ?t& zw1MnuHnncRQN=p=*(#x-Oj&q0F9_!86;0~jkg4=h$5gf~(uMu9;-e&NMjh_}e>{Va${p#KcqTVjmA1UX}mU0#siCk=b;Q(-=~ey|Eo-+lx+1_<9DngF_cl6cGwVG5KH%xO&{@$&wT^xttQ z?C|TA%-o%4va5qe0B2^R>P!SMq42Esi3^Cl;LOEH-b^G)e@(yolbYJPi8-dFeu=MDGI-50Z*28LzYS% z>9hF;BL|QuaiZuN>;8@?yn8@qp$G@5%*PqmP4Kk={jkF?CFpOR1fByN@j$&|Sh7ec zbj=k;(@ZdTW8}oU|IDRD*OS<94`!n?d8+7&k2;i+CDT2Zm@g2Yfh!uOyxX-;Cn*!H zB$?iUBCOyv8wXxe!L?DE`0Tp(sL&z}-j*QzZwYB`KAX!wv^~ASoc%{P!Ca6Ui&r@< zpe;?3*d-6{N^G1iO1=~lc`xZ(o9RldBuK-!%#R`X`93v#hkXwcJ6Y_OFN2d-J7a@q zGFUEqENWSHg6X(ej*O$$fbrP^h!`%MJ!kas82M;ob*wm4Y*@F5PK`-qUz{4plst7u z{s%))vQ-z1|I!Sc!)5K-q4?Tab-t%i(w~?v5X0@xsKr<&p5#N=hp-VJ-?Md%d)PPZ zd*-kAEeKwGnjcM>faymt*P8c=O*GFGqP%}h8sk0)`6ofvA!TkCVW&RRy1&-A+TZYDl> z><^q;YA&64d4aU--(>0YXPVM6yK`aG%X>U#lz=fKnDJI8#T#8|dV(Z@ofL0JMWXY} zVa1EcY$EX!AnkEFC$iv_KG6l7?Ep^Bqu{25^D1O;-}?DD_mvFRn>1P)xY<=&;pixR zc4C0^;jhHi69V6Pr|NbQ`G#mH$zB2J%{|M4#*i?4$F zi)zw4_y+E5y$W1=oYEE%uIsl5XS>ScZ6CFzAI49RvJ*y0|K!O?&D}miWBdbtG~)z} zEy2($Z-|Y`%xIBX0()P+L(=h6%(UE|hTMPshD{_zL4L0{DGNnIH+vK0&#i<05lVQ_ z>>lVjybxQL{R4}BPub^(J6PGnHLP#qO?KKz(vJFDC_ntq&l3~OgG0B(-xGD{mUr>2 z_QnWC_TDW<|D+*m8TAXo3VPxDf*~NkYCFvCTnZ6lW4_R}X>>PfBwK@vL&!H~L5etE zXE-xBY7CS6a~dr(=pFRA2&US)!qPdDV01z<#s2Mb^qk0e_D}pHX5u)O`6ksyrPoM% z+;kCc4zEYz?G_N=uK_{Vz9UX*#W|5LEG9<~T{UcIbAs-_LPL_j_M5oKL^Xg2!kL*2|0Rp9c78&YWBS3>g-?)ORs-UklRU|3Y_H~FEZS*6 z++Thnh455#v;7h3@79RK0pxb^STK(nro{hlHW19LYr`dbLibaN@$u~VJ-Li#n+3ad zyuO4}bUoW3kIyM|p)KBqyqsr-j3QsQ#&dhxy@l36OHD495=`~GQRBjG0 z{JKz=$v~L1UlkiAeuo9x`|(h*`u}d2`nu2a|L(O~0zYlH1!Iu%=uUUmzW-ZymPaXFk2) z`uhRC?Cguru6P2jrMOiufxY1KAJSNNfZdTV z!))rT;x$kQR>ea1nM}wkz6Qw-aeTigXPA+3c{#rGpb37ESdrQvCt;FkI+U+%L_^1O zA9CTdRv=)`5sbkJbIHeq%VOsZ3B>HtQsSlT&DO|e@|eO{HQa4p4W%K!Vbv=!#6Kwn zm!;~Mb5x%Ca5;Y5N;+Hzo`UVfKx1_8SEP4)u{i$nD;W1Jo_{z0g9#%TwY64~_y>$Q zL@AMN9B>6b7nKfrrwF^uh~11?gWYbbkqXBrOk{|t}) zPGh}DZ!9^r4_3A#*j3U1<9-PbZKp7rNP>Ci@lQNrU!i!y-bB_&{uNFTw} z=>zah=~rm`Aj4xSgwZ@97z?k6te6HX@#uBQta@iEDmu6T4)-%-Id>i|vzWX3e&W`{ zV>X5KK&`qqW@JCYm?abO#+NnV)+md2kblfXgYdX>L$GPbQ~1zNXkc~{KGLrU#=bx` z`_F~r+4*x**td?R>{9VckoTX+mRi&Rm-3snz6lDKi11XGKj8iHA8>hVoN;qyuM^JI z>;d+6H;kxP!UMvUaG^vWubUSP`&06THBH#rd>|MfwW#dcbrJTL^io;N<;9Y{q##^* z){r$DRl^%J1rz!El-aVlKI$)z;YzAAXO%;FrG!){Q^QZeQfXax<+`z|<4WKDD9Z zpPLp^dFRsDXoZW+oy*#wBcs5&U#x<{NDXqu+6i3B@0a#I-fL(Li4W&WLvJTB?6xs7 z(uKP}!7(Dl*kauPlaFiSGq?1liyp{GIZUYV(Ao&b%wAR;CVzoiGcuhW`X~ye5;@4_ zIh9N>5s!O)QsT2B?$s*c+XqFsYQkUOB3?Oh(lRS8sZY=ZX=YvoNb2%n(OwcNG++dd zIRMfHi-z%-cfx3T3FhFI<=Kn3=2CA{(pfz%8F0Hb1Qb5JXQsyILa=2AMCA4q&%*b@G>{U*ljs``B(m38I>>7Tk2xodMmdIb zdW~we4}IB4T^~st$3B#!87V|-^F5Xcwu=S}yFw@}>*XUUH~|dj&g0|q5jq?$fKW^PR3v>OcL@r1JtQ9lk|c9; z5mr3%na#Wu&QF00!q3x~U~u3#>eVbA`tsLDY|~>Y%FJ;?qfI=Sw*zc>^+WQsUcLf# zGp`qNxBmp=m~~)ktP0a81v>osT4rF)HJIKM0plkO!j>9Kv9*aTb9jgfU$e;-PHQ6w zX4b3K)QrXfw6=N%D|2=~s(bK}9_e~Y@;&G$U$Y55+yg`8)iH;eYS;*e=IDd6b2J+D zSOd*Hm?0Vd><*Y$T!Br!gK)~5C0O>zlkAae)cD`cGhxeNMKIQH1E|`8CbYU*23uTq z5RF}X-eH|@HoajC!`E!4{`d!Owd(l8(>_R_TMtWv+fdi!)98hhJgBu?NA4rS;GX{l z@HyEZNA)hnpMv7i;~^b9=6|*v_5{1*G}0qM zPa^WyF6?Za2uA5tIQ8(B4t<^&W_US-Fe`TXGAq{2L{^W!p{Tdtkw4LCa?O5)D~O2f z$~Wlh62W&W6Fq+<1M1=k#5xthxvZOT^G82C{OlsUB|Zv`_5I6Z?h3WexdfwE8b*Z< zQ=#Y2dc=ye6U5;M&okZT0ca7W2+Bph$dlL{a`m)7YO?rnaSbfB(*koz)Bm<$o$086 zgVXMSv#dI9+35PeI~{H`R>HekN-*ZJm#K8WztrHebXMK{2BmSyoS8S~Et)|)K;$}S zh_3q$e@1I!{gbk|m#&5!qqT73({hlxdISHNNMq-3?a;gRBCL9(g=Hx>JaF_995m(_ z<}lxc&zdK}{IEGo**i2)!5-;s`tC>6v1RL+9Wvk0_<}I-iMt9#>`%C+qQw_eaviI{ z+ba8-NmlTfslpW4LokD$XHwfza;X#VQrYZ&acI~x$83p~ zHE=G97migy{^_5**U+4U3fT2aC3xN>-o&IU;_~3J;>ikHXpq4jQ1Tc7Z*zy@s_sqr z)n4KhGj=rp(3}K}AHh6O%%QxkbEzTiDXiC%p=?W*0@LwA6$(ir>7Ak$Vh~&pj}DX6 z(s%`|GqeKkEGJz?q+P+{Jh9Ntybgx?de~vZ4PZyf;s3m6;hC34W3NwUJZ7a(?hYmx z@kLkac4{7_uq=hO{v6Csb*iJ45A>lsHN>57cMGvQuH}o6+-NSJBBi1eeZWN^jhQqN z-(MiYiXpamt3@gd9NY-i`L-k+x)LgO3Aeaj0_GCIlpo&dVCnyf@{LYr-Ok9dn$Af` zz0Cl0l6t^mbURcns)k?tbomTPpY}4|HixqXb=W%vuOmLU$9D|Hik9K9aX~wbik*zJ zM_0kAV*+NbFa>TBOx6n3?1InjRM)E{Hnh7=lB#WrE_JzrYg0FmIUprYiBWpInF)vS ziV|TC)9`}Ebpw_09Fq3eHZK%vx~pKAsU3b3PyW|b1h<3?0TV?qcQ!d@`|nhwe|;mD z#nKma?!hWl<2^yB*|ZXep84M(W++L#%ptN-f_eC!^bQimeSE+aoO?Ny9DSYTerIU!)(4s%U zwUw$AkaS-}x`+to>^wO>Z|#JE4bItI1Us%9!xxJ@v;)ltsntoCVAci`_LlGydV{bE zhzZ8@jBb|CA|ra|{seYnha%cGVcR`T~Igo#?gS9IMU^jAV<}jQ9hD-Ky ze`$?>Wi!MGU;;aGRscI?y%sy{st4np{u9z43-6{@m;$*3*YPVHtrdK$^Qc8t|Fe9EAruv`ox{5Q2PnQX8mBjQZ%LiIoGg< zvJ==J538Yl*lT_?O~TUomS9AW=h|B;jG!OQi)XhhuRu1Fn`r~nYdl7U?2WnhIBup* zSs;h+`xS!>rG)+a^}$$2Tm16kGuXa)h}1t0N!Qz$OFfEJrMnDjL4Og$V?qT?DZv~` z*_XND)Hph%B95&&ZY4=Q_mqw}{|RyNRKq((q&fK+WG+y|hZRY48T}N7kd(5lseNGV zNa58Jq)^v2RywkNmh@GtgVb{xaq4OP4NEFt@R;Yq5x0h5qywF^R_&ZfOBTklX`kB| zZKql2wdrS+jN5pOPV9X!dRYtZYHuK`HxjH(1an}+@;P|)lJ_85ZzA2SF-dAU+d`_7 zs4D&M(GTdW6)+ow(flNsIh0~{?R1I`Es15}>MN#Sg)fS~d=nio`psjy&m0A_k~GLo zyA3v%4goz+8C#J3!MIHxxU#VZO4_SfXRIVO?`&iJRWexF^`9YUY&Jid9s$!uFw>{R zW*`0JL?@kyW%p&?WVAF*(LcO~S9ED#6ycIlc6?}1>UvMGIynyJkOVod+#MtS506l5 zgT(lik}G!{nYn|3Nou%BSklI67=iTkxdy1k7rrf?aO&L)7GOWesfs$X5`Sb*8C=bLc{wShntcHZ$$pT*+dTENPiXCT6S%*tm4h_U zj_ZF6e;7jCurGBWtt)Y;SvDD6WqzZG6ZgUIkjQ{d#$Rlk$i3MG#jWL3tI}+qK^&fJJQN@REb--wkqgdl<6X=$8qZ9KU zqAXIknN!w^a(|?P#`rheXeZ&_*bvNz z(lg@hqc*hkLo6HnS%N+eJID0Y9%pnWSMpM;4StRwpSBT#eoTh9hKq%o4RIv(bKHS< zrsTo$-ZVTgZW*3D+Y*N*UBsPZ-@(=hHU8`QN%(mpf?0WDi#Sr&g5EzSjvYJlKJtCu z%Itn}iSbmb0Ou`oSanVq5S0KR_9B#Cy2saSp4@DJqQl;}xG@TX^7Zg-b2~^+3;~g4 z0yx#x!a|Z)AR>SI!tZ7V!8Fgd7b{5y(}wrrSjYI!OwpPwiB?k&Gjqom@RF6s_L*`$&DIAsba8TqF83wCVL;O(YF*H+`OLk~!>#$v4cP63;%n&1Ot z-EeH?H_)gSHc*3wcjHYk$(!$IFMTzPZhV@+UYETMZ`RyF3A~yRb^Z-_#6BNYZ!l5vLU;@9$W#h;8^a~PQu+1Wj5udFTuIKWTYYSXJiBRofq^h$XtVdIYJ_~D>6u(G6;pJ`78%o&1t z{?|2oXRx#aF zK4v_NzktbaC0s;o^tq4pwwfmJzS&F)`uaq;*8s&@oU;+e-$jL72!|gm5C92 zGcnct4WI1#WOdU1f?gYk2$i+eCrS31GM`yee{0yw!&2qRGL-<+=iC zIGZD0`6mgoE!Kd0>tAwjGaF}B8?j%;wlgB~w^^9b=>#L^neVW4syE$vIF%Jk8c{#p zOJX%|O@=Gpa|PmuOXd04>Y_!RFvzbByj~8#_xHBKqSemq?(5NPchFf_GG-CTnbyIk zEJu9oRVO>Pxs>HFvBJ+&N-&DXhE&Q8Z+cBwDr>9|gh;L*{bJlXN&bl%-dbOqgmJrA z^~3o(f5Crh2XHoRXxa}@Tla%KmpVY|r?d;yE{z9|mqZPo?u7s9O_bV_FisBBD=eM) z1oNMj6UBym(IvN2S$Fk0C@IM7XGyPCkLNM}gf;Cw!EBvlM|r2Lq7ObyWn+V^ zm?uuIjOx$_;; zYIr?-A|B_2q@fu@d5oU0v-v_Wk%p#}*0m+{j7O<#a?NRngIo47A=YWxW-lT@)h8R; z(-rW=W=))bz7L{ZIso0uh9cWw(7G-wo!2%|srYgaM-Ou0}+KVh3M$%HeP`E#B(b>~|}ya~uZqNpQo1XWM9trK*gE zZay>=`oWfat#Hf=<0FgSiofig$``tZ2olAA1asw;DK#O%kxn7%huCj+bgTPXW~ARD z#D#4s59vmd99f*ORp?u*C+4%9ZO;6icaZY&9(3W}1N8LJWAM1Q1&-EsgE46}G|+p7 z0{Va9Yc{t9!KGrHjA-VY+0=m&2RgEzctW0uL|-*EnRDiM(TrXBXvV~RbkBp>vj5b= z&q%xuGqwdxV>1!wsC-iX57HhPgT7WK64CfFNNW<|_nVyXj|M49f@&U0@vse5 z9Zf(Fr%EAV&O+F*O&(|Oo`!cH%SOYazVn!qdi=XFBA9cUho~NrCEf8anY}iAGyS?> z2(!9{>>_9M!VITk6h2RcIpb!|Ye?tKFX;MNjIitRopgeFzNDjjlx}vZD z1VeRA_}-~2Yy)SdV9$rY!F$_5xKJ#@13J+E!Pp2hZ7jiDJK#y3P12|91|_qHjJ`25 zKU`zzGq+Kj_J81H=>=ROCWlc#vc$EIm;%@Aho39`q3WUw@fK3Ydu}P?&#!{u-@|_p zH_;X^T`&j-1PWV@$%3xaj$qF2u%l|8s?((plh`{WHZjcKNsLP0Gh|Vl2(n%eKy^bW z90}0IqnZSaXL&lz1ToxS9s+(84IK%6&|7vAf_v&AKHnNwhi-%lM?d~U@J|@cRD!u% zHI|Z8%h2~o|Bc+62>Rjb6U_U2^1$uWT=Hdqow!4)INE9y@SH9 zzQ2Rr-^iJi`~?bAU@^h`>QSe{ZU0cEzY^HfVng=q&>hT*7dH`?!_G-YxFY2FH`@4D zp&V8m)Bu;Gx*)%&6P|dJo@gUEa%D6DCog&o3a7t9;RiG97;1vA5LF9@$rdmk1QUBK zIV;Vrlk&cmz^<0@XM-ER(ANe9APp@!tn<8$ms)Y6K5IqtpCpStSF_Q+DZ*Q_Rq$YP ze^6O(hii;8K}v#Cmpcu|*&9IgE3$EMJG_Y;#IW`e0_ikywWa%6_;F$HO+V&|p;ulRHfDw%aZ6 z2n*g1|05#bMKF1mZ?o@hl&8(_$FnsX$tim4MD!=C1C0umA+3s}1&f$5ol4in69*H0 z8Yy@0ZWZxWj-ax^`0itMJnX14P7Du&%7h+RPNG9rA0)Z$2ZR%WyRdW~CK!LU2iXli z>a?n9JUbvglJ+nkjFO+cL@I_dxG1cZ&%)#4-nn85hfz2#gS{vBLC(^_xYbM<%UsbW zDZgQmQbzXLt43il8Ew!Rp#rs7I1~mEOpNZ8Z2bTYdRuNBdph}yWKqpUD*x6}q|hhA z?xdcU71jh5V{~!(aRF0sOctBG72z9!Cio(;nyP%!ABSgNh9y70L-OdM_$jeM+Ml1! zPk{%*@8$x*Z1lO8eOz6eKI0w7s%G^{W+wDUYt97nn4(}Zqey}H;b=XqGLINGn*9KU z!*Y1?92wjhJQ(kJLcT?68u;)0Q!uZVI4qH-i`7HwAmex%k0}!{HwZ?4L3Xx-sxIB9 z634pE%@i*^P#_Lna{_5w%iyU;{=lZ}X865bA9HFuuDP76r>!Pc-TUVKu}5?l4AND= z?{)-1OhZ0o6H`?8_m$9GC{#JR1k8PcvFR+zo_1B2zVRxSeYDt`IlMBE9+{wl(vHXw zSNOlga;k+GE*S9jH16kVJzNnxILl%B)L`7QgBUxLvZ}#>b3nq^AgH|u<}H>$^X$F+ zXvPXtAdz4Os#=Jf`^8Ld>o)pz<{7$JUlt#j)C*?)+IS`8(M8HwG5i;= zvpIQJ9`|Gn!@r1o6&0?Bf7{*!*Gs41lwmpia3eM89y=cMR={Kt%<0j)#dDtO(^iqO zY&iRvc@$?Xx$hZFajO7VOerERNt_aLw+u1=@gOnphgI-1vfEj%HVD6IApX${)v$*B zRd|lKL0MWp3|9$*rbGuGvq-??5KP?r6XK>NdUSD8Ec^Ucq(t6)u|vv;eUjn3Qn+PY2mcd;ULtvnWCpeWng&p5d!?|n5 zJZ7A*biO8-q>5AGlh%6lz1OiU>hR0%YZ@%+c=1~@AV?lhwwJ@)Z4_tU?m%hamTw(U zAyvl(&z0~^5|6aRqY=WWPVl;N43g63!sX8loD2$txqc+hiu^SQi%ki^oEv;xd|{Xl zJ+3d7jd`bnMr?Q^ITLQnSl?8@+<~3DDfCS-!6x7P;Z>iz`23rmy~^0$@h_ywzJ@=u z-ow0Zcldj5E_5qCgUg36fCCXTahQujzh@P}&{`him(w-r>5g%1YS&S8Ea$jnMaWiW zN4_HVU8RWQ!bG^xd@$Ay)xxjebc63@O`I@F1uHM9hURgPfnJ^s+X^tq1tY-mpV3ZFc`KHLjXBLYe^tWmWlC88wG8GOm^TjB z!6Q8W@v;QxVikO%r4)vY%76>ob5PgNGpKE`4(y3=0O#@mP%|3BkETs%kLw_q>_kg( zCsw9CTH;u{+H`ux**eKU_4}l5ql~%uU2dP&o<0P-WpceZJrMJs4*uJdYt(S^ z(%*0`VE}KT7k2eGkh?`JbDNazR=+2%7TKhadW`hGAC_kAnI!cN93s`!4}||bb$QGc z0i#DSu{&JFKb${OCC&+K!0l6%Tg*ph%r#%;nW-w?uSXO@#MI=snHn#<_Kzw7&bvE% zxeE5HmcX{eNZ9UaFa3Fbw)7V3EFIZ0Mmk?55_HEO;W5Vr%piifIB$YDkxip698F+9 z1O+2wg(N1mS;X86CV7OTh-6eT4eCWd`O?tL^c46rPZ!_rQ^aFu6u^!(v7m8wlr(Gk zWNFiIYia09LuvCk2AYz?h0zE-?B)a`RW%Za{kcMU$0e{fUqtlpf6o}7z#+^sXJsA} zy)pz^W=p^Ge9I`|kl^W@C_0(E4$yuP-Fy?k6%dM>et%_%Nmm6Bef2;taNn17TPCR&Y8# z0eZG;<7L${ILwy>JdBXQgoxv8wr?n_YwpFi8tAZ*+h0TKKS2P~e<+Wk2*w%rWqTI6 zP@QcFYX4nzf?Nn+ z{V;o=ubxDHP=VOKJ%j!#{}v{A2sa*+hx3?e1mpeRXmQgiL&}0Uj+yA+W%@6<#JrMU zCK+{F4#yd&;q47?(Ch`Ir+|diHTO?JX`{7p>EM4*9ZS?hN4^k2W;sg!l#AACGAMIt zEpm2{!uDO!{6pI{lE=&^m{YoY#d%|s93lrKvP<3-GupFLnJ90GB+gKl$Go-5K`V;Y z;QN6Hl=v?NU5h79zGT&&pJ0UZTC2gke>JkvdyG=rpP(dzDx^U(U~%|9kNG}|$G8(r z(229+m7(h#8pbEG>LFJpr!DdrOD0U*MAou2;<; z;S7@?bC#~!OT-lcsu+i~pmPUJz@tctW^5+9O%i*+r7P5avB1BM|N8%xyOVPY!7x%# z-cK~=N3)G!egxkT+fd%w{sR-)`${h9*-Ir1^E`~Q7~Ty>=c;0>!)8Fa&H$%lh7j;| z5?{I9)UO^^ydRC7(&~6j#rt@zc17ELjjb-nkxOxKK z99RIUsfln-H5}YWwZg(uL(F||{sPbc*ZV=fFlOLLcA zTpVInq!c)H-GSCrVlkNqjzH4mi0FS^r!8)4`~$C69R;7dC+P4H4X8C;f>vMq0A)Ms z`6)13n9v~vV>;-PcxS~zvGMl=_RptyMsj!-qv(D{;#t)KT+8oNV%j*B`ODk4bKR@q z&1$@^(|!uV{gQ|->gp(<{|3XPlq9s@aUF8^`v{fqh0U$q2>zj6CYWFGcg1_ECW(KM z-;Ms(Q!p{r2&Jma(p)MDhvB+ceS*kdns{{mIVpqJcc}6~Xh-cVame;Ocwey&uhX-{ zRTHPfYbOksth8{rws7`T5-<@2bNg6s_BG8>Vzn8BX0HSKclwlz78))z%*HaU=encmMDh&RX9t-yWYW0Y-f71nzE)>yWfLN#j`y$uEAN7FPW56pEKl!&7#-;JuaP_Ap4WY5Ovme`qfV zW@1mZL%)S~RNRaNHoR>Bi)B?{%q0=3GO2~)X-b&OBbaC=!ny7BP`{frmrYT_!6ZfI zv6>6MS4uoP=IdeuVtzL3?pXXTV?5TVs(~q62J@piB4COLW`J$7Lrv~3N}`g$wpE;B z)Zf$~17#h=Nff!!aK7rk>t%3@ghWsh%$yzS*yvapB!$hw|G{VI9ioH{F@7gr5Z_DRK&Aq=E_J84HiM^og|vWaC&G?aJe#17H>M* z$Un63H{||?C?QvFoQ^|%v%tuSG|bp#Lb&P(ykYiuJUJwX$gYK~h+qNpjbJ*zsX4q^ z^ORbb7thl4Wl4ltBD(Xii8eb~3*3a3-Pa0f%jEIgxx{9IXa`Rp(!}46*MN+hJsvzO z2J*)#;=qLaaIkR*-urqC-s7JEc5{TQh_eEwnP6&-z@hhT4HXs<&o2CykA7S)M7^Jz zX>O)*iw#$^;qC~y-_7OXKhQ8-8|PQn!OodhIJ4^%xDWgS`_~0R-V+nty_T5HcxQrW zmY}(vC1AP)wyJG&6l-wnYUe3zD7-KxJ3A(p4mC zj}t1NCc7Ay6m=Zt-T_~J_wv^IKlR$6VxuPBXlx8dlfxh&SrN9l>*I?Z7Wm=yFc4Xk z^Oz6;V@NP|K8vWA^UdhzX7TLhS883N)HaQItWj(9KTj**0l)<6IjjuQDAJ|tZ;inPrP`{HW z;M&sac~SX?kcB0K%bT&I`A z5~6+bRl=O2>kEPcY{DqTgdN`EmZR4Eu@DHgBwmw8k z4~I!AHmOcsyhSQe$0Ja^Xg3TBE<%^zy@kl(^4RRcP`F@wg2$K$D>NpU2WP%JTpeOh zuP5(j=1wEVu<8yy)xlC?pV0#w$!w|(BJtrR`Z#Z*9NtaZueel_ts~@d38{d5nSC1h zhV6raOVg0Cx)|E7bi=Q!Di9)C%VQ1*AL*F{^Yd4hL-;6)9%LKO$|-e7Uj0s@@Y5ZV zViOTgTG1abC?*z@8~WoRDf0N7ZFT&<}Hsn7$6m_?oRU-g|L4Zr`Jf&sV$vx`#v~C0de@dpks} zjDknYTH(N2W%TKEI)AZ}F2o-A5KIG!3)y?df!4~2XJa3XqV1irgC)pfm{&yH^z0cinl=!W}UFq+T=?B=`ds+Zxc zi2NN9Vs;J@%-}0BRKY1by1X@>-Pr#=buzb4q7$aV^pJa-$HxcYz{Q%FE2eOzp*W%# zI@LE6Kb%Yw7Y&}Wss=LBd*0(<$;`9Jb^0wpj~igp0VAn*gr=0kC|UCl?Kr_Kd9Osd z&b6ZN8Il6=of)*MmJ_3B+%35?>mNBO>++Z@w#GR0ih$YJV#IrQ8*J_`4ZdS5J^#}I z=I)6{;iOT?Vo4n|Z*-J~7g_U|W#f6wIf5yC(Cgq(ZcbCv64={I+9a3qrZUUlDKZBJ z)WLpdMLe-WgMVnZ^HlLkV$Q_rZ1QbB!re?usoZ84X^Pny__V(t@gxq1N9{jh=l5CC zsb41Y7zY6pMli>_5*%FC4yGp_BU=uKNJe4)d4?+5z#N#L3qCRA3rZ{u#w<6&=MSsm z+uId!sre76Uzh-jkA_Ic{-LDjX6M6_wR>RKgfK{~B(X0uZKRr0jd@J_1b#G;1XKIu zoxS`j1KPYOf%VQ#WKv$)GC>Nfnek3HNYh>#?7pOoxem!?0VE75;o*Em{Hfvpqw3A$a(KhH|MorYQ7VN}Ayl^RnK>^Z%3287vXnjB z#~!k^*^@1@Bw5;&O3OVnMM#p0v>-~B$Wnwze&@`5zt8jhdcFMpcFxRw%{AwBoX24* zKG4Inl!%4uHaPj89efL4!<+v(&qs#gYJhehiw?-)Of8NzeDcF)rjdxDhl-eN#C&-- zCGRu}E`Q9t&O6e}xhZ8VTv<@eC|AYP z)(+XMb}bqL?m7ue-S5JwK?daFtS7SfeGiGho3|3?7GkbH3C`Q+Vn~lac%5Hxeu!+q zy9zoyq?LX3gk{3#JzQZt=0~z>HjGY)Jy6bm^a{hZdUm!kM(f zF_zg>AIXf${KoihxXw6!!LU?_gTPsBa4@z%$(eSOsjvJbVj5`?^9nJY0fX~?)b*zO zS6=6H3N5&r^^=*x%n-JysE!%CKT8z&3&*R%NnuQ%R@ij>F*8s%k@@`OJClTlOskI> zk!bJh(A!vnXhysK|4s@IQ6lC8VhY!v%iChpkKW&MogXlGH|KWNk@( z8Nr(6^kqG9VkMXP49}x9p|^+1|M^gVuhxrDy>Yt5@h6P38%iqPUPDv{QNX`2DNOh~ zVpO|n$oCE!LPw~i@s&Gn@LNViF>gEKS>ukmkWn}t46l8I5t}grvEwg>aDIUAdaEJc zC>XZxI!Jue88RY$FqvZc3_i|n1#@Q?Qi~^6M=(}g!2FPYH=T(2v|_g0J$WSEq?g9G z9{SE7DN18r=c>_$w{e!x`7#Jwb+cj&*MJW2@OuyD?#ZAuGy^UxJqMMH2q+J9B~yPj z!s-2u5I1)qvCTonWanh@ed8`+G_ETu7){brl3a}E^AP)KK@uAnyu z{(YA)hKQ+ty-6M?n@e+Ocs}&?2__hGZM4@F(6!yZim4=#hrhz`CFs?O<8i{cLIsY) z{l4=Hde|)`!#B?&i_Bcfnvw6o(inF;mSf3_DcVfjqzX>JjFr|j3&c!*d0u|Id<9M6 zOre@dSGij&D_`aEhW>!^H!az7Fkkr*gmi2n(8+4rOEE4)>wO0-yEB^f+uVnY@8d@r ze{}%Y@CV|1c#>Oa<8~OwwFOM56o+Vsn1w~BKY(1Fc&q?sNVQ8|M6mR|5h_)1BeOv%5d}qpv_N-24Pd$2^Fg@e8Q6 zQxY-xQWoAo#AMk7$+xjH=*2k0zIM9@Jn!7at^YWH>6z66?*Bc9IQ*OvBE{p*v_iwO zTIezvhs<#$?sz_%40`5Fl#NG`#8K!DTdPF^{e4JCl_p8h!=Ew!IZ0a%H^jWv^OeuO z;YW8KN#*OeMzPoH9l67O6d`@rSM=m~F3u4Mm@EYpCn3gs*AH0G-VXM+<`A>Efn@Oa zab&yIH_*NR1JpMFS@jp2{*+`l)m>`ajY3R+Yj629ovHK=BYb-%B=F~~_REKSy2HdY ze}T9mbsz}*n>2BXwcmFzba@7IQ+~q1g5R({VKup*%aAiS=8*52N@SQ~1+=%@5vwoN z5SJ#6lDJFFl!=H5{BcO06Fq@;j85UNbaUaR4=-U$|Ku}k-+TeLZx}^!un`P$v`J7@ z8wgVo4Qju^(EKlqnY)%KYYin?$LEmdmUh@PQ1(9ybEuaTof;wg0#7vff%(M zxx6rQ9G#()!oT0B#jURH$GS!+i5KnGxYr;!k!Pk#4|LFtS0MOx9wh%DxN{|WXyiha zVyBbd>pS50$#fWMrbU<|ar9$dIWI#;n zL9rUS^hK}&F<-Ylkhl7dr2W4q@nif4Fn?Rmupi6iOvO{2OqqkC*GK3j#Ql%d>d#wY z*iZcM*vt5mKX1B`;X%Vmrs@OGd6EPLR?4K!I}>uWHi(!95@rKp;3zMjIG@nYJCgXt z)*ehd*USzL#uvcpU!uvWaEdELhY11c!a!LK?g!?7S0=aijUazfSowIWJ$X7d1KO`A zLf^$G8yUjE^8S*@LRG?qAja&$MY+iYnjUAK#P4WKV}>YpvQdV68DTpp=mjdawL%!a zQ-t?TTadaf$rx0cLc-twdJK z<{16L2|ZIW%B7cSMw>WCa8+NEd?>RZcbAqxD9RQ7sqcXQjvj&%m51P- z77JvVgNXT`?%-L(6uK^xe_k|z4nCd8!_IoQpKUr^l>a`tXD<~}a~MbBaL{7TC^ND~ z6aAsFnG*X;ldR9uA~tB9YaEyl`+i`!(48O%3ETud&)$TuBcmbGPE*8;kS^L4#AG`y zl^3GydeDtTUc2%HmD$2UUMRn9w>8oI1{f>xsP(-uXy;-$Y6mEgdnu>0^HRG;-1`6 z*Ad*bej22$QI!b#viDs zJrrKr6^WStN%oT?=H}|j@~U=A`oh2@zK{Pvrp1Tmo}Sw-o~luxEuD7}^K5{% z{FP%@I$?hjzg#_vN!dJvQ!2m2-S4JDYTjy+L1yY?kfSwedZR}+-&ZD;1^R@o&?9bD z>0o_15d5qoKuP%{W351-v;PG!t&E1kQ|)3kmeNOI8DeZ^Jp6Qv%TNsJdM$s^vQr^-lA_TD7I9aO~4$Y|HaY#b7umYRn55;Y5u1NT zBzcDcnX}j*9^_j>m6Zc%#ZF<`y8=W6B|v!C1)wT*#cG~N-=3clQ$FCd8>s)F+UDRX zZqZNLHK`ZZ&-@nWkZwRmoYEsX+1h0At=@z^W+Jv9geaGsG*l5Snhpa>&EfY}Tj1u5 zW)|5Fhs&}!_?{dCLnr8om=%a|qeTVbhhAOTA zeR5w}hfJGcOCqB1Qz{2vz)mJ2MlWa_oY~P6QoXGpI*BlgUJVAlf#)FL)H%rhV<=)g zhlqP+N`=;_&7xks>3#_@61vj~sb%w;|k3Oj!tV7xpY)RUPuH=A< z1`#Img=+Q}jDePQ=AgLP61G*0V}9p2L*vg&pgHdnn$>BDn8U+Fj1FQ39vUm_KjslN zqA-3I#ZiFKItO2&B2J=@iZXwX&s_kV@t}bB+TYRCM4Ds@69iFSe$DK8XpW{ zI@O=ie>4(KxL$+R-BV$*M?VoGlRl$N5i>UHfULGhA(du#onJlCi0RZ<=K6RX;&!?l zkpaQ4D zg$-1$n^=uCVq&(G${L>JQtwc0S8q9m$-a1(9p>f7nP5DnfXO_kEn);yZJ`4tT(q?F zdgO<%IeZMafcMkXA-FJ<-u8AG?6~|0wAb?B+Yu;Y!lmyUN5uG2>Qt}CH>f=+*ZD)b z?#!9~r&;F?J@KLm7~z2ytD(Ay{j?Sn6S9-ksg65hN`6hAY)?Es6*7JFz~CdJ#O85 zz!j^>^pN%l=tR+&%iU@ictpaS8zExGA||tH2<75&nVL~_ogX+VmmRC$CO0oipksR& z5W(Tn1iKugbx{+DA$7K1Dnu{`ZtAW>t~5@CQw9{&aW2p>;xDb-xDQD8HgI;Xf=3G^ zOs%_!@j(oAv_IAT&?Tz(c|674yNDfm(^dXPwUH zqD9yFjJ^BVCCATGE8M3ts@SfZ`B#q&f2~G(%JCoki=JZ!+T?COo|V5 zic%{9A!Ob;0+%Y{adhDrQ#bPvO#M%hjQdm$eyUr=i)J!jtmY(QR!nq~eHee6 zD({-Y@9X=I?U7YP4_$td+4f8Woso2jFtJkpucs)r5{zaheAOqnkExSxBVM8?CI9apx9LUB48$nm^j2tiMZ+J(yfI0k($h>H+^LT`o5=?rk!Uz zf2$MW&}%RH*a>@q(Lrc1bG`!vC-O8eb>gS_7M2y9fVtM`P+6S799|It28wFr<+dVd zpSnh@##q86A;x-{wOjb(C)D!^$-K7PO15`u1Fb$Lnu%~yCuv=D$r==13Yg&(I#`|f z0|n3Y$)#@U_-;QAv-)PhU;T5;dXt0T(yT(R#NUO_ZzRFx4e8!wA!dhT*WsBH zUQiCLNxY+;4V#f)NiW*Fj|teJMlN9%)KXNW{_oC4P}>RB2pXuKcfP}=gp**?kqJLL zTD8UoRh%rpDU-|PhZQ>WvWCM z<%n~-E0Q~ky-1%HLlUPhVPbJurswv5u>b8Dcy!`6+&UP;jCa`sfqp8adB`p3IdH-M ziz!CTnBE_AO>M0iUjmh3Da_rT>%rxxB8hg(fDc<|h?rT@MSFsn_hu{dT$8?0>DEd7>FHkF(nlv~ zg-;etJ1S9CFYA!Z8w%pjQ>aE5UHmy+!n}^uCK1aMpzLoYc%`!I^zrE!VwRy9d(=Kg;%!i!*Lg%Q~R z?Jz%6!qh04k&z)cVR;>f4$s5$&n4Ypc~~>_G6)5&RC}=+nS|*;Or#x=XIiPzW4|Tx zJ}Gb5uP!Nc*rG7;G)lN=LN)j9^cEMJWxDMkyw-#VS{I|>RoC8x=Kjslqi-HF%UU0X zVk5tYatN3Q_YpB25=JduQK544Sb5TEO?te35Y;@@f zR1#k}`mszWGlBj)zbAKf3ksDHQxmH|+78%~BPGV9=jvag5>lup=r9`3dSjnP?L92* z*vF*JXk~1j6v)b7tKrwX0U~D8L~%_sN6e_WG4k33efs&vB>t||UD;zMg}(1Mo~y?t zQ@{u_g~C2fNQ`kd`UO`v;UqC)ex{j|p&?mtVQCZWr*|`ppVl$grYVqXb@Rbyxr>PD zlrX&!6Ek+K{I!QMy^c%bcU_+)@4x>h-OqYCC-epWcNMVlwIkEhOo$+Wnb|I3G9OrA z400yy$2m~g9mseYbIgJRIC*qu8aR{>6fvoj#A=)n6RbHwuJN%eZPO*0zkAD=4NT9a zBOFECXYItjfZ?{EuzrJyxOC2ZV?m~F&IYIKxA0}(B<7?~9HWWvn@@iy z!z?c+5fkJsVum4Rh>DL~;ZJw^pMNqRIYvirxUHB@ObFp-qH4@)}IZOM9F*`!C-(YuBu^RJPn7+i{gj95{=r!4h z$zQmW`8Qde^c+ipkJ4}v<0WCnBW9BMWck!*y=i;J6#i_(2YSMy7xY*rfU^mfsyT*- z#_J#U5x0ZF!HQ>sgt_EuMPl^Q;h1S1yd0fCw*`hUk*qdZsyiHv7mg4yR#U`kd=axT z%|kw`#({SAz+R`{GCEK7EB&I^c+SL2!U!+vh(Y$^*ILw@Hjrs|6{{(eS&^@Y)4=24 zGl+KkMlJ3V!Z_e&xMBEU$Tb=%Vj8E47=OeJ-6@m5{^&$^*_FbNG7O?CJO0x82l{d4 zI2Cc>Hm=Yp^gkVJFYck&PHKZS( zM-hR(B4!z4suvEDU;FJs|Cg4+&n=ovU+JUFbYqk_RU9P|9)W4~N@R4SJ#oM=O`n|a zFz14VS-#zxbaqRIE*Hu{%We-l{Ni$E=X+zK#t#I~y%WW1TBeJb{}40vgoC`d@o;+T zlN3I3oGG1uNrhQL%h|v9Iy0z2F~6QNnKjmd+_}`12*c$^K6Vw`cDlQ4$dyr7;7er) zW0HQ3UDUUN$v*1`I}-=NW^)O%Wu}PPj+oicddWF!hSvL-!uuMjP!=&C=_G|I>`oj^ z5-^qa%A|dp19`|{IPI)&5Nq2_#B91~L#6~@fnO)X_yL}Iyvl&}e0rZ3TzFuAxP42) zEb|jF;fM)&++W`3D$v=#Q+TcZIO=P5o3&4z$)@=zkgIJv#IWigc&hdx^Iw|~VNP1e zUKN^X(g~8evD>L9BVvfH)WZg3mKt$S3n~I5BSzU(^u8Kk{G4x7;`8 z1AIS0hQ67I>5wpmh}og_OE$!H0R3b&ngHn+F(qBz(D@36%v#?sIOL*1Hci%suiae0 z-Ub5#j{IZ<8v{XhJu4hYvC08BJ<(m(OnI`0!`0cH`!eW-l^>zeL=s%u&JpiTDPoLM z45^X(UFievDg68oW%Q8M4D+GTmY^`Zc{}g4|hV>Mfoz znBB;9pjO(k)?B=3|AT2jOk#0=s?2=?&9*1=p$%5d^5u`1nM6-aF0X&1LRO;|J-AsN ztbZM4{L9}lJAHI9`|cBr%nBebPp^Wq>u2V~&rC)KGxQeReZ$y2MY{t7OA)hTo>)yY zVg?+NQQ>8C>DUL!{2S|6Ov<`4#@M+(vv&APpr+I z+*){ZOOX@}bAlu@2D1NZ!t4(&q8L_~UOkt-nOv~D0@r#a5(kWM+4|~?h#P}0WX&l= z#8gTz0)-psb9?sy)rZ}SUuem^@|rHpS7lWg8y(09dD4P$bMd$RV7THK?7y}hV%m;? zca)ZBm|@WzLdef}D4N>=fq$H!%eh)83zb+m}NDZSRT5VQK}1#0hyLo}nB z%>TN1oi6WY3}ja$y+sGZ9bG%ojhu&Tb@(q2Cs#U4MXO^WhkeuGF!HNC3p5UgqbnA^WFu&XZ zxlS0YmG%On_7uRxRn;QKuHik5s5?qb-e9_KvI6uR@tHY(bsM?u9Ye}}3t{ft?jj~$ z+HzPSMy+fm6|Q-e-u^p@uTco+?731VyfaN^xc?!<>HPu0FynX6R?tesR8sZ@Trkig z>A~;7ec5sHU{C?%{HNh{kC=X4jVP~@YxIxn zN&KU!x0sFr3%GW*YQ|jmzGQeF^AogApo^Fmij~lD%rZ?=6!_0S7eStPdPB0iBQZOx zNJf7fON`~=q&T??nO`zj#AryHTW7>vif@qFOhjqU`XoMV-A3LoO~#$f*~JJNDB*0) z`STyhUEc;C$BIPEfn-f$rBshrU@;`aI0Js+C)P~t?gp#akih&6B)|SK6c>1jm_43i zH56jDO|OzYSGYj8I4ALcU-yME?TPe-uE*u>Z!ju!-5FpaWay%9pn-YDJ&dy8 zQ~P9c=h;Ex^y4?&dOBXjES6fTlM&My%}^$5&(q!kNqqBKhBxL$VE#S>Zuew}R^NRjADfW3vZjj|GfJ$+ z4>2>Sqg3OoSh{{m68~r24(R=FGu_~>$VIl4iat;dHt3;d@fSXfcm#sI;d*Ob;vW76 z&1dG2_U0U>o6sgU+6 zWir@Y38z%6;9Be(pwVJ-%fQc25avzPN8~d*>odS<#7>B5v?Xh*wvuI6vO&4hLcC}Z zlBjPJV%{%FqRt*ZPcP9+=Ism9xjk_YY2Ov&MAu%Et!gA97h?_#Rfyo6B*as_{%A;Y zpM8Vcx>;o2j6cjc>#LZMu?xn!>XWTrONe42I*znR%9LQ~m}nPb&XE5o1GNkEmj%gu zxsf? z{|H$+iM;m4^Un{@#hp!^bhfr1F`t?ZC{2S4^!EH@e))F`zAo=H6>b+II+3$WHN_*m zb0zAeb}23}Vc*4&Izjz#yuUB8>}CPyd@jS)Nzw4?NEs|IA4b|{sDR-CX-;~PbhdUJ zF%ciP$%69F)0wF5J~X718|KoHdntP>7nk}Tgt;}(aXLh=K$DnGZ3dysaiG{tlqFbn z^(0&I9pwIGA7Gq4#E)bl)oBn(@X29L;-s+x{!NrH=Mi&v;&ZoyKIdtd6)F6uv8J-% z)W>Ywob{X#6d<(i0`j{M%a52F$+SSsoxgDGS$A?su0k9?^e0KXFEFhx6JgW}A6TlF z1tx2p$kn8eOud&BUO!iQ1g;@Q``=s{JUmOM-b~>abQ&>J^K;mr2c~gCx`J>Zxp%Mu zx%p3*Y$$AlkzcV7ebZ9x3mje3oj4>Prgz4m%z8^dNSToi9-ACUa%wXp>wi|PW}Ng0 zWFTf7Q!KOp?+m>ZKRn)A?O@h^dC7i@a_7AM{s8Yrj1r$^BpS^uc-f9p5hc0>NOS8?TQfdF{lT%TOpdZoSw=bS`$Ip4~yg`SajhctNsy9 zY|XVObR}=_oNc5@Kl6SVjbqiXhCVRA!UA#%eMsJr?(KhL^3zoIGh!nEH0RtkU7u0k&n|&2t800JM3Cy{s3Fj{;3Pu#5cjh0hj1i zFXhaGo8GX=-x0c0J%MurpV9JnQb76;N!R%nF{+o9WqT?^==pfClJA|#FZDy{PtOso;4N#)4!=VE~bk*sPBF2q~nBRzT zSw1E&BycfZhlj;YlZ@DL9kJXU=aKXaRW}b7)W3x>-5r>o z)^C_S?~dVz`!Mi(cpg&rjbqd@6~za7n6!cFiI_8fVR^e!Wb~(rseGTwYTRANah!UP zu84V|Y)&38=tdOfCL(5jl%Dvc2?Ch<{-0r4bOe)nTm?MGUxNuA6nKm|2L1|O%>7|c z#cGng#A^B>=HSPoJdG8uw5v@j|I@~g>uc4ETY=k@ogFwff*6w%UCHY<9FW0k1k9Q( zwq)t7E~GyuEvPNYW#F7KoLI!do!>)1YxNmg9ToECTPw3vy%)@FF<|~o#PpWV2nb@VDlO#Pw?1_LY}9hd6DL*RY!suxtfRP zow%k6PnuB8j)%R7>M0%4eZ3layh0Z*k_$XOQVH(k7s4syU7*5WXND&#i1$WaYIl1f zrg@L8+`Za{{<|%OpSine_!oH(Zu>7+#%78tQOxT`Ua}~BK?j(E#hS#^36(1Edy)&= zw8_~C8f0sl3ApSWjI+A0z&mCu6dewQn_*v=`cf+qlO%1`ry?e)##$bJp*vlQO~_su ztLW*c`*2ncg59wS`RLn?q_r7gq`Lu$E!Q9}#a*!ZWh0(R2aMMspC1|nEfGyeXB1TvG zj9P-2raA+;ZeKmRygHemHD;qMb+Hkbb*4KboZkp*TH0R&A}Ar}Tv8{BO}fP7cMsAs zM}sW5sZHp!{a}RVL^wF*HzYTnfUvFy;9;{XOzJ|5n7a~Yt#EHVP2?{eHRpFt?S+ zchht5Zt{MZBOe5(_Ky=W6Q_y4n_$GSUo7OgMas0__GJFM;V^bsoFcbmaVITU8tvR_ zO4!Nz#K8o2H&Hl*ftH||Xf-K#rmWU7BtdoVke;v>=3<-T%91$n8L=Dw-FAV|>nDhq zQ0ap`6ft^x?d8u^{!-4flKGRZ8(Hr;f7mPK_h{jaKzQFAKxLN@Rk_{~hh#qDIcSU} zdH4ulacah7%!~0jKez_2tkWVbpD)Abw%t$~>II_*Op~gSI=6=rGwr;S{AfWdg+p-s zs@JZvVIhB5udHLVV4L%>9_3ZIPZLHL=iF5#_fKPs^|J*@vr#1l;f7?I{Y-E}CpgU& zI%LqlM0i*o21}pKg2@Gv;4)!`c+p}IbK2KYUU|KV(ne?4+N~q#=sVRc6>dulCO~<| zO^D}6Tv&$akn(w|#AKQdNtV8d@2-wdj%Swi96D=^2o-MVE}e&%*b2hvANI5ZrT?C2ft{^8xw1& z_@2pp^GO9}de3{TUG-ME(C)rE&V)p4)FrB6+Ttk5H%^;uo!edX8mhs4f$PZ8u&`__ zbjJwZ1pm8me(+Jqc)S@lSMC+>je^u2%tlPewNH7M?JFqve#!j$!msp+NB7z32Sy}6$*i2!YJ*sp27HYxvMP7a_{p_`coS=ZqXhu)6_|43c(&$}3U%Z@>5<4#!P zA?-T5NFAtKh?!D#KTp3;F=fRh^JS%X>2U^ytih)6|ASfiTZb6fY7@&C74mwWHn~%1 zPS)Tl$jaVo#PI>Z>-`jfxi0Z3DTM)7Pk_&`Nceg2kXX$b2~&cYd-qfFCNvgMmA=V5 zEk8n2BRTfcXpVjONP!F=f=^nJ4iU8K0_KIEHesX8#RhTbB2_}|1jxkch-cV+w<@cE z_?ssnIx-y88}^HsLlWjGVrD1DLPyw5gd3}RABW!1P&P__oU&E|h7JM|3Sptxmvsau9wVlfKqQN!5Hu%>Hf;d1l-t zD*sn9U$iBeHhy}Fjai__2|v$*)c=bSf;U%cOVzlzDiTeHc2Ljm4NQeT_@2@vW?9v6 zmaPO2ld`wg&M<&!lx90PZYI+Pz|49P>0aE8yBNP2>Cc5W( zO*>6J^Go4Xu4K|dA&b~vTY7MU8=SCo3Ya#Tw&*w}V1!4&K}nJHy5EeEJY6Awc_;G} zlNfJbs)c($;-IAOVMt54AXek(FRp2Zi21iDY?$fr;}o?og;(>5rM-KtWPPfP#8cd` zXbE!)1r>sb{0_QU2)`R)j^M=3cd#Zw6M~lhU~a8fCUvg05P#t^ly^G}%>&~_OxO7$ z#sV>~Fa=U=-Vy3f4yMPoM$lBtHumOFBkqW)5;^fw!U)3`fBUG37-1C<+~9_1yoQH+ zRbZV>Gjkeqr4);6VNzr~OjkPsw)3xwm`({}hnNz>JU7{r{gmQ++;WWHPNzHwV$+GP zc*1_wv8#B|g!~)fwI)=vreAjvBeu9-d}O9%yk_n+|AEb0tKs?RtI%<2KTPwGFxwZ3 z)eJ<;mkSEA#)o0l4m^!|_f$@7tSAM_FCM<;hJwO7$u_6oA`#<;n5@s&+*EdNp_sv`{M)rE zY$$KWE%{X?svjy_yNdErA!f&Wow`_!@FEcG4G*io1O!kR)T_lSWW zsbO&aMv{2ZA|=cy#OPnrbPKvPpSplDxIHe1=;ar4SZdKrR+z;V_GyAj^%EM)1yre% z0?fgS{ob7jp{PGD*1@Fa0w!vl8U$rx2=vf0Sn&KBY&^RcT*lrIF^eS3M8ve%{c$6! zW>72Fr1D++C@_hw&TN$Z4z{39i5$4pjf}piP4IS!et&` z7mCUh?N3rQx+ifS7w4ptH*1lcH4^4KCXXCEdxG)4_=1UQse_GcUclQ098j5|u;Y+~ znJQrxAZB09Ntt*49I81wm9P9{&OCTnPYqmdAbzl?$;`xy*5kD<5iImH`)ZNxKhgcAM%_}pXa|N>fkMt!W{~A==D+7v zARko+pDq@GXUHxH>6$NMel8X<8xXVcZn5m;v=!7lY(MmkiGm-m8uDqFd>Ms z_qa>9$^RQ;<4_F^3m!vt?;@zPoealL zN|@zSmM zLKsW=M;Ngv-5L=KfUbGL(Ma&h%c%_|^{dJF`Owr_Y?%c~%AJ0s>aA76A(pibT z8*ENu@m;gVPmiSKXpoB-i25MIicA@-Kt`3ffz5_z^i!J;Ou8xugOW=@ZGHvh-W&{N z^^)UQpOqpe9Wht>U6dViK1B`fk;+@_4Ut`5TuMJus-^G0RwONp&B-Y=oZGfvs^*BL z26^#Ms^;^7pD;MQPCnl&hk0&I>EV`d#4iE?ql>mI z!bhQSZY%d^+yK!(k62A0K$)ofZTV#*K` zGHZeC$EY-FLMCD+-C-wBsHe|Ze4*1$D~L~8IW1wtpQoC-*tr#|iHiCHwpquh-xpYB zVULSo7n=ZaCpgf48_XCRoe(k4Bup)0Tmx-om8Ch9>d_Rw= zb*Xl{%-*65)}`+iE+U%t@|i|^B3iJc&<&=+P)m`_jev-X>+h-p#BEytc8kQMcY zJsq6QEH&N_4Q^4;7XxfwFK?sLJf#nh(sklR`;3@~$;aIkA3vb>`Uruwb`=*|Vd zls=<43G)jv1&K@C8geQr>%l4f6NMUi?)QmqMyrkz0)DVB3LT;2WNASt3 z2k}J@&)cst&v?cTPHvdOY|h*To;^aL_YFBL-Tr_bZZApVKdl$5QOd#r=I#z|%~7wY zL)}vNF}a4U@|L%B_n>R^Z#<*%oP}1oi`0pb9=G(DDw#80S^V9&<5}BKKQslNcbPNU zcZ{K{*TKJ0J7Dp?YcMr_8>c>gvv_X?ZWJ*(hzWUYIs9==GgYII!dK5<#STrkXUc4j z(n181&==^BJx`%8AbfjT4o9yJTx^7xo$t9CBrA41w|W)Nq(9jTE8N4t;!`$EZrRPX zSV`5)-Xvm75yJ=7=e(+Dr#zdI`QJ{v+29&I#wP8I=msZzNek{gLSI0zq4v~7fxnU! z5hjb<&KiyWr>1FtByG4LyQ0xkdSsz<V=2qV(QDHClBni1T21cN5Q1jsA!2Lwjj5R1TVoTpwV!!O(pKiHkn=3M~F*)O@_ z0n%9M&aEQG6)|+mggoOZ#`KJgWIo91Cfo1fD(1c70D770M_4n{P*mFq`aXi8PzPgCH#@f->>feDdev4H^E#n(*%9%<%$Nrzw2&1c zjK>KIV!=G?;N{=o)C;3rUYp@u)K@sZ-;wZ-ue18EyTDb|&9LM&I`_^lg?U@e`Ngr) z&vVaqu^J!50MD;@({&s3Zf5H|e zG&yVPCZ6It=rx>ddRJ(Au?vO{I|xN>62izE@CeE-6lf?%rFyi$r#vdC1dFs}U>oKPv zyiDB(U;Z733tL`6_mr;uhyeJ!CTu^L*A%jTI7`!d=Pc#r`V@q*Qo%oM?TOgV+OPK;3LXsLj_JZVCz()4FW9ClKMmws!2K?H7-W_hyxZIfG&A{zu+_BI z++@DvrDm>9Pj9AT%4_Pws3I{pN(kPpn9(6h6q!HIKyZc?BE^;7`V$E3LN{}P5Sp9> z&vs_Q%m|D{sI%lJ-IG4p83_}I82c;TuJ!6y9^sWUV!y#nopl0JpwHf zCJ8Zn#+%6Rm~N-_#wGKzxpB8+&NlHJLB9i{cb#%V-5{Q@7%sdEnf=T{O&ybovSvFG@j(dl$q>T5Hfi z^V?FwDt(|r3Kl@ZwtN_891U(QIFD04lYjI-Q+T_#iL1a9#Ek6iE%y%wJPK z!36!-$3B1QM5CWD<_)!>E(7gY&U^x;+!An`QwGy+U`}C1IrOTTLZ&pz>5pp$qC_MW z=-f=0&{q!rWmbGtwe+ObN*ApTF?q}F<$+gr(erF^O`9FeczPLd{kK`u#Yb*JZOJ!L z2IqqZ!`lztho>>6ppEaW4Q|g{TCtN}+8s|k<{e;ko3^ml{rk$IPGrHd>K5=@@e16{nxLTq^=UW&>!71X zmd!2!!}{T5)MX#8igSdmH*UbU(C5&1!9BRE|BgMlwpzS5P7R;Xia|2i6dkI*p_c##a#=^(Ftzgo>5JuHNW_fTDLw*fH*rmS^*G0HVGylgoXm$j+srNs4dYtdugDwFPsngaGkAGD2d!ld zu*JFnexwz{{bfod$`UW2u`5}9+?~7ptChK)Q3%m?~WoV{zACt~6yj6PzP zR5#`R3kaZR;EBhVTUK1n3}3Fy(2z}Ebpx&)`v5||XVl17FyuQgVh&7KBts4q!mfHp zvghJ*cJ)9txHq^G;yz$d`hSODe47FRV#vC!%qo(Is+RmmY4nQ;d>LJ{M zAuG9Ko}cA$+Bd*&XcOe(!qPdW4z&777z{rlxBA?M`KnID&_T{Rt5-AICOm=0Q)Tda z_HwvkyOkYfa!JIfN|@e=N$tNUFJ*=gy`4_xKc%dtPOjd=ecv{j&3%;)t;+8q@@F-k z1U`q{*&Jw@J^(Eo#$0xy079L+lk)Y^?1I|M%%j3;c(S1ef)f{myF8sH_EI$;cZt`QL6m7i}ALzf4 z%^1rZM2&ch@Bb>u>RSUoF>(=ONPffG8Wz@`?1b1!gqzWLn;Lks3_Rw4 zhfO{KU}2fS_zZa`Jx zo`TQPDsWbjgHzH2IPUQaw7SY+T4NjNsRna5HifWr*Oh_ep5I`XGYu}^ea(1!mx!2L z2{RrsWpzhn4;1a_-RG0}=d0T3gVWA)DCS<$xbgdqc7b` z=J!V*V3ppU=hW_T?C;YVnBnmn)}niIWaDEn49dgzP6_%vpp^7SHq8I;Gkog$ke$`b zkscV*2Ck33L43R^X07N#U`mmQi3t@k{)p){dW!6ZvJRd4BAKta*_Df9W4TS?u_ET$ zy9V&`cnm+@my4LJ^$)=`sugPI-h`DkEs*^#n_9MD0v(Kzyhc&q;ApQ_W}9Ibh-7bx zn9?v2vkWohMVnhG(@8x;t@@LD9o&Z>F7II#bfKvhsl;gUXW3=Uul-%&@=U1-IWAnp{D+tkmyf!sR==T& zaI*Mye_Qz%>sW4k$vIY7)1q$GLzHJZI4&v`F~2XAf**VV_qYtWaIOKU$#t~i`vLTX zk-8*&L??7pDPYJ+Cy?`Z#A?<_)oe$MPjr&omnWrEQU4TlgBwii&x_(RA{Mibi!xzB zL_I9nSq3R3xbR~&hH8%>^z0{iYj6Yhs8z$xozZk=|1eg|O^;-ERVK6d<}=|-$DpLA zRKy&XstHF-*^{m^BmHbj4aXJiZxzx5wIjIM4SQL?*i7)5UJvdcA3@aR2O>t8Sc&v( zhP60e@^98d$o-W|PdNIOC3XfR4Apm=l!_U@KC@wDcA1E&ld6eA%<1asvOa1TssE;? z@Fua*^d*J$oV)!_K66QK$>Vi~dOLJyXKW3%y zlN$2ac*Rki)84Dp|6*b~O5k|YJ+Q0DgSFGkq4dXlxYj2Hd~m_o!T z%v5*VDzl@a=@g!E8jzbAV#Y1p7)Hnaksbl(`wzhF{askrDTiBj6%gn29@h3xhGA7D zpmQReIk|T(J79qoS&4nn8!L2~WykzsvE6O)qK%Xufl|a+_ZjJSeNz`|iyfM3JMX93 zFaKdf6OYm9{cpnBPxWZcCSi6hU`33F?R#*4oCL>KJ%HZ|iR8Z@EAF?WUSUPv!O^Djv0KZF%#cGb< zWubJ2RE>K;5~M~wfJT?O41Xz}4S#D+nkQi7`2R=PnTOTXc8@;|8iYzhl7u8AmC`wT z?{$PEnKG6sDMRMWnQ|H=Q<_WjTu!4joINFkghWYX$ec{c6!N?G-tY4~@B4m#*Z2EJ ze|25wbFKScd#!b^weEGF&?k;G%!m6w1e@kAU|JF8;iD8$!tZ)<5XwNkRxFqQ{7utS zmFjp5H>OQdB49Wt-F>XK7-=aYrHhvE596u+Z&Cp zv#|KcU6{Dpg}83CgkC<`K(Y@F0W8`42OoLV5qx(G82T8G`HCUP9%YCNQO;(N zO*y@~bPhdnZzJBirVKx4{^{;@v zNhOcrK2J`XWhoEg+G{b99`_UTe?3T&KI0c;Cp^b9witn*Wht)$j3A8$!u(N8m2X@U zCLXpSj~ySqg>EvqB(@2N;Wf>-=n7*g>Z4!{5-bxd;wKCp%ima@#jC!+>DnX z+J6OnjIQ#*E%)76qJ#>EF}{oL5@c!;^=^^4-4|`iil!g%%5Vu$p{oQJt%Ukb&{2NT z3=!tdybE%pjR|7uWb`&sXEL_!ejhx5Hpe;B*|h^DO`NX4&1YA^%n#+tLT`hE>@ANO z+tLmypLgMr(jxqYQ(uXe9(ridD3~~A^M;7&s^AxGyMQr8nArJ6@>@G(;%&BhY@f9& zG4r}j_>Qde80QGuZodNkm*}bE!`C45^#zc2)j?`rJCCvX@fobnr{Kmp$#}|FO-aI= zZ}9wi0&#TUMMC?zuxN~cu|yc^L#;f~{i67zCAzdUPl*b<7lT*MC=qjRO=BI>Drq$| z>()TAeib+=)IoFBJ06p%@CWkuoyHeVnM{m6s)34OpCPZ;Il^a70&(3|kS0#p8w_D& zkt*a@&Bx*e=!pA%!*cpYBZaqrTuN~vhjHy|=s<@IQBw`bovXlb(k-ybdCy};Fp3hb zMTWTO*f>H3J^bWY`Wki&y-VP0RuQ_d8Gh033m6B4d0sPuY#G-r{vgg{%W9nI3jr;- zvv&`gJKu;b(23yrW$;eE4)ujq@P5lp@NM|OWB9y4=3M;Rk1d2}x{Boey*KcF^BZE< zYz;zQB{+gCL80d&OxLCc0{qzv-5u^#9ryIh! z9y>(#vUJ8WTv6{}-a6*g^iJX{1AJt|*)&d?DvKNZp-|uPI(+^42|`Zi!OFQBlBWR% zutz0~7=7;tOx*DlUY|Av_#|ay!_M-HcIpJL(4GjhadtRqQN9Or-jc^=7jMApN1GCb z>HR70v}Se)#n1?&r*MqZs#Ned(V;wM55nYal9IC8C~Wa=bagQ! zojBN>jDOvtgZoS==J$q^#<%JgkFh^}1xndY9y26NQ^Fp;iFZ&r1SNh0duH5&#Jww_ zTG5-HGw?1i&DqmDMv5>4lt+>Mo8qw89eJ#`cmme0*oCiKCKY=;F5({(ZmzftnIUyN zrg=FUB2)1NHdA?UYLB<)G(6GiuGm5}tFUoJuz6|v)w|PwJ>dXAdR&H;0SN4-w(mHtO zqNl{$IS-&y_bzw_Z-*Ny!A!EYkQZ1P#!C~0Fp;Io zomIe}q&ZBk?_D0FbH565fB%3|*L-N4I#_Zia1rg5^PSLGMuCZ4HSGF&0*WJUG8&%3 ziQr!t24T`n`jgcgYq1AC^H{5vFud0N0p1Z2kB7a<{~Ob~qk+eC*jIsBdKVuw+;r+e7THW_nZQCn^XUi9t>x=oK&7HzsJvYWW5Nw3b`I!m@a?U{ z_cfW2?0f?*O-lsX`X|hDH9^zf37D4%!(OeeuxDN47 z8qN`T-?#^H$WFx-SMoU;1JqRTx=jL$K;apqqXh zl=r5=57h_E-a`V$S->b)pbC4xz4C)mYPj_=bQgDvI;Jc;iic)^c~EKMl6!Tw&%o3!3&*!1O^FBYzwD zvAACN1%!Fs^9k`DHG;o`K!D^0NZJ=&LlVdOK4;l<-&lJA~9SQ8aP;@P63 zuxeQmi014A-{i5ZMqeS^Pw1Eh7sM5A#_pRP|5gOSVDw>3=EONk~q}oy(rposv zc=!t#w~&7@Rr`uzYPzQ6!>U$hRJ|ENr5=SVr_V$C=zXv-YczXlsu0;&3m9XBQF!Wa z=WE>;N3%WI4onl9WZ#DEdftQPFq}=}f?G}+E>!2F;r52Z*uL&1InwtXGrn#Jk+?q) zy51MV@w^?dZMzxUVI?FXyQ6t&#v+X0^8~x06SQ!PR2gf2SWE64ABSPK!+4BKe*weo zjm`>|$8bqV--E^QFkVfvzNC&Z`k_GFDh!3EjpeYf+Xvvc0Xz1O5DVDH@)#R#(RRh! zO*pNEZz_)*HXp?b)+M&Qn#q9PUyeY$vs9**vUs-z?^Q$9^1ZpLIo=~fm#_go7%ruSr1 z3WRXb?F=uC6T(ymo5|myQ^2-cGPbxif-d>`n+jd%KzEFl@fj#ChQ6uQz^7Er51}~& znm_oQjTqCCsQ-#%(oBaD-+JW0V~bMA>M;*!BQ?gK>oAD)xTT%xh{VU+T3&Y20T$Up& zpr^!t_8>-mnGx}B;bpjw@;V3K+5j2R!pyoQ$(D^uaW~gvInSacM)u&Zi0Sc8Qi33KDh0OJPV5yRVB(>eHf+Q&#*OjD6qc3 zz|iUaAnkoU^SrO1(3g^U%zlK4xLhbdXVC*!{3THRT<2=w-n!uj|OxN zo&n>4YN%ROjFOTRxXgJA_6`|vEutIdl-#DD9~^<#M8AO7F}0ATlt;`bHZTEl;q$yM zVA2sLgB(oG$hn7UeUP#JYn7>f-Tj%?dqtR8c{(VD-G#Wv6yz>P)u)L?;C2ITG5PaF4QBrm z4b`sqvO5=Jz-;N&12_Jb25l4XfD@|biq=vW((4kBaCl^0ZBTsSf58S*8Rv!%tikXEn?!ZVwW@& z#ngkwLOEn^s)UZ*e3Yprp)LLeI890h&0im&+anQ+(S3tSKmG=-Aur*VY6x-PXB0hP zlaN&}5inHp9niuKcN?W*3z4=52d}X|A0Ab9)jM7;lzg{8FX-!U(S@f@4Yz%8V%+f_ZeNfJUD>aQjjQFZF3~E0Ce?Z8>ylwSsg<0+hx+hZd$=d?81X z%0KxBK7_o2X&a1*$ioMzmz_ecGef{MBFwd-9^{6AMC@fPn*A_TBEGNMn+aA#a{@zC zpmo|UFh;3W=@OEEO!$$798&$BfJiSMUI(|r+dB%(n^VAe)}ew||2tsaZA}M#*JA>` zgnI;ff(krAnDg&?lJ{0eVD1R>x@?^|VTA(YKKG3Z3xrTO^qDV zauoZ8Fn(pBSYw73qdY8))Q?IApLsVR4i!{>j1jTpJ=&~hxK77@A`tz_AOn7b&$*&EqaCdwX z9jcc=4YU%R^kD(hjWCzRm*s;Lw_xiUWh_3x1`o0Aq{V&CQW_hR!0hyOP~2Gz`kCj! z%_19oHG(T!KeWotTzIv5fBWFEFa(KF}w}F@rBw(4p=^zd*k3Mrm$eF~!Oy39bckMxmG!gYn60!D-|b0(g#d!M0;rE2G~K4YcgvC=j4i}2r+ zM_?>S8!m&+gB<8ul?QF;v4-~}i@{^m9U#V_#^he*5cCX<-<*A$2`+pOWuIH%=>?3L z&rD)gmk8-@Ou$SY;gE2t1_h_>%wPyR zM?xGvn~5vVWxVP-ApZCpNI;X!;ramP&!`%HZ_WvrB?vS0Ook|9z6Rz$CXc-~X9WKJ zkOA5GW+vq{Ard;sDyW&20VZd2pm{XLH&pHv5J4})NnCxxDFSuk6|t!`~qt% z-oa+qAiTZvGOa#bC`i5*FdhhFP**L|RZ_=>n&+`iUH0M&R^F7B)P!nF4u{nC3lI{P z2Fz|0O#O~WLGD>tVS5V_4+etGyGw9x{AA`q#$slE!gusU<$H)TtHmSdey444Ap~jJo_MJj?BXB-37m(vOLZ-76t&rzBu@A7&I zrsrWrTER~rpJYAr)8BWx=Dsb=QF`ld}u^nPT(xS5S* zj;3`1dWHi!9*T$$+q{@yr6zuFZVMPcgt^Qv5~)7Z!Rkllu{{nuP^E4h%13 zf*$JX>N+KbeY0M|jU|(rUWfc;>gE9rvI>Je$j{=9+QYLrsfVJhct7nTLTrnCb?326)W&$6MfuciGZ<04uO+~ z!!$=^@S4V9hNGdt^-Z3Pz2QCjmgNV?c>e|px3)3r1Y;Pf%5-ebf5#~>GfL;3~9J_@af!=y$+Vtia+=L#EJ9QrCHO)9B z5rPh6@zPXTphdflhS7bKf{Wu@`1A7wV>>Z|?wS1@v=pDi+uF@UK=ys6vRT-hWdepm zm_z4>m$#)%#XO(MSeF&LRDu3gLc}6zM<*OXj<8EB4}xE zwl(fHuL9u$rjFa2Uz+lc5sR>WHRvQA9!vE#x4@e&yu;!y9fy!$0mIoe?(^g@-mZ7R zr!)YLZ2SuSy>b`}*I(sRIvZi-xn?l9dWa}>)nezS38qsfV44vow0^E!wQwbtegS0% z3p=PD)DCjrPW7~E01xkbkQ5h8=w=wRiMfI_?*z|nGHysSy??Q2FAZQwN!5fnd zM&_~v+kdMbUR&OUrTtG3Q)Q#r1c}hmH9*FHH{TKF*~L=1PqZ&qRDx9CvMY5Xd^}!Q z-COJyeH=JxI80R1S>8f(m`Af3ph`Cgy|vy2+ka;5gHm zdkLK>L4q`jWDkX_Pio}n;{C9q^GF4J&QUueEpVH)Y7{3;m9z>ahm#=nwt(rmG98>s zP=?(By$w~-4O4>7F;OeOSL`vr3j?p+fg>hig!N++c5JqQnJ-AAi7*S#-p%r(DXMiqseH+*S|yLvKS> zOEjTiXTn}XCkZZqauYCm2y^;vy<9gk2y>uiY;ZstHEpp1K6S_%%6Kf=o1<0WaVCim zIXJf_RYsHFUN%7Eo*;0F>xL)|lKG(VQ5-w60s30i!Q@@BM9!rVY>0?ZBI;v#s-4lz*U)p7u+vjx3$x4vM8@+5*uOZ|2W>=1@o?n|P4 z%>Th~0Td?y6Hyg&`ZoHzi{1$gvbkr|TH6X`D3wj^Xx(lg44fFIZv0G8NBS$?c*>n5bI^ z&o9Rlo3w|qU)2Shwx^KC5C}7~xlpdDc?`2}kg>{HQq1VVMEO9abv!25unN@&{wJoV ze-Jz;yI@<-GN$kP2V{vy1JqM>a7Q(faIqi8{@N#m9JT_+5n*P$43l?#4Z-d=Ar;7O z#Xd&tll###|Hg2!04ELidH(y}T*kh^>c%`K-J}O?WZ3|LpOFz-o z#sy&}zu74Nt#AxuAIMna!&kA7#TUpY)6dJje;tD`Ici0ikj!I@&j^^BTw&4nVLxDg z+BxQBrVE{QxdARCgLCh7Jh9k%5PO^z_U4L!S%xrLk8pVc$^(pjC}R&Qm10>c`jjN% zl$hI_f5&j9laq!!cyN33`rbFV`-)-65kbuw=SI7h%?>IVxL;T}N=b7a{V%sZ%{!TXf5q`#cQJ0wiA#DnV;je##TiQ2jYUNirwe~ z2P_%mAmR3^iePL`B8<(w(Nx*%lh|nFJ$4S=wRg|IHv-wXw-Mu-6Z&T%Hu%!{ z1P;VH65cB|GD`}C0BVkaNky2MBPqFJ+CfY=SH^w}83=|Mne@p~?=fHM#NQY$bvDsK&kR7oJqY#`x!eiRYU_cxc&gQSu9a?t(Arzf~GAOFfxRhK;0E>@4FAX zmW1+Y8-oc|6-{P$a5&C~>P5n$dFbWxp*rV1^^s@fPHVf&80c}}6Mdm_5OX65HJYD& z2bufAi5=+G;J^ifzflqtx)fo)mh=Z$reCan!B1o>aw|_t3Ge4z3#wBAo6TG7TGqlaNi9V-0IxF0Xk^DgWtF3us^2<@w%5H z?p*i*6sFX|1}!h#HzO9d&GrnV%dR2s#sxSvZ$nF9ERThCQ4K^VCz^ZG3lKS>`D1a7=4xzg(HSR zoyTFKk6SXKx%oV$^=2CpI!TXsys849{5^tDy3+^q5{2HCk-yEnr3qi&ld$E3T+gFP=!n7xiOVQ>Q|a+C-T=*=zp)F3rNj#76rh!sB)g zl|5i9amq)B2u`iQS8NC;Y=&MH=NJo^SOIevVeT}kQt4}@;{FJukZ?r)@zHV7-1w3I zD~8jwjZR6#hI!Yi@b6oQH6L_{BT|If9!@;;D-oO63z#1Q<`Ke-2vwz2k!XeD)0j3a3Vb@McmmI$}4oLpwPb%rdOIORq;Y9o`o=l8kS%i7@_YUFE+0d zFbRS*`Uul*s7eL?J}jQB7t2;Isu#H*d23hsJLPYT){K9d&g=iF0&%H{MB0NpRLEX5 zp5>i3ae8GL?sGki*gh{zEQ%8_p9IVZgt<6Tm3qAUu-IM~?ag=ey$nwl?OB@tH|8%3 z{ohvLW@aMMZg`hEUbLBzHfR%~b)|UKgD~O}ep(!yC}3~_V~#N2SF2Kawo>so?O67g zLk_7hW4+zjo7%jE{>#{K7W%(2fr;_N^6)Nd$vSUhePM4R=z2c>xFD2}riI#Fke=i< zZG?cCgfJst^rRf`NyX-UW7*faQt_k}S)%0Jw!fv(vJn>TzcJ}Y;)%?OUn!;S-o)du z-bCMP`S||AP{KLtq}|j*|H23=V2?11(t1)??4;s(nz8K19XjL_HB4k`Yy3al+J9pn zi4zH}c}>*1b(@LZ?%Kp7&r;m@Y#33QBo!W@+2EP%H zkRKvFn}_~SxAt!;FbSE?=>3Vr?~V7Uee*XHQ-ZaLE&EFG%*$a!;+x&#k%t6~nPAfv zA%}qS1x&qw@kW^SQ&lOg*-~** zcMKb_NI|sDELR>d+4es$e>v&k#(zSNPohNP;iFm?GKI=y#4=1KGqSfD-`o`|0k$_)!Z(;mI&ZKeVPe=UN- zL63-ORu+=^U3QSSaJHmzWIX(u>jI8qvBYNf9VmUhfX6)B!efFF#&h&#yL0jiQNx=U zHq1;6b8SWNq}`IZ8aoCq1*`?58$&=}@i17QUIkd@7|_V^gMep)U~ZJT!SKGMhYc-)VXalj|oE?y7=$dXokD#Dx zyXq;JI&de5$OIS*KHw4l4I-_V!o78cu(k3qk-BO&@ij#RqeEZdJrnov#^%FD9+QbM z%a3g&ho7I0^^S;PR~FBJRYU5DE9l7;C*`AH#-OwiN}sxH&*k&bJ^O{g=GB>yTNnr@ z`o@Bt^b}$9_%LyE$a3PyH#MS{c?2}d-{Ga6Av`8hz!W0P+U?WHN!I?@x&txndhM-5 zlI31}_o@465Ksgv;%9-AMmWev7DDy;6sYPK34OHkzc&&F{XtV`e-TA!Kg{JZr5ku@$C8H$$yj$Hc$_6K&0PU=6JgZ<1j@zbp;+Yz zv}k9~;EvjLSo?t!xW?f^)R=S*T8lEEXA$as%0T_mlV#vL0kw^oq=8ePp44&ulf=y7 z$@rI^wfGLxXySH98L^-|jL0@y&tpslOcTOvJvv%G$Ug!Tbw{(4*i?FCwi89&ZpJ&- zmw?78aT7Pyk>TClUATw5HxVh9pd=)^ zz-&{`FIuLc0<8#RwE1_%`X>>X{82Rf{2ha9ty@W7nkeUQ6KP1xAlK?FteJ2T?0=jC z6Qgse%8t5K@1Sn4K1(R&h59sxH_LAvA4iR!<4N39+DTMqoWjXhw|UGsL7H}id7^41 z@+*qKR$Yu{&2~J*KUO-53+u9Qvjr8X*|MB3eYYLG471UTvEI%lP`~98f1%9j{R3*i zvM~Hs@k~6)BSW+a3nxmZEFxz7=!x%Lcn;%KV60#Tz9P&Y_a?i(J5OLkGosmB2RG5q zsXOSC!)3V7hYE0cf_gYY@<7i8U5-JmR$PU>L*+79R>{!V+&o;gqCc^~CK;a28NL%;p*yUVpI+;!dFE7X>s$EE!$#*)9?}s$dA1Mc)h-_ds<$=>)bV1WQ8Q%1LM|6F31#!MHc#jT)l#TxIHoKKL?r{oy z+zogO{aa80Q-rAxF(aS4kH_jo(X8sesks0B9W;5)8E-?aBE}VG`6Q&dMk)BB265w} zTrfwi3BL9TuzuxRLdAIlgj_O)d8=YUfrtlu>OfQ~NU2H{>lb?#ZWvi1-yr5gWKkOho2sewam8u$mA@R(1+cY`5JT+e56dhY;it3fpTRXdx$cW^fy+-D*# zw>%5EcQeqS`8Xg>=EM6FiO^-12~vl%&~rsJWM9#QbfpvU`iU6s)SZPR2Q$E8?ssB* zUN+b^j^{DBuxJhlQ>dy#zJA^pbJmJxO{ZDY-G=3KRqK7s%r*y%_oqQfXEdL=Js2C$ zr&PP&p)Sbvk+5ygAei$$9+tjEGsn2RtUBbJfL zeri~F?`YO|n*#mb_&a5q6Dw}j$cAFQR8&8U0?U>h&|fbkh*OtmfeRi16N~#nSDys1 zzTyTyT;wo&VPyGOLEoduOxeI8>YVB8QU)9Dy#IIIU2*DIR+m`&2keF`W?-ydSR zeHKV(r$D_&BwzRBl8_#o(|GTxfjT4R1@wjDwb9_eelp1Y&I4td0vny`3CrF&;AJ?H z$6WB{zZ*}4NvzpIdKA1BpX?LOhKSGO(|2y9ry2L9i?sxdygLGFaFd4`@|C9nFB}i6Q1b=hng$~jo)XsRJ3HJooX4zP&to3kaHmfWY^Xc~qowVH_tUd* zFUOF_OjyTb_8^R#%zzvea#QSX9L>Jj*Bhs19;Ux!hO|fk^PkMZM9N6ZqO%{m5)k+#C*HMg0?p7agaPFt==Ej;m=DDp(zLlJp=a}t+QRkS|~ zK6fI(FR+16bv`plxLiUZTCAxyT!q7-_(I^rC#yLE*bOCSXbs#)lq5 zdIYfIjYp!{Co_z3=N3J@&y?YGm^VssGpLs{BnIr!EeOs+b1fsq-33tkClV(4YodNpl#>edqa3NUk$wS5+~{ z*F?cWQ*8*iG65{VjR5av4009iq5pj&aiDO7nP(OL8gL*P`we)MO!le~$0#OwSw-eSLBGl?PzbH4QR$I>DxT z5wsl_!Qv$%e$k2qX&xfXTBm;G!YQ5NPhsfu)Jw%~T=d6{mK9(jIjAdDJD~=U}_2g(`PBTdmF>>e8EYBfcc0pV@?evn;UeobiZi!(|lX3xh4bGGMI{U#)bB$PZCM46QQU-V911xeZHfZyqZ>H58^gLT2k13-5cD7&p>WF@I5Ef&mW58`rO6O5 zT?q4sQX;>&8)GJ0qgfBTIk@J4GTig}WSsLi8jl5OxPu2LO=Efr?3#>jN1&ct$pJ68 z!;XZSsgCf`zYpA+I|ZJc^aYg}2Jkv(CXZPnV3ds&6}BZb$aDIS$6Vc`+2R93u~oI@ zxPy)dUVJzc6#EsREsp_*cLFB&VKT(sE8`XVoAL&@R^1PNzL*O)n|eWXkp$9x{Gi3J zKU}d}z+)N&73hO7U#8uXdv%Gh`7@(gg-O#$&-JL_HSGw_-6PPLRshB5WOg!y$ct=xob7z-HrxEQDk zKzBRXY%niP1P#1`$4LD>VEWCw#HO`kC-MLQ1zc`71YIDGIjna5&e5;~)3>VxgzE1$XEftV@CK4!}EnqRM zg%}b&6<#n!#EM}$a5`lp^gVT!sCKsD7cD}-*dUBX<^Ymv^TwP}WYc*%S^nK85r0;r zhD(>E@(Rs40$v&mq-i4sOo(kHY%BO|zk|V_yhntNbLKHE z!lFqKMk!B+>@{*1Hljx~>sTUb+y zX>tNqYCj^})EDuX-yZzlEI^n;V2{tB7?T-NQk3INKMQDv+6i#LlZ>w>%-BV z+Yn${hk)nhJ>auZ5fYxD=aBT#TLkFc;!tM+^H#vDLzuJQXOUxX1Y+&oQS9(>1L^F9 z&zS$645|ioa_Jm7%VW697hJEpVMH9%+Y6Ze;YUGJ(Foj(wtyP(lL+cR1}w(=!^x#D zh>iCb{<}0j2-ADFGuiSj5Q|rdX4kY*;;-#8aas)k2$l&L&e%xR{u85~;s-YU zw7_8UO6XzHNx10^gR;JR;E&`nv2K-MI?LSoMca=s$|X)@=i5Lm7RAt+<*Tt}$}QBR za3z|Prps8sh)6jf3vkl-)Rpmz=Iy^9XtFmbTe`!l@hT8Yy;I9pNX;Rf;8nTcxgfr#xLKNtkw>|#3+V-IXD)zTJ;l0B&*V` zs9}tYY&aF*j=0|GDB?sa&~vJQSvh(I?7;Qm$d(1rk)#HFrjGy%#tX)nd>||)Oy;HW zUddzP5a!%=JF>A$ioF~c%_jQ}qUwK*pqz&Fq`Od4QrnVT)Xp0TT_-E}djzRQXTZDf zzoe0FhRG!sVE57$a$|-;WSu=MWH!P*)!uNjQ1CYc1WY=@Y`2|EI(|Hi8QDg&TD={p zvNlC@*)NCUF2+=u=7O7R6H1>dmfyz8EG*KMs2f$J&Rpn zK-&b^heD7I@pEAD^Re(cLcqKeFjWXs(#M9(uGx+4a)@T_A8Uv^V#BF&aTv*6!QwF7 zi6F7NjE|w6OcT%nUcgX`9bvMAC7A!72J!`y;KqsRuyw^u828x<+-D1sjgNq-MHt^- z!^zVfTd`vZb3jQ`yv8M(3Vk{vzA8iXs z+LK}Ef{Ae2V-9S5IUNShoB*Off;6@QrV(M%%Z8A#joz3qTC_i73dG7Y_2{WB&KT#` zYGTom38flVh|9oiPa2$jn*hxLC^@Nu&NGj#!0VkIT)T*YVG0ggugrx98UP!@ETLha za3Yv1XxbBm`Ez_I`Ebn|tO26gUvI22>tGA|iSiCi=W-e^4d>R@C<_>kf<&k`5-|Ig zjDv@-Y~XIMi7@Dk185GO2T#t}!0NYRSXFJot3aLbdA1?U=<`EJyxJXmg+h)sBX5Z> z>@}ntH`HQWEWqsz=cKt9nv=$`AF^|8=t>syp5$302r;#W?c*(=ByTdj-sd;0%|9%o7%^6Je723?@DAFTr+Opa801u>9owm(-%AuQC0ge=rW4(RicnX~0D` zsUhe1)7l56p-`ed3F-{TgSeW2)SmO8J!cG@I*P+ka{==&o7RmmTS~Oat!L(8s-vP= zHOK4ND#o1dv*ib7*_IAfp@K9btdzgzv!*Z!LQDiq^T^@w=QIJzqs-xutuv&2TM3x~ zqapsS6Oi4;yfl}Ey-^#Es<^6(WYy4_7(F@A1xn_dmCo_y=YF4&+`~x z-DLiJ!=;AQ3<*o6)@z%ScqNe0x>E=0Hq@=nhwI?6<_5A%~P?P zebL#|P7_;PG=nD1lyRro|6sU#Yuu%!Acth|4lU*v&8(j;Y+HlD&LLyaQ+tcRu5|^7 zEl0x?<>fF+O_0V?z!)G*sLB_4`%LtL0di~l4-Bz5J9T>7Ks7$N{YwS<>^KiPx@i!$ zCz;O2}y2 z6bpQ`DV0A`Jw-Jv()bTdv*;g;@#i95nx~$FAY~m6mW@VmDQ*Ew&h`Z7YolRFs4G~_ z63(9a%Xvp&fiRhgt#UU%Yb@bI6r22M2DQpHlzLQ}hq)F1vuO2d=i$9(8YJc>gZ>2p z<9coY1Y1pprnx4dwrVb{ALR-0OGZL@<`S6sZWu4kSV0;Q!q|^`A}{H%z+zuTv0>HL zo}QVjt`>PCqqKX?`DTcQ};~qUwgx0-naaxG+YermaGS}QDv}V+i3W9WD2yP zK*~O3ILdv_0soDHLf;kk#)Fdvdo0hGFd7^75G~rVU~x?IDKhkoBgtWS?};42e@nwT zf?c{pAj4ScgwdPZDt{4girGGjLN*P< z29{1BODIK(I}|o|3U2K$4ENn|i^h3R51WzD`sUc@U8b5?t^0HIj@ohAA3Mq7Lp|AYv z(f;C^ZE2LqK)`SZ4^E*uN5I)M?(^g#n-t~I;6B_Mz8BcQ&Nu=+l0FB16p4T`pA5r3 zTl3O{FXc5Y1Yyp5{FX~i#$ZwHQLOj3lhhGYe{B5EWQw=YD1hQHoE6|OoQ38}5jv>! z8ZQ|OV~34{gkuD3Qk(?$lxBiOK7f`x2KWxatvwPHIs##4^zN2hP9BRb?TBJKOd6?9 z*EQJiucs*PBwaHB^>d=EI%m_&^3p&Wh?*}~pew*AxLpu$1BGhl5VB$tTov0w(Z%VY zyU!kewpv1UPa))>1xzBs6rJlqe#sbzE&CS577xxOx3Pn;Y@>M;=ho`o1Po`Pxj4z^k}etOV};#B$EcpbkUHPfvDb6*$Szcc;xJqc&6SBb z43`(+yeEfA!X|<8?0zucVIrC`HUKOyj|Z29BFLb1;bV{x+4K}J6vC_v9YhiVHW(;G zvtRZ|sg7|9xMa;oc~w9fbgU9i1RO?RBOMhc1&sa_bV;)eg95xCP+lUiiWmT8N5_I% zrv!#g(t<6Xf(l$0G_4w8^dA_Jp;N`!V}!}w?VZGed?Skcj9yGY(r{Vzzog;P z58cDg@udhqgV|`vsWu#y&4LBL27``1dQb9-3y@d)L)|q&1$GL1Q-?4n8Y9Ugr4nok z!cb@H#g`oZVBami@=+)Ed2)r7zc8(f6Zl1|Zw>={d>*VDGzcbMngW-W=|f$J4cMJp z0_Vr;Ky#%Kb#4^B!Y6$IeQG?$OpxY1!n_(aiaeFS2-Eu##S&#W#k`w_dj@)8-d-u-Ta*1arnMPe zmPN^wzc3kcG{>&O8cKVvft2#mXyoo3sCefKTS|=~&0!^v!3Al)Bg|$+GtxA8DdvS@ zff19VD3hb(@ja9GV%)R@t{~Zr!g5X;u14?|re=E>yms9U?{3(^of&JvJ?E-EbJ`B4Ka1YE*jT9GID|4MRpr;M=KQNaIGqfIc(f zkNS54LsD|FfUO{n5yFJjjvzgctjFHpj$-S5jIh)fpRm@C6_{I(>7wNY@yD7u z!Bq9_!^kDZqQB0HSgTjVgy$@C#0EX95Eq2xFm^5fVz|2}hv9qy-Ljd`XQDA&UFZuo zYeqxwN>{MBH4k);j{(ocH2e@xF_>VEHuYnc=*A+;Q=Hf7fd-9!CU#J9Lx)dO4Cf2{ zmgX}_v-*vx>kNj5+_A9J#t-t!48h^JJM8!n0l!L(V2&LPKU}037lKjh9?X1S5{u5U zBDN%Cw0L$vq1bfrX~Fi_+o5>dZvMjl8^a|haTv}|^B(38Q+$oUZ+-}jx;++-)lGqO zV`jm95{WwB<;?HR>p*_dd_YQ+!FoJ3MDT&xfK?%)@VyRaLP z<``VJ1l?SU;e6=6eS^VM#~2dF20_YUeW(?P~-8~D$Y!`M8f=M8tixnU3l9Rn;tH_;2;tRD+^ z6Ont;*FUB(5Ai$B_NSJRm}1RKvz}s-2*zT7 z0;6*$8r6|S^BSNiyko5*ky2dKzkXGl{^6W-daNC!m~?`1(~xDBj*dbzPKemq5tGpz`yjD)*#L%f2RUiB z2W;dWsB2G%#U}0`clYF8JYLQj2@THj&|EzlZVnsJFZwi?*F$X6_ltj5C;pTnHx1ie#j)0TR>12!_M- zno&&lUh+wj_8*6pN&lg<2YF26WpfBRghBd?Bb2Oh0hblQP!I?phn!({DaH6u%zlE& zmsVpsy+Y6$f=M;7mi+vyOI&H()|jqJ`aN7C55%W8lF?L0U{-b|G})3@kO+#&oM{1M zydrpoI=~Uf88F={6f{0q!jDJpFro+Zdm~G&z%hauc4j2A<7)t#by~!(Nl%yPRXjyu zuT}`MUC0yO#TtHZB8E~-?ba%2GCc?#Wg-}zYXPy&4iNOj6$Z)r!Q;4)LVMdO}VJr5q{7p>Q3JCAw)RRkgd`T5a~ur5ac_uRdqfBY;sH_Z|< zb~?eZc6!BCqL?;<3C-4J7CKHtEsTf_mVSkz6!jzT*0K7_?i5IUetgQtL$Q#u@wS<1SXBv;Ed0E(eOk=)T>=XFqV7#$^rZ zwj2N>VovY(9|MOX5qL5aq4wJpc(!mlI888w*%~&`u1~E%DE&O&6O1@|JX2idg}e@m zSjEB5#X}CLi0cfs5%=`XVPr;@gM|l`hRcEC7LCI=d^QC^oD=8^a~_aeMO{gUR7= zq+$~M?3w}wO8^r8@PMy%!Jv2B5X>BHNkTKlI8ux{!5mAT!tB=YMj6`(=B&H;?5b3x z(ddF?sz^$29F^ubhU+iDNyA~@lII8iT34vlngZ9yxRahl(_xgc2`qesppWYWe$nJ8 zMvq`_yb&;I2ffjl%_4T9Bu4CJEpk=sQ2-Ao{umxmpgw=;cF`34bdO6DBxi##vLc%$`? zH0q?YsP5B4;OqTgF#*F6cu#kP9Y^ipEl~lLCDY(Vlo`xcnhb`I>E}6#N@GPZCw$x( zcB~)jEETaj3jLA89zUkikz!6+)xdvZxXhH|m;=B`qr2M*tQR?g@q7o^_Qe&}F7<_~ z3=^mwi(t|yx;Hr#V@ELiZn`tq)%?-BA`$!Db^sIRt%Url40&ldjP9XwP<=(E;V|-% z2Y|~}w+o#F%~@7(eya^MrrN?~B_}xC#|RFUn!tmVG&-0|F&+eyd3-A4XA^*2))Oo6 z+?8?CZb9ug)(DJtkk8YCVz@KWu7{M@07~G#2n|dJ}JxAUJ=DER=edFL= z&o~ebpvESVnofU$3Has0oVp%}POlTOZStE0vSEkNpc!KXDu0oCXTSd)GmE5=yncuv zcD4h&B8S10K6cRk&>N23vx0-|lc2zi#?xvjCX8UJ%$=B9uY*wKTC!+&6~$_u4+IB$ z7yW~AtEVb3O8sAHILs3A(*fmEpvTt%1k+sLOTVdLf6bcAXfuVy9u!kc{j@lO`C9A2 z_{E1Hra;8LEVLI$T^ZC^nRdC6ljhoO@~Tc6oN-YSXc-Nmc=wPoe!zEmD z7&~Vw&2J2+&|DYA2RmKiYNR!|zjuXJdu!--!5J0=*+E%=0Yu8u0C5?`Y#|u`iw?|! z)EHz(F#BKqU}i;&kyN3g4JS=;67i!KQw-Op?Y9bK6aOIii5tAM5x|8WM|e|a2^w{7 z@L9(JG)Cw{btUy|e$L?UH#OX%Ewp1oX3a(I1al~0B|2TPip+(4*udqdahRZe6w{kS z+ULYngW22zu$uS>UC)H@QGEh2J^&%P#&BXCkT$LY*zKkbl^=|6bv z5UA+UWZ2af6qEkV89L-Kd>HCPUd(Jj-rWV#0_-3-X)FZW&?NGsRGMaj`M6BTL}kxM za|ouUJq+mxb5YNk8h zt>AOjldq8sJe_hd8Q}`0Z-kH<>H?><5d5g{fVHMm!0g&YuwPH5@uJ6CJHgCRc4mI$ zEkI4HMQn;$3<~X*5^Mk1B#78fQW8?D$t;2`@LuZ>pLx$ETt-#a!nJATFyOWwT%LnK zvDg9RV=>&kDFeZ*X-NkJYtBy5-K#&ia@3*I{R z(!X=$ zX85tl8rXUPWVuWM^PRR(q3R0lWKN;=g9$LAhI%%E6eCYC1q%g?lW8h?xRiwLJZc3} zJtJ*Wj)bDt>w6*M$qthFxE0RMI0!W#w(`XnHtm0ayys?+B?t1YZIfYxixmjVt)Q== z9puiK0B^89beyMgfnO9elwhV_v1cwvr=qp#B+wNUy{i?|vOvs&^_P_vb< z!sAlnRo2(Qgc?#^l(iYgN*Tkr_XvLOF$ZCyHT0}<0fWAVpfuG0OwBcUckl&uIYx1q z+fI!2fK)VZk%*nV*+`(#STE==)eCskwTA^R zn`WVFB8tiG*b2p^B)>C!E9ify;cE(wx;I1dR|_Z;+QExBdteov;Xs@Z$&ofAGYzd^ zO9XxTUO+Ks1arOs7?hffS`tO9%EoZyS>DcMymv*tt@}V;jY`9%#BVp*3T9(=LGQl( zz+qbS>>#?`8w?*{I7H^(sV#~nqeV^NMWZvkTQHelG<|woLj=>UhnUVK$tZQ6h;5C1 zkIdu_i>v#`q32}M6;~CZBCG)4_hfVkX{70vzYCr(-Vb)f0QDU;8IqKJ;MYVunBd|M zHChp1y~P|Hq}^fkJL+`~rP4SN%*)$0Oh)noG%`lSs@0xh#3uwyf$Rb#6S^OIk8B6^ zMAF;tL@lg7zlCo-+2y<+Jc$ANHOvH}ulPY-JPCAp20+#62#^_0g2dPzCe+itIYBYr z1mmZQne*$C(eOwSJ9J#Q`1u@LbVp+_;yU zkZ(s}EIb|L0H@5S!Wyamur$URj>stUnBmmeWOIA-(}-DnBNA)0CH`SP@bj*o{>RdeV8h= zGsP4T%yNkq^SV0>SrbgcodTpi$wAy%uvAb!l2qX_o1zi5lnpn5y2>2(_$1oLy;oEC>kC^S$Cg` zI|qDd42< z=Rc`JpP`sag4w;(i0KImLzZN37VR?>tMpG6o8RBcwE7)@=gY~{5NXrKwK`6Y-on=u zMjRv(5or`uM?w*KS}hrE10C+suzy`7jQlYQ&UgfY#@|tnSroIEU}nuRWnQB&w2NRe z-kcTxTs<1SojjE}OeQULd2Q!Q7hjuD%!G&J3?dkAZ&pWZ!;+g`aQd@3EHjOU*A6jo z+kON@Ys>@}RcZx3Q6IXFV8XVIXFO)lLW%(-(6#ofxZk(G(1i$DaTgg3^c&OlV?S_} zUN*zX@P=i3Nfl8A>D8?ZZEb#_@oGG@>W4tlyl8k{H;M#ceBkp#>fBDG(lil_%ev7_ zhgt~IC*MuwhXVrf&KpctQC%Zfh{<8f%SiC?Z;YKY#WW>Uz&m?V1T)DGTozi8u2(^D z|Hd3hf1nNen`S`Aerg4#QE6HTrhMfnX1*u{T_G6%D>W!!#5J*$Pg(;v1xwzOWJCU0 zNe*2qjpyQh;O0T9j204%(-1gBf+Mlfin z3gg%qj0}Q^P21UuJZmK46Up-hT-7&My2$k){!fhA(>=gRvv2heJbH#D40@#jw^Nm+axLJ6=F|C_O z$^5U)aHER&2L#hvSpk}9eV~rS1|IopL%?wtIJb5h1p6z4q|6qUdk*ETfGfp3CYTRW zs*FouAUZmOyhbf}DK0yGezlR24i=pgkd@?*5C}{%jMD9b|U&AQUrI z{GxGHcw8$m4#QR9anjhnCOsiy{UGX!HQAB)2zQvqr9EE55N0M&(k>*3H_m;f6a{F13LB z#&f`ZZWKHvk6%BPf~ zb*loSZeIM@9hF9z zV6b=yDUuCDcU?v7sgnIjs$0doSPYvDb98lKu}L5lO{AWUE|o@&V3Y?cGGCbh6zo7^HnI!F_h0Qo8(+^vL8C}k z9g(JSTovCLmg@=WYeO;INQ#jf+AwOYJA~e}hO(nGp`tJxJ}BsdjHwSCnoJi>iDGmK zX6fRA%*&C1D8QCDP^Z%c8b8koY^N?o+{ir+^E{GbxTbR}7f{S|i*4X{XcSndlgw@t z3rN-qgv(V?@Uuq;EUx>)SydVxG^H40f-#aPFbBp4p%4Li^!k{C(r!OyJlobGwru-(w{3I+q zmky!=9A-)n!6@0mUS}(ie(Vo{YeS(SO$SCvdBaL&dRx2a&qq1j2y^}IZe|IB`0V+#k6kw1GpM?T>-HS=dO|SX)${{?;?Bjei9pVFoM<3 zxxk9mW7q=MR+h`GteoCJd&1u$V

    g#6|Mh)@va$xO%A8x zWyuxdSBcIz_532C-qw-A)TjA)`MPxy+kVS=%w>uRCYaZ%=a}gWO9WG#%2=r@J&kG} zoi_b9?dCC0-(1JPF@^4Dd1>wxQ)vw5F2wf_SBU#wcE;a@i-i+^stYGP%g4QUS4s{< zP-(tWOccSK)IP_Al3~J=UCP)i7ZaF(7{wd^VA9aP7*marcueC$Jbrk! zSn$Rf>q*jtc^MkQTMzPa+S*)+sbU5%%@c}ABADl`=NNaLGJ&sq8JqT~lW`d~Qy_Xa zT+A)ne@eq+K1X3r8V>V0I0bJwwp@I8fD3k>mL|*?qApy~Z#9lSl`Gk;yOhW5OD*7f zLZ%Z;)x~p+T4b5P#IuZzRPbrc3T&<4xI#+Isle{B|1R2pmu8}W3QovcE`BNFfGsV!Tt% z{IfTlG+luyxM%Bfaa=za92=G<9KX^~xHBvt-(+$nVWTO=oMP4y%;v6hj5w-H@O4@l ztL=4@k@DDLS$F0qzc(%pR2sF9U-5~k|B6Xim4X#}SBOtca={ZPr3#;~F%-TE&Bs0U zxsta!6!V^9HWJK~oK|MX^)kV`>1AwZm`p=k^FqOe&VxMW|0PXyLJA&Xmo0v+?t%lA z(}W!ghQcRt`S^Z!uB6+NV)~~QaC@_zU{3U&V-Bto369JtV^7TYunDVO-YC`2neqO% z^uO%Qe_yoi-3zdMSC;sKrVG9;lP0W~IZpV&FCSMt&y}3ErkKx*c+7r+$t-VW6efxU z!vo6LjBAsbu-y#}C;Ed8r)j^X;TG+`V~VAcaPG!=;uAw$u*$eJ;dO6Ap?7pX&c2Z= zIc7>R%~YCW1oJhom3gzZOfZ*7Qz#TMJufS4PE1x6NbS$WzxReSHvb*-`g0;y(wZk8 zHrNG=C#MOsW*Q2=&B@2cS92xu6DZ~>#hf4*-&L)Qj+RI;+rNyB5lH}<#5Mfo))+wYGK)kI4&d<89jirULV~CScKw@#297 zF1RN=RhY{d3VQ?daYdo#kCj7mCEq?! z%qfcbPB33BTNt}rC4x7IU|vmbs624NTJig0UK)c8x@a7xeg-u*g}Ky1|H?_gc_+q+ zcieZz+27KHH@_MQ?WX4AXrC35@@;g{c2P_}6B(&++jETG=@J20ma#p14+vI&Ue6dE z+4}!ow8FRqyu{E*YDN&6Z#Uxe|k`RGLE+Gl*bxI$D@V2E_u;iDhiC z^Wnyg{&Io~3ahC!_wM4XMm;QL`W*+1X~o{l(s*AWX{8aKR~&pIP3i>Gr~EV%HF|?!vjI_oav9;}j6z&lEz7v1)#HzY zhd|QxGAvFqf}!gafb>el{ktYW%lra7K~}}~Ok1h2ROu_!lznST7!)8eMryWy{ZwK* zGqrfkPTHVJk6^YaU206QT_wn|C}WE)RPa36BTc;{`{I_YACUXO6tcFoVcFd-@bZ@t zs7ZguejnVSKB*PIR!e~S5sKLIRTdmepN}8>lEYO-SHb5>woo&(g1>vF&|X6m2(p!&UP;6Q@%{euTUWzh_%zX)()H_^^XRs^HGX$rG=;Ag?!er4=>=?}Q? zEHYAkZ=_IrhBc(Pla_@gW5Gi?4t585LJKLmHpel5a&^H1t;T^P?_%}8nuN|4BP2pQ z9X#sfT(B$ez%?;D#N6Iorv20G2qsu9pD}G3g?4-_W#xYT#7oS-3ypnN2~A1XY08-h z=zn@LL~cuk`WHcvd*2q?dgGw|;v~qov4o`$Y9-Qt9>clrVQAg5RgA%W4`>nJ!&CiU z^ZnCgs5Bk~qj1TEc`xmX_O+L?E(NL*ncy8l8TO3Os(S|LeTfFsdOPrYnGSbMW`k{~ zJA6Np0;a(jRPx&Kr$MZ^XK4Xe*66@ttNJz#9IXnk?d}Le5)Sa5jSrQ^pJ3v0vza{; zEzsw>Qr6OLs$|l=V-lZ17lqxEW`W+>c+g(%2`X2zpt~~~-kSJ=M&G4;7sbj;_wYj7 zvBJqSHweew*eEm&-Y8r&(GZrj%iP96&%q&0HTaZIa;9}ruhCjS_$bz=99$@g-cl_KYK-ewv#-C2_#Hw;T zg*(V2etc^do@}^_#}rXa9Kn1!|D^Hb5-YTNaVh)BVo=h1xKi9CY!=nUMnR-bGNhgI z1K;nbC|Ofky{X1SZWSWY?s zm5wWAt?Khw+e~8|QLo0Z-`y7}q ztTvD3F>0AJKsK02^C=vfOUaGQF%347M|-%X55A+rLEcFRFLcj?5mblEOD-%5#pdtkf?i7`Jbe@h4teRII5CvR zRI4rlzss($yrM52vn~~%f4ie;(vKXx@>Lp4I~YYWx(;IRnMZjQ_=94$5KQPP$A+mh z=AqKG5;kSsct~6IsVU9W1GoK=0J#BC;GH@Xy1%4B^{OB!y$}rZx)(zX$ress+T0Y^ z5-)JHkCp6sWdxp~p)iRw&6+l-5=NYH;H9}lF*O8pRy|uVx5*o=axGzR5BMr^DCrg# zn)Sna9f|y+anguQ(m>B705rygf}c++k1<@UKoYz5;HWlodge@n2UW_jj+{4O?+B~* z%J7(VRG|+NO!!S5!M83GR64MPeQx`m?JAus8D^6~4uM2o8g6g4s4w89K{k;vbj(7~ z@S6&;S%2Y*S+?N2fx%AOE6Eho)7WRtNy+T;cUY95!E0Iq#WWJkura5YLH&%8;CeB; zbg_{2TJu71CU_!_>^Gmsv}ezNI$crXB7m4|@E$5VKMfV_lE z-GE=b8Ps%9S%il*{E~1A4HVN%FmZ=<#EQQrA<@BNw(83`e0CF(L@#U-)`^lKcX|}4 z)doTL*F-2BO-yH53{;yg;4$|yeh8KJX@X4n9C6sq)o@VG5R8Xz70TFILd&j2yb3I& z-QX?}OiR}xMzzKqm8>jgi(31GXxV$=G>twuWm5{2iisuYm7Y&`#30A zUw}g;D*9q*_gZZO_7m&=LiXAE)pbWr}%8Fi#`{8f`ABp=5$7 zJ5<`V|4V;K{XG!((F zl!0(c>JLf$43bzrLzy?7o)q($U|u+uG1E>CMY|%4*()R4n{GWQ6ed|&NH~n_p%`di z9tgo~0;I9z|FU^-XI~<3)6`F|$D>JWLsc?kh1pOHb)%I)nq4J1b!!O3n5gspI$u+a zlqq??aXZWS%d4X$ONv<+yIaD&n?9rXp0kqfwf__2piVK|-dwSl2(7LU1}(R+-l?ZW;4YMC78m^udT#q5svsd(KZOUe7ns}j8}sgS!WmN%WM3G29is=WIpfNd_+=IrCW+-M1)Vw<#bc zHeGL3lcUXv=H6r;^Y)lO)Gb>8-7&<|xiOnJo!oijzorK3_>6$0A|L!h5(KfEui}99 z$Fa(z%Q(=plE)mS7(_6-FY}m#T^eY?j1u-*bgr;LC?mZ1?W!dA(tJqS83!Cjao|Fz zvkHaW5#f+>G?jOtLN}z~(f1x&X0eTS3q8KNF$+%21 zQ#D4Ry(uMZVDTcH*Z#&P+pkdKu$@@txVcd2?++P$7D4ltP~I1)d$0)nDxF~R*GwGb zw;wCK*(;per3(|Te84Myj)lK=_2S;}KKyy(N?T8Q6U^SiWsQ$NY9qPa686=bLgc4r z%Y1TIk#Oft-PO5Js6QRrO42~~T-ZOSr(U}w^nJV=ZxwXlqXwC{=cXYj+-SmR_(;-t z?hGC~_!Yls`Vq+$40FmUWyaf)Uw2~@9`4b5|cAadd|QgY=0XU53E z;#)WHjt%?pq9hG)@4p5&E*J~bB119L@|DMYrI-YQQU4gnTy8c-D+)^3SyKixzB@$d zwxTBQKn;zEho^n1pQaHU2_I7fpzdTQTp+a_y+fp-@Xap#;Zg&>SfdPGuQuX^*(P9? z8i$WZO7nYjk$yL61ha3K592Xt5{k|!VHIwz6c%=3G`MrVFtUFPI2a{BOO+4k&0hu_ zrl->%ex_zYWu`s&T>py2-s!l(y%A!9jOeDRA)lT9$SGx{)@ z3FhcZ6j`*&PN8$>L*&%DLfCvU3jEe3fOfYxY;n#6^AnLUuVy-^3|bBaBkf_4u`DQD zU5ADK)wuG`3tZ;81?M`sL7WB|>L3}yOJhz|pnzb$?d{Lx54J)%o+WJ4H<6@j*LkG* z*B`=W_c>4}l?X|Ly`f7ki+65q@A-k<4vJaltpnpSOK{Vnc095}8XhXA;f+-o23?TH zAr1X`%!g<`${`{cw#1p)St>wc(-KzERE+wt^=GRj+dptVbjte#aB=m5*Vb7OnKuVg z^87%zPc|>jbLDZc%|8jR9d-)`ES7@2k*D#JBxM*@6CiB6sLW&hD5jENW__H)oKv+$ zkA{`7U-nLvOkJjlJM(r5PoN-hAPbP!#)+WgRIsyxjmMH^GPCM zN86BP7t|X8$C{1 z#$zP3?_eFlDDAw-$n;->R^KmX=gHYOy}0MnG^w>%So$dps^jPK3O#EA#c-Fx;^b_w zBE25kS17_nM$ifJMkhZ)7prPMg|mAHdn zX5GTeHnxg&%eD)1--hwVhEwSBP1(E^;4l%^*}OD+_GrT6DDwPypcbE8R*!EyS%t?% z_(90gYFu%gX4^fdm==PW^6g5a)e9fAvACFZ+r(h)6_HI&A8+y)?z^eH)4Dc}>&!>;ym04Ti|zB&?)<7{3c=@tC7~FvR*m)yHkPq2?ODXvq|FjbI9n4q!H! zg`kq9#jK^Wf<$|*xkPI1hQKDpB79``YrN_9 zCmhhW1P^VtfO7*j;mKMZJf@vu?hs7hOVNzJT?opbU(6aTCX%Gq3V#$15tjOe^HzZS zZuU;17*5kTOje9D%p~v5$G%Ij@#BZMahD==eqDq!G7R8y*G&B9_Zl9PO)-xNrfS?S zCj8<|R2NmuMx>idj@y=sD<=)(F`P}~Fix%HT1ytq$kD@(VO`F zFgY0iCKun9GK7$+_P8RXk;kY|%v*v{f3bz}OP+;x5KQr&JwiR%bjh@PXT_W}{~Z&i z=f~fqIm{SF6V87+ge6`bIPm&l=$yJ7KZ?+W2uUT5Xurr~gcQ?DFf!j3Fgh(ENHDjU zwJ$<=sQXDKF>j5yStH^fjLpX7yryv&mD^eT6*sZsHSXwFimhiH#F{_*!uM(kmWiDJ z-j{A;mrXBt%vp+&ok;p}WSTK+_fJQwQ;OLIo@>$Ln-0S7M@C9Mc2f+e0%lSFVmJ%U zN%OH?7OtLc!27mT;9oO;;61+>yqh#Pxe$I7Pq}e}$HY-9piD43RBRZLmoM@r_Z!DD zu|%yzN}?EFz{dq5lj3=Wwi`e()!x(jUC-0sDah% z8hp>KmdEV=yI&{4n0YK<2Fm&(XX4x*U3x$ge`|+icSDZEVIeuje$0cIyWSvEk;O0C z6*Yf2Wt+u+p7W3Qfgsx_IOxnN{LRn=6U<-YT*f-m6Q!OnW-o}mgq019pzqsq2^SjTTn^53 z{wIbD4RM%v<4)s?C$HhmD?m9%JC~C4%N{-hKt#7$6AVnO2fGv9OgxR4Q9|)tZ{o8*3{O5M8y{D z+^Gi2?w|3dn|pXn9#sKbf{|V^o++B^jJEa=3mv~r+;ro-I6*#Ek}@ymAJ3+HdM3YU z276|J$3+^pi_ScZ!w)^eGc*?C3wKCeq4+dzukQnn9XOE2XePtx`=UIUy_sYMR+=t6}3{oN&!&r*(3p|cXPQAu$B};MjFVaKpbt~47 z|Ay^FA8^CdZM-y{bkY0>#%W9hV}5H2vQaHz$GPf?rKW8WlZQ)5-NsmGn>-H;%%+hE zF%-jv?S2O#M|thXciW1ROO1yq+b`jbL**b*>Lc#^teVH%ry35-M(=y-m;^7Wa=d zoS()i^t|i;V)`!MitjkT!!yT*;saAB!W6Zecx9^$bnH=pgu>0dG=ES`GQlM4xH93B z1?btx61IFmnRvH#v)FsH7W&^X7n}omADWY9c;a?^`sG(VVCsR=egm+fu`WUs1skjV1HgEs4i)#~OF>;H2S#_rEcm z6 z7bOREa+%GZ3x%9Q=UOH30b&mGvE*M2cM$Z|mf%k7JGiwz8?W^-gGXvNa7Fev{Qi$V zFxX=Yzi7LtG_?e?u-cBf-ZlxP9WQ3u?&6W+7s&_jIV-?9PzO5C;MarN@Eh}0IBC2NY?*Zlw~beX zwt+qPW=|cD$)fFaPZ3PKw~(=#KN+nmDP~>oEeJ+Wvn~t94V%na=v@Cq{`B0xFO$DU z{kCb`P5SQ6OZai)di-ZxCf0P&htc!x@s?~|m~n-{5Bt(Mv>L@+AQ+DkAaMy-5t*0rt1oQ9*>0;qnts}W)+wk$uY#cZqgaoBG?1t(ReA`ZhXn&~lj(0jcMeq*?qUV~B`p>E{>h&=QX zC$6l-*{>C0kK!TRZ1V`$_q&EKxDDoS1nsn0<8y+Ey(ng`?$$(87mxsPNf>Avs^dEg zMhdyx8i$e6^yEi}aTv~Ya?eEEg}tY{3ybuMv2T!zpsBhL7aNZN>zZ`frg0k|3%$*& zz|6nch{V%g3qWT<-zJx?!Q#@KNYML~#A7&ju=zGH+lR-D15Z^pn{OE-whas1VuwdM7$ zrmIq?h5Ng{B2Jp_mP9!5)&n9$%OQh|&*3oKqMbNk2lp#=0I6NazoPHr1)GP#yeSDd zR{9fGAG86lUrD2bk+g+ge>0MnkUN1%y<~v)x)-y#k6y4+e=w4#9(Q_jDp3E>9^@qc&?T=5*KX>-u-(%kOhE?UH(QRInqr0BT8ns1YogMq5RA<2 z!D9QdlaRDcG5dJesHVVLFQM}QU7=oBD35uX@5b-V&^YMKVYG`?39pSf;}2ALGI2UM)_{=r7VZ11mV z==WLwU?R3rX*kb@yWeoq=#b`2r@PDXCg)~6siFt(s6B_xyN#e!;S~O}_A`%pK#h$) z!4&mPXATh0##pVG9si=Q?k86Et11i{ZQdLT4uSJ|h2}1W+};$tB#Fs;Y51YBpdK#^ zdL`VmYy`gAwhr$*;R@?7On{GH`@z%>I`+VgN@GeeQqxx)zdQ#c6S-nGdX{s;ma5M} zjaS)dcZWBadxY?sRuPl~^Au-6t}eVVg))dq?pwo@h7V_*AR3KeI#ir-k`TBoX4CB$l+r) zg{%u~uckNYXLV$-2D#US-#v!QPF}{%vz4)q@obP2cT3XihVzT2PZ!OBU^ZkmFxK^( zP}27zcHf@Au-`MIrsr@&k^;d{I$$o3Io6cJ2UEnWT>0<=XQ7>M9K$-bd&I5xWFV7N z7JXU&SonCCCamdIfU;#YW|K`Zo&+`ozyfW?O@ZFzQggA${?t& zm;;;IsP_cw>`5 zF#!bAXxzdKEsI9Xts=JKdtH-H%oU+S$PBT|qM7`8v%A29f0O2njX{PxALS@ebp%)2 zQ#eljwlJGLhgUG)u-C~%-224~-jbC#AQE=RpT@*->B4sYh(Yen7q(6=X<&6q3arz7_>Jxy&N_z3p2P+_F zKptN7_&UEgGpMG`Bbcmj4vng}qmWi@5&KhDTWD*rscEB%95%P35BVJC@s}JP^VG`? zg5C~kKTVr1S}MVqwHq-Fr(#h` zNfGNYc}7!0P5&km`Q)Fz9o8g3Rv~F7_cjN_YIJWn3>Ud=`D*|;jH}174MQPf>I8^t z+8}Odm4}?%7W`IH&r4H8#~x%6%#v6U6Z6;?eP2#AO)x+redDsQVT>7%;e3JL(tIa{ zFS&|Sd1*MzSqnY5e}r6_gjaB)yELdBiNup_Y~WE%0p5{Cvmc_UG^+{5L8_G5{?P~Z zBo?u{+gAzS_Q{r*X|xI>|7O|sc@8bOABa$Pj%Y~e=;j$k% zX*dk0X&lCa3 zKsxyQqs8_`tbDjM9@U&JtXy^zaR-5)WIq3ScKGG;7=wMDAY-+hyx};4T1g*hO}&OM zlNXM%mZ6ZhSQTO>&IS8qfKy(yV#S{>+HQgozZExHbb6qY$wjQ@%3)0}T&sk>R`Z2i zl%w=nGN1jxVYq`}e;*${X4Bs63~xxe)uCTsNrq}C{`^1>dRo8XmkJ~_PF_9K{TysHsx<%}- zW25vjpQ=ro&_*N7SWR#HxH(!@BjP`)HXC8frKfBDI#l!PV2@ zM$Rhucp{Pap}B*A%S`FK+YjdG_u^sq?_#~@+R#^X81y|D0aBz7<4DN}-lkrao!}Unj?Gs*_3v_Qf2xjW@^2VMI)@TR8$d|^WCa-!) zd%m2Qd&pmXJd1zGH`Y9n_#L2_B0Mlv_b`=idebRM_mnHo%(tK-z1eqrvpu3$)l4zMvh`$6U?Um zLzpAclabPxB35T=mgEU3*hzerC;s>@l~fUDL+;g3xFJ(O3ivYk2T3!nd@v^Y9Y@qj zf7`pZuxZp_2zloZ(~Jj!eA9IBdT$M*##67egJOCJ#?jq_Y16ktJBdQ$*m8;IGO=L) z;WbS6w8danlLOtE5up5|0P2!6`Rs>u_tkKrDj2R+jRc>m+90>`8GhpH0fj+daL~`` zkVd-pUVcs&?e8%=GLvMa>dhxG+q?zHa(odR>T*O_U_3{X7siN(%4NV_g%!~3HV1qS z*TFGY61{yLM~0)V0VJ9Q1IB2PE0z(A*B%I|KS_VCaAn9M=C$AC+3;|l9It66R2oHs zNwCyqWO}WTifIwMPU?)p` zzlBsGo&IaY5#yFakZ~UA?Gy(puL@z^{9HiMN#Jk34#b*~pkHhPCg;3CK}8ozm&Svf zv?1Ke%Z8ch(a?L8wwqc`G1>%k&tn9WwbL905}UU7rL}m_$@WI?k!6Cz`PrmJTRv2G z$3yCYV(6W-68w4>z;lyAn1`bwz1RreeOCp;#d09r9u7wb4}yS)aqwdObdY?dRd~zk zh24l?#-%)M^cZG_787Y!)z%8#5mv@MV2U5EAYClhLhknzaElRvYU6777`+5~eM+GqI}tD<#j#KHq2}f=aG4wj zPb&Mt%;WPxfz0qYSV-S*?CGMB=A=@F*DRU+ZzrL@$fCVI^iixhz8_=oY$}pzUq$Mk z*Mqrc8gzwkgbJ0lpck46$!Q`;nY#cw+krIG^oE^zqe0Qy^{eEjpg8$yqwOhz2w<3s$%7Nkw!W31;Z-VCKVFb9C0Yi2bsvR8sI$rKu=LS{S!_ zE$Dh}fNI;Nu+p29U+I;Bkg0vBAer?jc32g6nZ?b6Epp<{{dCqzKZtlJa=<6;K|rgD)ua?^+GY4@uqh`fNzLzZ?R? z{Q#Yv0@AnEK#Hj?6eVtgcB4F!q%@t!+@hFtg1Kwz!PK}*A>F=3?EXg{Lgl5>!bq=| zLV3$lcz?PAiU*L{kgs;~#pTzCp*ePS2b>zZ62d*!!`bO&&`>@X{4V5?LgpM;DbIlP zv|_N@Lp&n#H;!U*38ppZV54S~E>ieZ$i{u2D^%(kjQ6^KMXmW8_yXqS*=s<5-yYz4 z4MmiYVYGU?ptdp}Iy;iV-jkHag-wOUo7aK0sXgoqAidaktpRz`T9?CEQOr7mIc>h9 zacR8)+W)wa#d?-_<+dk6x7gLf)ug8#*EYvaotRBh!`|pjTDCI9d^vX9hXUyTBNv8= z(m|>s6lVR*Ck3@j;4j-I*rT)yy1y;sF?}dzBf%J|I5d(`NvOQFkUhq}lti9U!tG{x z!Z^GY(nN+Q0|O!C7*5E-w7`FBYt*e9fQ>&9j9?1vq&Zz|!# z9}8f!wmpyeJJ7YAVCH>z)p+Ua1QaVNWDRhKB;R3yWMPlBP(HGfA5X<~ROZ`)p4bD= zH*Mlu>vPS4GcT+Ljc_tq>C`lMyJRtZdtv|+n%4vS)g7kKqX$6>z2fdCm@@ewrf9P* zdbO{RObDJ)h{DEQG z(iFHm>n*P8{6B2Hd00+e`2JmKMw2;nNQ!upr1swD7D8mm975*IMF>e0(r~LJA&E#t z(zx%bK~a)aQXz?wkc6lV@4EN?et*CBINrCvpX2$s)>`-4YhCL)uX7)U#k!ICOR7{5i z(<5;|jvpdz488#GBizvSp*Hs09fwPQC+ynOn;*2JLNXFAB#1o!?nx+ zU#Ffx@IcZSaGL>-X%tdJg#@GezK3|EXa+Uwm`MK0`vJZ9O}OM>)B-wL=_aZ(N&D%Q zq~oYv7F+=Vp{0Xj?I!1_c@f&52C`KN}S@P#0z(G4oZ)vkv98ri13pmG~zOX zTwP(5GZbTVEbv2rE2*072Y;nVoG3Yj(@m2Ej1Wx?!6d%+zN0%Upa@CE>g&RTlz8r*0!7H)wHL1gKIgZw)Kv^M?ZVx&Hy~8tkOtKJ7E5UrX zQ5Rp;T}q8SERq*Z+$P-`XG=d`b4sGnNrx6nk#Id8-hL0z5G&?eOf;3<=k4ANN8iAW z2d6OB))SZ4M`6&k1+dw37yDC=WAzka>(mpX`AsmZF4~A^IIN~@d`0r)fzec9=vB!) zrJ0hb8_8%5l#@#!F$?Hb0AE)rFD`d}m=8PRG(Y}MB*wqm05)$23_C(#MbzJ~z9iwk zX#fsp3oXJ|3DKxql3Mk^|HR`QT`Bh$_srLqw@1K&jyZ!sqOQm6s=KgTtV!wgBBGXQF;@2u3|};|EPuz~~W7;Vmuk z@x#X{UM2RiW3=aDp*c3g_ZY-6-oDBDrnX3$*8MUHaU`;ZlcXnJ9G6N6w792sSPu zZNl%PjyRI2Tz`zZp?45N`r!W9c@!?Y_F_T$IoP;vA?5Hzh?*FK#F0mNOpAaqCzz)L zR&j-Mw^H$UMe^frMqI{a(%#6jRO0)NBlS)XVM^a4-C;|SrkxLmG}2l5{1Z46bi)BD zJcdTX@8)UL&P~AN*C!Cz^A$3d5qt3?A|4YXV5|v7-71EwTH!&x6pQ5jK4?orymv@G zwJS-D45Ww}RY)40rXsX=Ic(NGL=Ev;Gbnh9)+zV!HZ~DQPMt!?hf}zd8VixbZt~we zM(M6ASeJ2v$21F#X6y)N$e3jAbG+NAQ<2cwR_FvQrY$Cmn_O$WiEOUPQXnO1w6D0*n5n|4q~}9@9f;m@%7R zg3Qivj*(u}=m#SC?TE3I8(l#e?hTcwbY>y>P%-f;TpJ^Ly%q&`c=;+ z&6~0?x#BpgHf-fFUzYG?aH|Ps-}YnNhzWMmvI zxGckVr&sWzpQ71G2Akq)$Yx3KZO>`!Sg;VR$8@~2I0my7Q!v#f6DL#sFe<@?$G8a? zH-eexqr){`J3{R)7Rl?4y{RbWY1F>cE#jy>58&{t9I;Qb;5_p++SZoAnfz<3J71FC zsWMoP62bf5Y{c)Mje9Hi!;5sdcDR%Q^N)V$vq{*~)-L9w*-bFxA}qNM!=qGciAX-? zOSD8uH9e!{NP(>p3Xn7CIaES(P)NVQhNaKYpqB&ppEWR?l!bxT$DuZQ8v2z?hCPup ztS7DW?v5dLd=m~Ms97*Y-63GS3FgvfRqj&fQR?;+kzC`g8r^f&99yLeJtlcQc?7$( zO1S&qhq=;Q$QmnPwIdg?KDBT!$i}S8m+<_*UFb1jGsO1csK{T5(Rq*YlQgHToiF@6 z?F7sTf{8J{n%O`5D0Pxx;t%+Ur6$*@)!y%HN>>#j$FUl%1M?9edIv7C62T-zwS9IS z+*afwtTq~>>2M2=i zzQ#QzE_ZxvPu!b8xt@NErmHVt;qU<3CJl(vBdcv?KD^@J!r|+E{IpDgX}9C}H}nYB zu(60->4i_#mDn8-1LZ}>dCX1$bAez+z1YI_TjEbeJQB%c)-RFXXzxX>w!Xpn%8Ow) z;S~a^AHvE1Jz8U4U{3A>lv>x5vsymfoNpn_-UHhg`e5AG^Qa43M>e2Rym)aAIRvlx zNRL^_M{|u}zD`)m8FW2PrI4SeQ^yU7?z!#MyW25T&c`ROY`>gm@FqAlSD8T#SvV^!;{p8 zY?0h@qNjLl@n_1Z0SWIrTPsVohj+cNZup&r&!o zd4s6mMdW7i5pAN^QjbmG->We8DdlG(BxbUne}I4Kk){^iA7*O zHlg(4BlLK99sP++YaF)|2{(d3g*ao_$Rczh_tm;{cYJ`3W{8!o$sXFn!(@n568( z$*J1O1sy(bpg%83JhT|~dbcoO`Zm<9-H0mR5Lh=kVdlOPcxQyeeeG^O zn$&sxpw$sfd+1DVw$5ovHA*C}t+ki5zAvP1Wk06e3o8)i(SXw1PZ2%zE9sl|4h;F% z+P!E-vHuh7TT_4)+k%KOstEsPT|+u~bGvc49(#V?!1;|qJVsl-r>bd7=R8B%`k~X{E>=}ki zvv^GK93G=Ifs`dYsO9b*j-rCe#Uqk?DQPj%rcVSMp|p=zA@si{#BO3<|jS zb1qVM$i?HhRv#*6m>R7z?gi!hsTxh$AJNfCKFXKd;9Kwkt_#bFMfG=51xe6fnh|1K z3Tk#a_L(=K)i@v1fAnFW`ZW>HuV*}_WEPLZCfHBj9Hx{I~o3hW^)M!SE#kyMe+)>JM>Tb5bZq8mvX*B_Oq8?U^@Q=wC{Jo zHTg4ax>h10{uky1Rl!tQiOorWf|um?wfw{fytNdDxSAw8{eI6clIgHq}81_9e!QQD&hg~$KEaB2&hFI2;3LMII7zr+uEjgX8 zF4kd(Tb1MZaABpLn#yA+f{97&$%T<;p?DXvppQMFhPN6}`MYmYuBi<$@cRYVmG3Y# zO__~yZiDNQTI{M;Vx!O10k4|zWMmuyuiU}l*gR}bj>V>CO?KO*0&LxThaa@gDLlrW zV8%LWaLHP?D9xoJc~<>4iS=JC`jdY&Wmxe6IdPpZee)jmtGlp^6Wd`_{ua+JsIabs z8pz@40}{Gj#@Tt7Q5G%6*vV%wXs;UE@I{8vU$66+l*v41o?_6}SaKSAiPS_Vk$ljA z^Ac`O5@pj7M0Je)jO73R!EoD0>>Z)T+GzZNiurrw%~WNb5|*&<+^31*k`VvY;ALv?c$$-`gyNIq@4KzVLBLe-sY!DAO? zR^>r6o)xRJe?}{@4ab`>s+&4%Nd5_r-ao>?(A|h<4j{ia5>poKLJHYx1C%ep?ws(w zp}|M9j$r1!o5>CRbBF3PLnIGeVrlzzN-Q;G;Z7ekvEV!1M;_3z-%X&f8DxpQ?rvO zZ#$9vlGb>t+fIF3QRV^4?ok{1T~KA+xBkG;ZrbcLw=S%ENejAf&|$ zryRgI10gSPOo+x;5shAC#-!A{l%*~CNQd;M?U(3FO43$Sv9o@|agPSuG_MoO{&r&z zOi^c}`?P^J?#4Q~wBy3l3+Tu*#r+rmVNC<6#3OG6D&HUCwcR!pU75~Db6$uhkYIc! zg;|f7l1$lKiR8T+yHQ!c11H6gUPsvx>z6Z}CL5ac2NS02u=71MSZ3NU_-*OVawj{{ z6m|i7=Ji0Cn<@0PoN)D$A%^zP#-Ae_G5)#@k5Ln%i69u3=`$&+e=?P5A(D%BO%a=3 zB+Y@ZcB87S$Xd_PVpZb);onqUHppL-^-}6UuD1?r>iq{!M$xEQ)eRb}hv41Pxv<|u zv^P0oh^?1kQobNsvJfyaib3n2m2rCWJ?i#2k-TPdp~Pw9N$TngW9m=65*y^B%_c@E zu@{Z>*vvUvY@tghjyUMDo-hC6q{{{T==YZ?xNC?#f9()&@r?=VC&!i?dw9+r%16^* zz$6gN;XT=zK@U@?D`Ut}-Ko38j`OEh-_)Q6u2p7J$982`_E%_=jlU^EiIDg=rM`!L8!4@X~B%&adW>xq*RxpwPHEQ^2GUOiM&RF32a1>M#?@ zmk$k)m@deql%n?8j=8PO7KC+W)s8B&`?u(`r@gh=?SFowAViN=Co5B{Lg5@VdyZtCPt`l=l^D`ALb!B%40?f(UcO*e6POT&utQFKfxSK zSS#LLP)gOhC)xNt5-|Fy%Iuj&0kh%JZ~QN&abY6nWvO9P-UwWCos51T+L&$XMJV#I z!}<|Iv&Lot^O9iZrOxH#ljIaPQY1Hi^isO)fDtX~Ze`ocLBMR=@P9Gtg`GU+#}Fm< zr6dFA9h69-#SYr%fPnT7%-F1Fu+kk54VgV3jiG>PAQ;zmG2H0WIn)G#d6+a#I-uN& zet0d{_QyRX_UWyztduNlMKtHh8Laq82akzz|A*hBA7HI7X*lb#2p{)OMAi~zSdyd1 z!1-e_YNfE*#0k4V3&Hfg*33Pudq9ma7Re>;-qPm#XXvE&i*26`RN@!(1Tx)z7xh`c z+1hNtm3AnW!1jc{c;H@&4?d%yX15$GMmwOlYCALFL@m@J%+TZ03_hAC0;YptvT_W? zdp;IZ^GAr}@4L>D7B=P5Sy?f*O-X-oE?Jv3c>WK2ob=hvPqbKz9>4enZ9z65*GDgi zq3u`<|Fs!M;^$$ovl^HoA8>E{1k4Q)@&cP^enG2Rk&})27;(ph=hTH^B6-)n0o+Tw zxAgAG##CXCKiD%so2@3l__Z4P{4P+J(uT~bdhFlS-`F9o!xYjiLyd@=TaL}bj?x}j z9rXkD#^dnbMfecR6)-vkbNax4;-24Xsp~^Ta^lltyKuNNvvcW4$~UzWi~P0N*t$P( zyrRdRzNE=+82AGhALz3A;!ZfPZ$!5HBwT&86=6H3kQLVx_k4a}f44Dcv|P#$+CdvW zn!W_n7;h%l`S+3XA1IPH7t1N1GA*VkQ;#wo(SeI)nyhQ%Z^YT^vAeW1S)HJ72s)_C z24{C*xZwvJ_&No@%RLaA&mzL355morSo1L!*cu?DhE@p}BZ5(J93hTf|C8F;Pb9ZG zok%6ycV}!;{V3O{U)VETlhuCTiJ<4Y>?~&uHu?8g?Cq<|y0*9D)}kM{oH7`0E{hOZ zY=ntbst7J_MVzx9)S87yuQQYQXhsvv!uO`)X@iw%-JT-((mCfPo@=!j|Di`I=dnLA zKUjlRG48~E4_$WDeRXz2G&zPO>9F>r+p$9J13nY$iA>WiNEkdC%Qmawfqy$Rrl}&b zQ^-J#5Tdan7>&9~;usBen${J`v&*(i9Cy{xCK_icl}kS`=CwMTFuVi%^>x`@`s!?h z`WK|n)?us1{=)73Ul8Ek%E(G+n3Q~C)*Ovt5)0lSEcqtW-QR?to7dKSG%Ud!@|rBB z+_h;pEs;Eb=xs^oofov_`b$)T&Ufq@tbtM*7eqk%ux$e8{(lhKwgZ}@VaD?&7z2u7acByKw} zfG%kZkuS}@F5c9)jy^bJCY3Yc6V#TeupQIBp;u{F_EoSloA#uhKd1Hn+=A?wCm1+b z!Yub0f+yCYOuQ}4lqb|6?}-^>9;d-aV`IfH0e6BiJGWBYZ{JY52f<9AG@p_3%Jxd^U-~UZ6l$^8el=qlxoe(3eTMP7rGx$-=QDR!^G*B2wgI!=Bj?ONl**f- z6|co^ctW;Ia=&qm(qx-Ae8RX~a*^*|!n~^-2~`t+#;NN{rf|e(w5V=i+I58^M}>g# zCzyw0t;MA>6M786JW>y$)!g0bc@5LWg~#8)@cM6fZU2O9S4}pmssjo;Af~wx10(M+%bbjHSh|xL zTj78wwB2R5jt&i)DzQNg9I}6) za9#tBEKy^dJHDZ)^Mq3#(($0(0jw zNUc@a>SwPZtxF}&B(BU|4P{uEAEV8;>(HWk1?W}Poi4KxB){7P%x!`hWH3See9eFK zBXyD7%WslccV(5W?DbxW*Y65Ar+tRX%Nq2%sLU$T52kKUFn6jFt3LQ8YNp45@lav{ zdpuyadX1pJFI5qbNzcNt9nBJ{Ov2C24q*vo5X|Vd(c+l17IY2SI%|Uy>GBtw#R-O2 zByQEEC@g41Yi2c!`u;=l#P`td{RmN!ztL3q93Kv6K+o7xk z8FkP(OA^DiKM_rrVdsno@E-YwdD+brD>D)p`_6R6MWqhjFE24_8)<$C3>Gj&1d~2r zTkP}WKRSqfq#HlC*k%mLkyv)zmpD%%kC5YDBl-1H@|Z%>5N@ydHv-ePRzw6ABONw}PtYd*xGKmD`3b*UKbZ(q;j#FpfTw#5IL&r_Nk-Py821K z(EX$iee%HduSW9f$MBc7fbpqBu|$gIuFY^QFF;&$4fGFB!}i;rh3LQ08zt0+E_=NC-)?dIh5zHooR&G|I z2^~#~G6pe~ll(usInKb86wdM~WfczhP+PX~^AUk)#)e=I#fOcSwU> zE;$RE_IMt1#Dd5CC72su+Bi8ifHrm@>4yz{s2M4?vZ8-OB?c`S@XaegN39ftYHE=1 z@Bt#uB!OH1l7Cw}cCZRAMyFsg@*GqxLlHJ%FLKGb!Q|r^ti5`X$5j5uV>BnKC{>nz z;e0Oiq>s!J$ytdr6+2<2tX8gMt9UH#*!ln#1I5@beSy&3d8Dr64l24lk32A?g}c-9)t6V@8~is4&0|`9&=xa#(-cFU7m9v{JYXw1k*F}GPQV#t4zu8 z;-sj8G`L^ML+sE@()Yd+fA{6W`0{Po%q6=+Wh!=tU&D*g)#%ZGHwqs6Vb5$QdFt!VX+zwqV|iAk4btiW#f2(eUUDIxp-FT=ClR)`5Pz*3hzNTp1$B`Fj&*N@^^ zkl?)vaSmVi{WH9m!NKo(ri6JtlU zC%D}w8H2wYLi3?6PFvn*#N#*MV;3zj|F&Ur`~j3^R`NS^o)FDcf|-2Wfje?TLS;@O zZv?g_w)665$gVZ#Q`JAxQ92@rILM_Cw{lW1kRylZzdNMo<756If0svpv=Cbzt+*2A zdAbLTatGpGC{c%zCy7%;ZmP(ql?s?S3QX61-0Q+bDssF?E=^IR#yU=s#U2Zynnq?I zl*@+A4&qmQu^8H;`7&I5*L$H-#W|p7ibi41RCJh(KSNrayx-YhuWrVHfe>b7F zQg9^M7?Az|b#WZpHWKH!9rqDjb^}-1k4Wveo@3s>ije*cHiCmn5HrwnF0-cC61^vp z2DapHzOdPN5{!RqJU4&zGV0hMkv#hQS?T0U^JPk(Ol(>=r+|3b^5r}UEAPW@Uk2~4 zps0Z=^|^*kT3NE9jM0)8L&9XW@6}NJ`6bn}BwV`ot~Pr8BL5HaS0F5CAA;$#T+Z#? zIElJQFgYbRBw6={$}I2S6uZ8@3vJ(Y)ZLAPCz}PYZz(7xt`~LRBuE<_iyJFcWxtKi zF}niWq|7R)_!b_sY!#R3XGDl(gFzPSb&ThS~Qf(=`WHWkulP@*T=~k zr!|S4q{I~9{ypB3!gr|{o?VEQxN96r?K0r5cM;F0#K_!--=lq}OqNaSJpkP^ljxFf zagx9>qp-VVCLfKeumr*h=DM?#8&s%C6%H23uT7prt=-rz9WpYUw?kARg<$T)TTNkJ zZ`1D<{Otw1cZF?rne%;do$Nc~mDrzp`fDESNc)_;IA`X_(3PlGzs@Tp4+xlOf-%&u z;=*jd*(Q+-`|_e=0c@E?k~BWFq~psKB;UV*Qdd$5nN19Y3a`O5KZvCYbs420URbN{#AD_QgBDLPLxyXJuY7%JJBMUB2IV)>L()e{ zGww)j3rWqO!g9}Gx~GQ0f>hk)s0N_5?=Z%8o+a)En=u~myr8+z0t0vT zfuUO{RNMqv>0e<9Boj=e+{(tPti{%kEP;u|#~Dw%cl7peMYQRuNECKnMAYMxC^Wr_ zri)ReC;x%u?wne^$^v(lXXOG38%qF!PH&E;-ldR_(TdS!=mu}%|RH> zeb2a0cSqN-T4v)UQu1p#jD#{cAgSSeAL$=p0FDwmo3 z%b@hs>ul|E0^zVB4CPf`B()t0Pa6?m-R)*C)T*0l%a}gndXrMon@mA^5OROsXTq*0 zGxcr6v~GU~KR1tsK`SAc;r1cog_oOcyO4a^gnJIMKg2QS)iy0!Q4(LbI~Z4c>;m^9 z3<0+T@jb#D4o5;^nd^ov+qyxkV=wdula>-LB229*W2SpFF>MEC;!XM}KAN3EG}QzX z$K{LHnkZBGBxe)5=DqZyc{P3ITo-8_sV;G9I)(Di&E&Q4G;&6rM7fhEN*{&bYUWy$ zXeBb!^gc1RsY{sy&C5`A?-pa~+64)#jN!RTgU3_~(Yzy=C0Ap`rT_KLJakJbzlIfJQRc$bMh`Is5IC7)hiV~MET(~P&3(9dS~I6j&o1d}{%jd)IPBWh(Yk-XuZ zHa&aecDiTEB8j5EK9PFO0RbV4`9>txiEJ*!HdhCeiF&mh}8^7bZh%VFE9mR zGZ_0%%hCMe4D%uVDIZOU8ILg~nBd<7#3wV1sZ=sI9$%a2bs}}zM?%>ux?TJF5m`Kl zYu`mumwtRdFZnI}cpL*pPDb&)z8Gb1#LTYGVoqERW|aP0!^k$fLt{=jGx|vjkJ%?+ zED2`7ix%#UtvR)n&dcn zc>@01Y(WG{^O@IvDtNV3!mPck%N*>r1<#w^nE@{arPs1Cd^8NfsF9l68{Z~S%>>gq zFiTpsd>5TmI#ANrX9@0Sd1J>ZjAG!H1>5f6_QOv=_NIL1~0rcrIn;Dh&md6|$%SYox zFs%dUiKXT=b&Gs&td_o_e`UV1X^gU=PQ;PsKLpcqYBE1)>qtqJo}nF&A&wOYUI?6@ zIF$LeL>(3SZp`^dd34mWV^~ZrVcM+!@|bPH0cr)ol%E+c-W)KQIz*!Rb>=o*8X^}r zRXR!Zo;dNCS~A^=C7{44+P5o~z^3Om7!qlVEytSaUU5ozHQtw5vuHnkJd1SfCGvjf zg+jOML;flw<3fH2W%`Z16er^<)(0>AE=K&VlOHS|@ z_y1VL?0QC*{!l?&&<>_<_GNm{=)?FxJ2H00D*QD{BJ62938ugEKyg;X6lxwBw13a7 zr4sH4RoOGgwozS(CM%bPm+~n-8U@DSq=2z=oB=yuV`j$0?l`$&JyRR(MVk^;#G@J` z=FP%(e$bo*j2FSU&$ANW{Vrv(PDG|0}^(1gN+_B2Ug6D0^>XW|BLxpJ{fbS z8!&$!YT&}+!wegKitg9G9|Pj2F|U+_xfw5PoyQ1ftK3X{=b1faN{)lSlp3g)O_5?& z|0wnUj^_UlGwmCN^n)sl)*(&U@9<%kJqn`V$@XJx=Q1Yek}^MNM}=sD38rV@FtNs& z=~O7$Y}8E$+P>TuPU*Dy@R*bp|2LXXTRri=gVwFa2GhyhAkBv9@ch>_xHDl@1d`Xc#<^J?PlFLkL+`hGlSVbh`iGiVD{ z{x3$c(#n3ZP*-J{m#Z|fBG891>Cj?IuOCE6=T2tk{qOwT^cPN@u>{k#-dJovi~=5M zi{vSn0ww1L_mr$lPou{5a^fYwY}91pE+2s5HhcI5typP_-_6;VfhaXLK(ixhAs%Of zvGcw#y(E_)-Ps?jC)@GSEE1x*MKEqow&FvQnN%uyir6mdD#?oICw}?iCS@|7G-fh7 z#BVl=-;DyZ(0&Rk29lLVHk)L}y)b{*1=X4i^6pq+?0_OBH&29DN&WEFU3eoHE<}^2 zh$f8{TSYriog{P1c$(2Jy)W5X+ZIs2(n%BT7l+YE^y-QwaNl?@20XHdq4)$;$?E%l z;s|no4+s5o7FZFnLrl^`jP@18X-~z4;vZ2HRds>E4|2V&{SPJgUNHxs z1|WmHQR{3S#1GnNA)i)AFx~fz7rTyhpuRMQ$Um(!pf_y}l4zQqr@rT}frIujUc>JF zH5l##efWNzt-FYJfPAF)*?EDpoQSO^AF*ej^oj(uBHLtj>3aHNE1GN~guJI(ixo(}>FW<}zZ97($vg6Lt5X zH89Rm#okH7p|X)BeV~-!XLTHZrrV)ZM=;*h6|T571k)Ov-nm?!c4q1W|btXuuq+k-g2>pi*ME=wO zoa?m)SDpyT6e|JKNHB+&4i(>fZ%0ip4w17lYSNr5nUwxbCBCn^yH6lgXRL*5VFU`7 z6M;GD5^snm`n4#u$2tNA4mB+Sikg3(ZM7GKJ;qr!4S1LUYnvYb@vW8p6?4BW(H#tTbeIKj+Y-&34A#hNO(6(Tp-dtIt6qUeJOtEi@!Fy2zUdgDnb>=2#i z#Xun|RrnOTPCJ2t=e;1BxD171cDVmO7_}#+qe1&D9^MMUtaPCOX1#zhCzzR+)WnsG zCQ@w*jH@nfHUFd3H|Q>9v@8-TkFOCi8M!@^ynx%)t5C^4%^RdI4he+TR}txD6M;Rm ze6Y(Z5sRN6K>vt%cu114Q@WgwrdhyP6HLc|VdBfWlc?Od5P9BFIrVZbOCK{>Olj}F z0Mm~oiUXmD(jjsz(;HA>BcKy<7hVphvB+mPp6+)gC34fTB{BjpR<6P!jVP#DoyV@B@pJh*nuh*%lNJw4nUDz~66DRXbY`Aj{7uGmoNvOh8=Bam?=(im^4r_(8iT?9ht|rXb-lS5jj}9XcN(AL((3iXT5k`q26wWjgT& z3{uibiaQ#<&*g|ZnF^*d7HvzUP*{r3AwR`2*CVhp&j){7?xLP_B3Y?<6FbfBpwCEQ zrBw=;)dcfnPC54@*^D}VCPY3ZJdf`C^%D0hOO01Z+HED8!rWN+KgdPG%}l7TyoTmp z+3>cwj0s=%qU*#>*r!DLJvd&#liBO>=v@r*j$DRXzVN$=5io896LIh~SJZzbbv-mh z9uu>J_I}|a-R|(7GMt}8iu>hg?RAZ)iyy%4uLP})H&An#XxY-QVo!EB!pH#KZ#;3!PuROJDET+VRx^x(E**h`%Nqp9GqCl)0OBG`vb%fJu`69rdd(D8+6jWOXbk5}eh;HQ_>-$Z zI7`1Z?UcB6_oZCtaNy*H@Fl73rnIL>?jRy2B9Buf?-hCIHBV1NkMc$Ehdrnte-q*x zyRl#Q9?n_b#PR`Y^VX-ZArCA8Yb#Ous+iZU{eAlkPU@-f z8|jN%gH}M^Z2^+)A~AdGd}Nkgh3sw&?spe32EvEn8o@l|=5Zc&!>O%@LgZBAAZb=d zI$aq%o=Pyuh26w*B>QFZk6sCCr3lTD@Q+>!dECR+qX;~|0Qa+j<Wz7_jV+z=J*m0Fe~c!TP0a+EXsp}K1{4h^@$60?1zG}{#CiFErV*>tvb8P5-z zu7D{f7=33CPW`C`m3V-hY$|jl6Ynmirw$)2iCX^%u~s#_JkID(J=E1+!t?xn1nhbX zhA8v4uD^>pAwKvz*bj%F#v$8cA8u(>Ks74?CC$M+W}|?qB$!<#OS#?!6RBf|L*x~u zev%ccyQrp+6OyLfA{dwvDIAfV(@`9l>PZ9mB1h#!x}NA@Z^ted!C6-%=Z*hDj{iAHz-j z2Hd+m@_^q2mE6}bAM*gtr{AObOD@LOKPH_L@*@_9l3v$J++biJl%rZq~>Ld>8%EvBvHeN0O`(K*c^NSuWp~F> zo6Va*56P+{iFEk-SaIEv61eWKM=Vo-CZ%Rxv?NO>kNWi=QFGt{)MBe4v53ZX$Lpvt zPeEEt5I!{jgk3-;wisULF_Q$0k`3`;9~{KJ>R3scod}Va zl()2?gQzDDIDNnbHU`=`@i1PNgkhoL^czd{d^w4e1m z8dD}*f%v2!&L3)r2l+@m-gTaj=6{lqg9ygM=Q>wC^Efq)%#CAQ2vsrcHEpeFz$?9) z=6*&~-%>bV`N_+CT-KGK?)VQFEiS>sikD!QMdM2PZDjwsgQMfaQT9QD&Ha{yo`Y`j zn0rD#&4gf(c$3?a8ca(!Q7a0o+}x1mhvV$ zbZeO&_2+L2-BM^nDTh=3G-4_edN~joB9>FAaPmF8*0Wug(qRwNct69vpXf=S2=g_WoQ?X-{|q=eO-dlKmPh3rG#&fL~Boet}dC6*k(i1~D5t;iwjf%~x+= zWL_+0NlxI;neObZb=TmiDpaOq3xnoNFuR`5;|6r3Qny!x$a`FmmGlp8rCm$ZNsZcD zzS>SvIQDkADjR%VsJ1(Iqzh|m`3A4bh@9kmD6C8pU>n)>4-}wCn;J%j5WH zj0Ma(#oTN@!;P3Fr%Iecvl{Ds@edZytwp=3 z8mk@r4ts-sKz-XWTnLK7*Cpi2Re1n=X>B$*Hw<^RgmRu_Q+}mwCzuc6$GPqu4@fOX zhl? zpfj52)?K!MHdANEg!#ezh@g;sIEu&YBNz|$E1ZdU3AJ`oh+NjojOtaJLywFZPPa5N4@7O%EJ3FZlsU~*#1jk+7*lT;g!Exzp6nTtCTECa&%9f-uc%iwUz0+G6dkR0<3qv|K%;!5FuQ!8K+2xjt$C7kx7 zAJorZ!E)-rTxvo=9Br(lPisFVRrEAb5Ups(p+H?WyPF0(NVx^lLZQ0b*`O4z54xky za5nVy%(2u!3!>l_>`ODjH0K$7G#SF6r4UTvl0fcC$#1IXmtgrGvmTrc?$M9tDbtEt zb=pXamtdv(>#=KO8f@r>uY7^Oq9lHa*<+ZkR7J`U2b`k%!Pxyf^Ko`FzMdF@Hp{6z z=8Axk5lq1RK+f{KGJU5$SYEmIq|N8%SbD~;EGozK7apf*@df@0na{~>nrz|fR$djM zkYEL-m%^ow8fyEIH|X95aBlm_j3XNAGNnH7`z=&L&J{2Z31((dASc#Qqkq)|%ipEV z5m!6jqm%sNsaDf=UKLU2_!sAu4cNFQO;%<3H+&qS&#NNZwJNZ_>mQ~{V>15MYr=4K z9iuV!6J|K+LurvUA5EYzH>CvQl^x3s+N()lt_qgl-kmRLO_tDlKJ$5boI--t#QsCN zw*i|vL5r8iX}`eYQ!!^lR2<7u)}ZxBUxDeEo;n zHfcI+XLUtYTRl^d^%Y;+l@RW3%SY2DMAJYpDYpu_Zu@j;Yk~<3=pwHBeU6UV^Uvmg zF{6emu~j{Lu*;4KnABkgtn0qNC~$mE=O zpCY=BTq=0Zka8)AA;p)4UbA}zIRdw<3$pib8QG3ro~Gaua7t2g)x6sTJV+8XJb=3(W9&W}__lem!5Dv|U(feF(GJEmThmH9Lw(NKrIy`v4f=Zqn;rsStz#mZ_t`pX}BkdtBmsklUUmuGmslPPxS zNkTNE31$_iC*C!2Fg^Ttu-qo&jqP39j^5|7U!wS|(F?k;4p+Zp@Z0X}h;kK{6Ez@C zs~c-|^ebYnPb0U1{W4KXfOJFABbiZfmCUk~^ca{UmX&UJ!q=yz3m7Yc8T(#OYdYI9#u-=fW`tx{q+{W`4wtI0;6{fMX^=GcDd zlkAeqX4$8G@v=m(Tp^utM|Pv@Kt7uF!l1DPqZigwJbUaA`jAqHyr*@4deg%v z)VNogl2;?;k4={3MLCjj*b8~n2(w+dowkWu1t=ViG1Q^*cE{y z?a{J{Z`63qbOGZ)FedN5a&xu}p>;aRp7vuU?Wo*C>fWP_vglrejv>DgFkCo5)%_xx zg5DK~yVr&F>QaY?B~hTCM#=)^?u?RgwzRWqy6jFyGA7?PkV@L`@e4Xd7_@~1GvZqo z=MguU7JUzv_oI%|Hs69NuhwiTD)c#GOIuMltp;oBR9K7n78s~M!Kx4?HhC_|bZp>I zzsXdpc0~hs7hj~$tJ>M@xnF~Gqr4cs+j{&i@KV6I5X@WWWNz2x!Sv)$!Sa}OV(Eh4 z8uYE5E>!j05?HMIL z9$O@0?YXfs%|V0tXlUUKy@_CY2fXEC9vacd$NxdD{QjfW&h^A1Lf zp1}3lPk4QJ1E*djD<%5|i^3ud$mrlm8F4Go?(ygOM0eB8IPGJ zVB862-ws3Z&Uqtfb+Xy0&Uh~s&ACr69QTE4ipV0<{}KWHNN2087CxEcs-1yo&;N(8 zGx4i&`yPKpr9zU5q$DI#nsxSBt9dS!B!nbWW@X4&iAr^lB4kR)Jca5xrxTgS5Z63p zo-)PF{M-B4H}`%%_xt^QpMT)}T5GRo@3q%n!)tn-J%OFK?8DLX`U^{o4}#WWM}>d> z8^t86lQ=B2y<$iJALa6ko4{O(@onNHNbR~wt?3TE#4cHWuM%&tFA< zl}efb`&{gt6n9~-m=e!&)sIcMghJj4Xt$y#%7aJ2%xg(dc;XpmPK}2Zmo&t+Y2cW} z6jQu5PT2RZo3yA}rcCsQme45XkEMzPHk!_V%G5+!7_^3b9I#PM|X2+>k~5N zvFN+nu)qzNqPU9FtajsUpF7yTZ7V#}aVDM` z)f_)uxC*V_yu{H@TBGNhz9MEXUz;@)b8Ora;aj$ebY!Vax&KL1#bS>#MeV7*M^h4Mxcip( z9z2%248v|5!`bfZaMg-h9C(rr-#CJPev+e;gU9GiY)SnpjA*UIx<1>`a{CgT_NyE(j$Da4 zr?25v3vcXPyB;;H(@>|-7I&_@jn?iNc>HaOD2*S-lv0dk`%K}i$uDw#txTCp=en6) z-&ApWAdN#uX49nCBAPC`99Nz{f`ulV=+o+AI=ky21_v#pjsLD=-mMg@EZK^gFSg*B zS;43^@j4EP+>DEl@TLsW9CM6frtZoSrnh}U^7CcNJ}btNyDN57Y+QIvvLl>^V)nwqA#ezb`~@%{^%QB@?S#=iwJGeVjje6t>Dr!QFZGMN0man)m?JEcY$8F0GG*|qPg0Yj&mCn(|w_2(#v!W4k)y)kJ(`KSU zfQ^Xp;h2{cvu*B3;mMgC@{k&INBEOW>z-V(q^_G{+IiaQ_~vTb5_A!|(7u9A7p@eu zRBaPC;rjWD@Z!6wXG&Nq>aN~|acQ}j(>qmsleS$##~^f?sle%1q`94DS47UR!0`8m;G@1v z+V8O=Ef8EMO5@MBP7Ok(`D!ghPmdy*4`j-Bm2>4@$~whpzd4FymYK8!YbDy!9^TXL z&^U8Wjwnsanl+eWnT$<)o>#PMa~b48bY6~yJ7yJRL$S0@dS@B!)urwuVkYuEO_yS3 z2iVh2-%Vm8E?wPhqY}|Y! zaF1eA^Cd84v0lZS?SnAjLK-aae<77xj78OzgG7uS$8@BaJpcB>((~5j4|SD!0& zRDGrhITfO?-I$JNFD}Q&(m7&N?X$PC@hlw}bf9E~*zJ1S$;paa+thGsO`hV~&+(|9 z{1&RxWuWma1AE+AC9X{`j_JmfrgFKwkG(PRZ@pBR*SeU<-CI<2$Zo6H;jYP)BP!bG#zh_shzvqLR8|Xlq>5#; z-h6FrC`KChxO{|*4w0JBhkUEU@_S28Dw1{EE1EuEh_l~kqUZC8`0~jzbk9jcdEIn; zidlI4;#l;}T%mYW^&T|)*ekR*O~Y|z4`AuKPN3C!5jI=iR>X|w(zsB}sNR}FMH>y` zV!2c~=0lnS*6kB&SALVb=kY}4W-~{l*@$ehOMJZxZD`7}hKyoR+b&<8;<^Kz2Rv6i z|2Yjcx}1ismEll$WFD4ZHWx8n`043MF`rCY2s(K`B$I5HDj!XKMV7YQtFZj$BWH=q zwapiciOP=GGVqvJvY44-YrP25rw_qLPLHHEAqIH6W{}iqG@V^wrHLk5hoJsZCT3e@ zifgl<=XC~Cj9znXVNc-~$$g5kY~m#kP?*d2RW}jB9TL#YeIZsF(-aNK4Hv4m5icH{c^o>DVq{sm!mu-6 zBukx^D#JsU%WqllBsz6fLe1_;Si3k`9J%-PWhyr7k|@rKVAD#|ef#0BPn$u*+!R}? z2SSQt3JzA&!UN~jaGfjzEy8m}%m*$_48>e7=qlWM`%TiseyMUmjio~EWRUa$c_CrL z9a%Cgo50M5pRg=dHlC_z=mOj|JOIZ9p9Y5`D%hb{Ur0@xhHZPQ;0F_Z>=`^2e~kGo zViNfq!32u2sOl)#rTvtQqe`n>ry)$cvz@$aV?o$_&$!NXGHDi{vBL5?S)y|8m-%R} z?uX>eZHPGf1)Q`eLPE?4RJObd*VfbS%G*Zc-X57Eriv?V2F18;>>_MC+??q4q6six z7D}t%HzQls&Wba=j^A5=8g>5SG#`dx<9FG#Qk}^@c>TEoZm&?l(CU6Le~bt1%5xp0 z!@A(YfkUyK(g4^F?ZF>bk|@ULQ*&X*H+Ay18%?#MFNKA5>e9%r1%wT(Jy4N^H@f;` zMED{s$(i|k#tIvOlt1hTJXx_5N?N4BkV__5<&*)dJe=_0H5XKM=q_TE977#)mGu?c z!h~*GWEc%X8uc70^b0a1j@!NyHcy%j*eIqQLsCj;UFWPsG3{C$^h~^IguNM-dX0dp z!|Pzs3oQ&CH3g&}`eMOXBfPKbA!2MeCYNG{SG5+b7PKZk^=RRL%5nKEsXbYvdXvG~i#&Fs`8*#BaPh%w-AYsD0^>~VWReQ|rT=9f$v z;^Hg6749u9x!hKq_04|I2C5*Ib{$(g4{KieiNjCW9QK9d?J>XeIcdDn4LEu8ASh1u zk?z#I)y_0~GVUp_kz9W=euS(VO&|6LJgV6Xf~H^The_Kyep%SMDjM z#3y*q$G{b|6?o}lET(VH6{>D{zx{sclQB=A^|M?Uem+;85fpoQd(0qUpamj($(o13cNkimWD+8scPn1e*-1^Z$^;DWSC{{% zhEzjO()QCD-KCXjfh2lCAbvKG%P zax$Q2Ova_6>8+0G?JK6F3}Y2^byLF28z z_}@Hekm83wGDU-4mP5oOa`RgRr|2i4N=S}$z1$G@#N|Tfkx_~_>RD*>Xd--0s1`9T z_(Ogj#Z+9FBvgO)C3C4Xxw@An4`e?{!@k|Zjc)$f)HnrC=Ss10{!Q#ziHM2)B*AZ6 z7tk5FU8Peh^s%6PAsw!L9&@n#+jePvUR(6uG6o7$trX2|=}3`>bK&gR zQ=&9SIi{(U28ch$2+>9T$ZZ-`PqH5*zj7pr=w9CV8)LXxinaDMjWld7HexisOK`%@ znbo>lYU_)L!3z*DWXDQ33cC?O#?lze|hBez*O&JTju zx_Ez>^&7*K#xSwVh#P35Up z`V^CMDq2{#AdGbTAXDn?SueSDiI8t~+e8dIq#H3TQTdgcui~_5a?E0| zY7t+)byPZP%u9pX(`BO4esXC{DduwNP+^-(IO+REri|VYO#1wBfS9*iECpUQg^1bArLm-# zv`_toThk)Q?jJH`-P&;^sbhh}JT*|x44Tc2GVO}uf5QekF-v1ftFcMMT;&*hiV4pR5K_+o5V2bdi32+UN^fNJV)>5%Hlc&QbgTwc$+j7;M#jeIGlb9u0Ea(6fxO{F0^ z{*pthyUKM^y(QK0!B{k#x*YG^ewX?5>W4T#dokYmifA*d4_duUg#D*ZgR1c}pso`v znLilqgPw!xtr4O$suD4HA4V}xpZW=V`u8VoX-L&R;sfchJ4s%*Wj%@B(@(7Nuqky% zHq)!IFedB-b;apHuxm(HRD2Hw?dJmQyZ!}Uqb+!!AAolwnxpCotPAs*7Kj)0Z&O#ho94`z{?@a^(^{bIt( zd|2^Cy00gGD5g`Et|y4)3awVBqVHQb+HJWlUesREIc)1l)Js z6YH9$VpM;3tnaCZZ%p%H=)TR+=9eyhez^!X|LTL!0z0DmcO4P)fn#P<%*&zHLb#_V zIZn6E-n+D)RNVOdR-#7pOEL$D7{i5LSm;k3sO|As-_#qAxhzEHa!l>q1l1m1fCI*} z;a1l!xckIQxV)e_n!I$u$2$@g%Ya^o=+f#FeAA6EW=2e+;#eta>HV;&=?-?_x>#F{kaAgKo9`(c8LmVSYvuU9? z=y^?u3AU+If@<7;srS-npx6HucqMw_cK22A@Pn_Yw0f?ze2O`+Zl3Vy@*;Bol1zDM zM6u#V=-LXE^7K+xw^s6VrszY$p^ks0b zwl^GD*cs)SXTaUMD-O1E#@Bmz0kaWbo5K_{uDGVWaJVb!zec81o?fpQYE&wn@nNUv zbv9xK)9m1yDB9|yi{Ed|qVSh6c+g(B@WL5R$MnQ)T`of82s3>4z8kKMDg9g4P%*S-VuGoI1(0V&&um(yotNOMQJKMQNC;?qAL^Y?3UKhE4f>r``tp2h@S% z16nA%#R@MxEQ1$=TGB55EwH-FVDYw=#}9(D6m!jcy3jJ(g}_3Y^5kGaal7Yth2HL- zzcFkGw|hF>$GT2IHWalHliET96?SsaaZiJ;7EbhBS_-D?+Thn;?a@5GM8pK}J*|df zHohG!2rnJU{dv^6b$=!8Ym=m?9I{Npq=}`&9UCznGyW43R#yu;Uu5vJWFp+{ZHq&@ z?tsaux_D5f501atRWyOIys_CmifMVUyWpJAhm_8gDM4SZsx;_16jm0$WSG>2w3%#k zE=?nbP5E_R?18Vlyn*cn8PLzh4sK8EgkM&Ugy}a4hS8owk3KCCF<<%GJg1no1KSBH z0X@jFsr1pSxW2-3b6=!|ZdQV;39Z)wcUFxvK z6Ze>B;+^d6(rwePL05Vy`SY=w7`a`~*X9GotUF~djGA;qBA+W$O0Tz7?5(P=P#o&4 zc)n#Y?OweAZ88uYBNqL}u=$=h&Jk39c^zKX9E3j&Kfw!+5bQtMNhz1gL1W4fJ}L%bC)0^*N??ajJN%F=-fvc{XRx>C@S` z`@wf;D3~p)hL~?RAo-~WDs+r+YYYD9<;d4Y4QR>lw!VT@ur^tpEmK}8X;aZHszOjHqQR$IJcn+&Y2woo9A6Hu{Z-B8h69ABlkh>@=&z2 zvE0&hD5l5NctL+jXR?a^o_Rq5(r7!?^02Q96-gfkiqeP}`g^jqVY`4h8ku6MlYYXR zt8+nl?;@<**#U1t5Cl)O#`ukGF{E^ssI>PS(}7|Eu5iI^Mfz3_@vDzZ9hhs4e} z5T`(8uM2SLS9A1hVFCSL`eD~J6*M-^7ct3vZQLoQq7M=F1a&5w6r(b#nA|elM{>P$ zg^+KwPI@L^8+J&ua%^@;vtx~2JkAE1;I-CKu;|ML*#Aof^)j8{fYb}KKQ=}G{X0ZV zDaQm-OmLWkV11%92|OlK7Ju0ldVDksuXb6V5mV@zG$16}W ze3ytB&oR*yb8KsO!9?AHbfpiH-@iqZ8V4;!L_jg|O$-yGgDft<=HfC8t6pWHA%+=L zZGkh!bcPRJx1e&^TS)0=0n*Y?>}K&4QupvS2Fcu2kE57SFDK!(b}!QXfJ|w6L@FQh z)j_(IwsU9BEt7^}nAgcLuC?yyGGdX4xw^)d*4^}lw)-z*(^=CqNPLMUD_q4QJd*4c<*!4$LDMK~oy zg2zk=zUVR-X70EJ&GRloL4pk|r!^m0t*ao}?y!hi!EXffDW>j&lh7%>CmBE=BuDny zE&2Z3Ti7tBwTNNTFwDA@qLQn^dRBl-;`pNZM|2 zCBtv4O5Z)_7}MdKSlQrI@&je!`DKeaOM_^d^13RQ_OO>+-OO&*Xno8pE*P z^Uv!}sH*J&H+7$ZW~T?REw}@in?~S~`#0dj{;i@kiCk$kDNkiYs+VBh)s84*Wy(Ow z5Q)k_ZON5U8KhBZjcdcU&PEdm*QCBcfCH*smO$Tt=P+jOeQ<2j3zEKtV>#S`HiI{d zm=NAkxtwDBpVFXfi9LBAMRPfN&L&N6og}fzPyZziI|v#vY)?xZ?~HTG5PA)J0-gnT z;QfA2Xy_7wD`!1}ms)uuW;$;}eVk$j-3B4^g9CXJK@(t>&>piRjL7M6mnBST%;jLe zC$luNe!BR3GNrK{I(4oSHoZ9*+CIJm=Re&A|Ey4$n;(K_Pu+xPkvwH&9LHRwm@S*! z1g&sKa(SRkS?@Q>W%Boqa*b!n0>d;O1nj?I7`E9k3_EX{OtQzdHS=Mx>MgKY_6A%| zj{}9dJEliIgtuM=qBNU0<_5(CRQL!!j~vOlNP2q07P-pdO=Xq-Y69B@8c)ww+tTq) z&*^Bh&qLg7n9K2?zydWICPAB>$D!<}3byX&2J@}`(5U?@koqNwnCsjGYANQ?rC>qJ z!ihW{EK@eb=gBp%jw0#Xr^y?eGO#EI+dA1zI<=K2vPUn5$r#ujcP&qZ&ZEmgSD8r zvD8gG2)<8E!2D^R;ttLF3v@bTiq`3wkXKy=cCWucOOT<~^7Wq^(-$=gF1! znPSd{y9@CR4kU*fbl(o@La(nMg;1sGjId*kVc6-(jy;@U5Z zz~A63m~_|1X;Vf(_F89L+~o_rRpCkt;L^|@?<&`5ls3oQftbZnSN+L3Ql_(7{xd>X z&Q4Djeqb@1lMm8F4D$t8_#yWq;Ij`Maox{VFyMY694^$xO=lKC@h?Ywaa#osJI9IA zY~*u1G%2QxcnM=89Z1?FnR55GO=PTLOJUCiH#zeKL`f^?Iup)6b4G&$s@SqOeWDVw4=z-f{}Z#ukSopE+DG&{8Rq#kn=8n!+)md@v26m``0@1vj4&#I!L%oo4-I-XjCVkFJxx5*W~3-h)4%55P>itHN$47ALsrkC z8N~S|B&uwX@cNwIzc4HU^-oMrMN8bWeHH9qSp+-ZYhm=k#V}ga3Ag)dU}#OWhzaFN z3!#{^Z(W3=SNf2U>C_z@vYhm_I3f>ESx!_2MWEh7`fQiVrTHgjRytzIrB``l}7H*tAQN)CBrNvTA@y@=2_FQYS zj2_ZS&*(%FuQrmo_tyTO7%*sqzxpo&sdh2g_t2)H)J4!$&k2oox4@)(V?<16J_2bH z#e9BE1iK1r5=r;8wDtkzl~V=_=R?l_pO`!6+F((^GWcS@4W=*E#?%(6aOAclI;Lr$ zd;J6vbB$wWQA}qIiSWG6nw%L*kF|uOMBm}NkV?Drn8y6Av|}dRpl9{q2F;YFJ-rQf z2$8`J#V&|!rcFmyr$E6pC#+3ufibR=M9f`|NuikgRuZ8g&6-ru(=%zo6{7bkQmF9X zElR_7f&Xo7#`bT6G_xME9_)nt722ppn*h$a>VTt+HSy0ud~Nn}OcurDgn%%>%$kf3 zktr{=w3WOgw&hc{7ynk;KH0x5jY-qWt_`lr$Oe@Q+aX{mRhnHA4E*eb*;*}7?nTpm z>35Q2R#MEh7bvWFXGQk;%am=it%Ty1hXnHx;lDBel;*YR-%5M5PZ#yNr-0|x3XqP~ z#GxaT;99*C&Yq)=EA1wWn4KK6kz&3*03l<&718pd7mq9H!tv&A@|xuXe*d0qPy6r9 zhDkH?Y&)DgG!yp8OJHv~&9sZ4nZtojc*s!$yHrmRG0(lkgJ1{61jV6Xx7Lcpx={y8 z?X2)%Y!8>`HQyv`Pb+HRJ2W$a@O}Te3pBgi0aHgNLuOtn%yMah!+OtwCTfm2*rN$v zsGcig{Cq_WZDXp^{XPipp;p8WWJ<%O$>lDiuSxRZxrkxM8ar?PdxvJyv>a@TFOwI- zj4B2AC#d1G^omuQ7YD$YFCH`v>nrrCSS(7jf@7{wjP#I)&`jHk+^3l9VMb)5Lr)>vu)O@A z7#0^`o=xNF$uO;>%y4?sIna5`DLC=)Pl)Li1zkP^UJHK%mPQ#O<_cHZ9g5l2#Y0#) zx;MFq^eJM0Cor zAdcJq5t^29SA7-7Jf)b8mpufV8Y>b;Els;}5~*-oCg|)~CTwiMF(E(QM9+qKo&Us4 z>S%$_7so-w$!l=&#din`3jqHZ4=nTf6a4acXy_QnyrY;m74CvfGb{4YoxXc2yd=lQ z-w|};&WOPjCJpn`m^2K-{Io`C<|TKd6Z|HEn&LccfBXa9Z}5YjwX{>uxzDhqj(eR} z0ip?frI^cSKo}I>nsihOZcFGla>Dd5(EOMtIJYO`SjZViu zSs`MsbBrOy?Aqxi>}zUG)G21;nJkIMiJ?MLmtB(oAI5YlV8wC^R29a+*e~?aTIUmN z=;HtLz@58KV;()40$6C@E1X!RkxsHM%=bW5`C zrzUxqp-%ocX|Ck*wdvWx0@tQR!}joM=)CY9TvY+8zGJ6dcDa)l`hQ~jKC;Ap$A&>^+pF+s%6oA1v4^Mr zLD*^8Q`q&HV{UV4{3&LNho|5jYe(8S%aq5>42X^83?a8V*=0(8r+g0#H?;SikJPMSj0?>KHQ!v`OK{V)Y95ak!2A!7(r#m{3 z-qtj0C|FNYe|!KbJrYgWp4ND*F-v3TP1dr%FNI4@d!bQ$9L#S}!sWm^c=Rj~<~{bK z9j-n>X*~ZuA9AIQrI_cRr9%HKI@r0VOnJ|8i@fOAR>5;jSMg1{5ySSh#>Zl|r?HF2 z`6LU>^BoCSgR7yi=qGrs8U#?|fpKoH;YH~(QJRH8;(s%ZVj2#32&?wl6O|q`?fUE} z`Py^6<-T4$#l$h@3pAdd4AXete78iLE_B5g*T=%$BPZZaYjrvU)EB(=xZ<2?@1ZuA z@6gE{GnZmI%=ZxPCfbvM-DJu;wkycH+$n6;xbpg@wO)SiWeIKvfCQ-1^Q%} zqVdkju)imba@eV$^Q~A=N?dWlp|21fz>l>}eCu3HF(tkpf~JQf*=#OTmg{87!^T>Z z{66bMmxHx8Z1mHL9!~p>$$E_#@Vq0|&X@;LV~>KxTQzJ~ItJ2ayJ5jCHN1R3O;p+n zj#)-A-bdVpMS%`v8pWt=)RuRf-it&(x#+@fYkC!Pe`B)dP5XU~V!0e!T6e^UC$pe_ z>Om;+P{kkJ=7Oz}J(?GOg}9B}fhyuAu!dsXwLArlvvwq|3$2RSb>*aTk+F(kI^udG zX4Yd5Jp6_}7E=s+SUIqYX5GiT;F>3I`~Ib3sIVE zzBWY^v*DnP@Ug!GS=?Es>=3^KeC7lw!jBq}8!3at1Q_-p$t*4Q&{WX`5>C!S*VZoR zwQ3hEy7Eb$?5zoxca%ZXkn>RQ9)rdo3i0(gK0|UQ$Lyh)9cO;JG{xQ|z)YqLpVAg8 zZx4~zKZ%m2Ck(=(fVtwkCksCWhH{MOtNEe{1Y9%+H8T~6P|J{hTe%eA!w=Z5GY{Qj zC*Zp8<)SnlIi{3iqSR9*dJ+?Iwu4Oh^yc`A-j^hD(+}O{48xvRSuV%yl*J;3U2$0k z@#|r(_-d~P?RPg9*6nx(zYO%S&G;42P;ZI>xz^Zh{z5tPI#+YdF^XCEqNU)FYf2(| z(dyN?zRItohDqCm*eMu>S(=Thhxm}sb^(??%AQxVjA+Ji9?*86k0D?|YdpBn5q~9( zlrNm~1_oTb4ZXdi#axb$+yu^3Ov>GRLO%taeP>UjgYlOue8>J-UU|IQg{6-&3^M_i zFTnORJwyJA%MxHzCfH+K-ck4zaSN)}c0|2_svvVUz_j}Px_z1O zV4EGWpwj$m8v)#WXwHO;{M{LR$5fDf=7kfq_Xaq)C~M<+F4KiT@4jsLa+T zq5U-R-Lp|?>JJWrPH#aPv2_##dC5W3^DJ~!#A3fMfjFx@fAP@en3oiTuOs>f4YwnY zDJI3qPa2~8Nv?NhFxhy6uMNYn%zK8JHN;nxX37ydHZ^{(km{H7#nOVZxj{ef5AE7Sn>6`tY?7ztwNR!CvLBKF( zEt5rQ6xKFqNn@QKPM)ByxdvWY>H-zpo$wP)DDR@xS5(?4zBalP<1b4R-VJsjz3A3C z^0)-PHr*>fJDQpSefm!I&~bflQ&-Ty4Fb#^A!hBW8)vJ`xGYAcc^+!GC&Ny7}fac!6hFr~4Ku4Zmu z;qLSIQm^`zFl>7bNQ*KdcIzO#dqRRP$X$*h+!yFZG5MN4<-H2*NC#b+a&4G}{IhhA z5V9jc!hX+246`(50{_H}F>Qw}H}r=?Bg!D-(nnYu9|@|Ve&}P|1v4fM5S5k}A|BE< z6qDV#jS%QyOGrx^7f^|;P_bSw@r^tATN<`D|CEL)jY;Evwij+H%7f?nZ=iSs?QT6= z3kK2z|H0py~iz zb-yoKBFC)w(+MA5$%Z=vkS*O{c3>;YbJu;Oqy)j={-1fwg!C-PrTVx z2PdBAQI3wGqSAsX=52MjFx$_WJZs2S{)~7nHH|4RuS>1{mo$x-Mrqz(?1)QUo#APd zqwu}rG5j&c3ruJ?-%aC;5V!FQ`z(%$q?o7sI|>$mIFp?pvX#qq)1|v=>`Bz+p8vws zOXI~ot%Ez4X7OiZRD?N#LFsYW^XMV;zvvHv>wto4{duG2etd5{@ZCJ`kqcqC{dZ9+fSeRdQ6@E1T2;JAw*5GgHfqp{^ zZ)*=0*XBDnfe92-Wf3HNJmXBHud|gZ4aXHa9n6GTYcETf3Dghbzvq8r*q(O%wJi?! zn+qLxJ_AcP65^6Bnlg}k8{^CiL3Sv6-}k_N3V|8Il7bCVxyY;Bk?Fme~cH`MytPQ(76;N7&!@33MJ%HUAEHfdxHG*n|z_$ z;U;n>&ErpV#67L>0N-pHmBuj5?JV&FM1bm`KVW+AI;g5QffxCK7@DVpS;Yw=<|@am zr4by?ea=>XdDu#>2y2kM-lHvIShgM8 zp_wnhoLjaFFr_g}51KESetQ<&_pXICr#`}iGz%C};Eje3E$~X-I1%F>E-LK+#RSeC zC|tKA{A2z*q}%e;~U^D zVwlUpq+#a`!!&U=!+sy9z_96MfXiOPOFaUQ-}J)`-Uc}P5$~Dug)8kO#VkMDTcAe~ zvHy{+-1t3NQK6RJLY@?2AH6FQORVOIMN3P%(i|x2sk3ik5}Y51D0{G3xF)!ZrD5NiwX+mHw@Z^|)&xW*LS`^&X*$pu_>f!6N ziD2A>pw>%c{F*RI#2nz528!`B?JfjlN=Xy?d!C&_(@00$7iLv0Bb8*Zm~*>qrVma# zx(HeND7z6bOhaoL^BiD^=^MsC6aQl{|IZKLDjf)g1Em;uwLNaAFd142W3U;P zx0Hf&x+@+kHo!ec+(l{LMu-?~idpOCB^Xo_^5|K%^6>Rcx&A73Vz0MQltyo9BC-tP z#?)Sx*U2!fga5WprWp8Z5%|z6?%?Qe@U!`7cvVNoS8UZsJ!^9j^POY#DQ5O}5H4r{ zf!b_kT;giUgZ+E^9*$l69~hRUT3Qv5a8yry>^gHMXkV#>KI>JnNb}l5|IRRc>nxfCXA@ISfFA7lxSaj7{#BApnpco%FA0b^A$fXO^wt4w2@5K5oB=axe1A1(29;sAI(0_i9|L+q8yyINUrj4#DV z-=gp?3`qHzY~}ix9V9L!Q!>la_&0`S-m^MsmJ;764a1bW8DKz03LIQ32Zt>x7;}F% z{K$1hhe4gNI@m{)<{-y}QA`@$1;}L}d8e|KHq)Py8*R>&pZ?rk97$n+ZI+ne&oIXu zCgFtQKr#HlFafQNuw5p7zrjkdG5G-#3SuDX6T$1g9dN76k7Kx{MN!O}NPD4|9umok zY~`8L{Yd&4g%CBrn~152nS~G3{X}URF$sC|kzqQ_H%5KEB`~5;4noxr=+}P$+%ZQ? zHtmGo)cs&lj&Xy;-*Ys@%qwygW@x&S;^W!MyL*!aotk(d$>h2V8?eDJtSX|e^lxbx zW^6Mb?A^`;ztTxDwe{sduBMdRf z$4$gcRTTpS?-1natmJm3OS0}s4* zM;}`)0TH9lG5Hh|Smr5smAVnj)7i@0%tb=&{k?)p3ms9KqBS$IVLUDK`3sY(9VD(z zWwZ|_ukM6HXC;Awlf3f<5mR40Q>C?M}c;*;mLOGXP+o2g)q;@vT0;Ne6Mv zE{b{P>n4n^b0>!>CRg5x%y;o58xvE@6EF&yG-A;bmBzkeA~Ig^v zpFVhyYZNodak9MfBPokM^w{NiP}J`dtXtu<9%?X`hGFv0Qxga@kI67kI550D{;t%c)CUS#5OED|Ac?$XxPjZA>T94a7E-E=aoFmUIldy{X@Jlnq z60Dy?IOh3$s?IW+ity61dW8D8?{X zDg;G&lArXyS$6daiN@Y8-vbTA!hcp!#=0dmO7l-l%*~ECZvPDM%Q*qfe|!PsR+Hf3 z1SxiMHo&S}UicryG509uc~>I53iBjRRoTi1j`if-*PjyK&sRlh{)uV!c>*?Kifw!` zZAUw-?U)EvA5Va;;ytWPhyj~LUU)FW0Dm0y7EPdtZ=KI6rt?onLGh<2X?`?Yc|PNp zBr42Pc>ba@DN-Mbv6E=|NCs~)!7!{_0#h2p)Fv9^%x4*pS6%_nTB+cJr-LB~-LT&_ zBV6`^uT37ue4v<8Q;87e;zcYg=;_(LuTT;CNqC@Q`7ccUa*nBq=9rbOI^%@b^I%1* zlVA-RxYl4a)YZD;%}(vGh_(b_2f<{H`A#w3XFY^4OD}Rx$X3qvEG8;0ubdm4G)0W3 zCYR>eyM@?@u^%^293a@DStoRaMG#ki93;)Yf{)=as4nru_>QKuRG2I68($kW4>}Ze zGziL@USv!u#dseip5I+11yw4)F|02K!_-(!Ks}#e?AUxBM$$;sqq%yx^4A>rnp*~& zu6zNtPSfD@05^r?G=$Yk3N=vepcU0C2Nv~f!S6){kCF6%8 zljgrM%{I*yyNo1uGr*^Jmw`|BDws37IhvXbg?0As*kq^?);8f$4j+!`KrvM-+=M1O zyvU3L*~-|5yX0G6zm!DAWk?uCZ}W5!bMFL~#$snM5*nC{{^g4U-y37Y#bh|v;uP47 z`vGdIBOuSu1s5(eMzeUnr8o(FmfahLhj-icZyl% zSYqUkKW!tL40UdA~t!hohk z2Rr@?liOrGhR1WvSUWnktTnyI9Lj*p1Ipk}A1zc{I2BF}COF)uJsv!2CSuxgX(E`? zY6FF)H)vNYijiS!Y3Kt#5`Fw&Icv>QpO}EYv|}=p=D#t$>F!E`=%DDp=KT zCOFqSJmk zQyP=Tt#un*d1Vd6G#r7kpPFEo)nh=%7O=F|02^L&%m6M;9L2O<;Uknk^CnIdlaO96 ze>g%-UU? zf;-q@Mi!F`jALp3-4I$W!_JClR<6rgh$JnKC+k8K)p=sA0 z_f3F+3r^T`vLQO8@QX(lUz>D_f%p*N$0c7hCHzq%$q-9+t$>zo<#2$;Z0;7%hf=uJ^T; z5gvpya=0|RR73G``D_uR9cYASwbsMP(nHYXvN{fVHx{m)c0!eJozN(P*W$k6n5`63 zeZgO-()1(#o3fSpp4a7-+wVw<7v7XGX>wmo!{W$)V^~+K?o~z@uDTKqIw)bcU32tL zONN4MXN-StfPb#F6O}feZ=L%nMr}g4@KVR0tlF5Z{B?Vje5_Unl63xM-*Ag)5yPZ8 zJc`Y<87KCEV$!eyf+6<$SUxugtU~sJFsn71MW(>UVUDOi(-0r6v=T8{98*p)Dck!A zy8Hdf@D16@DX-3w)4$AxhQOziM$Eg?AdHLVnB!wYX#|5~wtq9g{AHQ2?8_mz)>#dI zwa>1A9ujE6Y`<^Atj8O)C}vF#6t^O{$nYjm8^d~6WMaiMT#j23KE2Pe{!H8 zTe-DFTi&7Pc}dd4j55~Ms%FJBab_`-hGC{msgJME&1PM#l_>&V9bH47fq~UunVQi5gNqrZMOd1vAV4CQf zg7q=uaG4?$OFkshAWIrX-`#y{_>M7vpYng-XWoMB=+PeapWj_K8M9NsziH>Ufp4*2c+PB^qp4i`){ zamS8Xu((EwlA}i0>lnv;;|BejVy?am5TXhK$R>&*uMd;-#LE)XIfqv_I{ zbFx3VM=_D@cMB=~o0ICBDiVe%v7UxDPl9o_YKn+?XU#FMGXt@Gy&g?b+z4CSm%-$t zT66%{63E)>Oxu5SM#)YdWBR33-WQnLk_qm~#?Xc2v9c){)6IT79iIxZFK)st3Po6c#t5hF>n4f#9!KLApWNUrs`mCiHwxYX^`kgMz-CaHhSrJ2$u1SehQmKIp~H|ATO z9^TMi2Q7LXfHnC#c)wf*7nDw@d7=}Z9^XsERC5!srI@$#{Ds!l{=|l2Zf)u-q)+TF zn0ISQ8ZoZzLeTqcGV0OsQw)gKW|Ste;_-<&k_8!7foVbU~WqRqp9W9F>X z!{v1wpkmB1I5fH?ekn`_a^D%f+nHfN?+{U%kRc+*n_~Je_7_GT_9dfN(CFZs&Mx5_ zvxF&H$0Z5E|BmtONOuO^w%Bg&Ch+*S3%<8%g~!J(g8RFrbf#fvRO{cHD~(GNLNR%T zK|;k4KO!v8R^H##mpE^3DGzUDM$C6}O#1W?bjjyROGppLT=PU^m{in9ulNGmK2Hv= z)p}T2yAZtI_QjK{%y5=I-vt6WW-!J4^b8Z6CiszyvTSA3^XKKI)4!FwT3wUaw}};% z_D@XKYp%4Yq+tA7)fVBg(aVzb6@#Z=sQ^KWSwhUKR*jN{xk_~heOc$p}`&O5EpP<;_h zS}(y@tIY9)SAeLru6%7KQOwm~U!h3Tm-Jqet^BrOi9}`PV&}0-Rfy+wE)B!PY)Hmk zd&i2cCmS(^w+t|%s0dmc9)(J}Hrcl6@cvF;O#0dd$x%xY6B8wxz$}W{y&zcd-r`Hv zrO``asI}a8jGI8ZbtJJj|Hd?~O=-yhQJRFu!5Es>7Joh33Q;QMux*S1zC4}^Re5%} z)uRi3&Esp+hGSAF=H8f4p}nymDO{AToUq2g<=vGKmnkQ^{KlvRhW<8zMht5U+G-_@ zG@UL4iTnhZ>bJq6Ul&7uo)ea2bi*Q7etNd&m@JCvKQc_%c+{74Uzn}*mFOij`!23CJCOwGDACeRZweKgnXp~ppO{0@`nYLCF{nK) z1+6{p@W+cKkW%G>Gk%)miQ%Q;Eup*JUcJo0HT{ z9AmieZ_M+#T$+Mi{jg9+7jHh=1~-x_pjk#+yf4iJulJ6)?m}18T*n=#i5#=z{}FcH z0XcVJA5S}qq|(wxR$5Zs=f19x%C4;Jl^wDYk4Vbuj*ukDNs)92&bbD~oU#rQ5*`PT>bdmW^UOS9XNS72fs0*fiYH$*$#_y1o$(<6gS;n3Vq65F~ht$?*78R2!e)4o|Z>3)muV@IVS>$ z+aHPI$v)=_bBrTp<-O|uQuDuIIvdx=W5RY?qU|U=6isln$x>J*YmeP;(pD8&{JMM4 zPzh5^F?TLH^O2@!FvpZpOh|Y?;Z43j z@rtC2jq58~v~j7@cJc)oD?rN@o0{<*8GOW^1uQ}k}7 zfI%+palv;d% z8Z)S;Rn8$X)uRvVeyR9{F}(PDY=}XqWHg4EG|B{DPTLDNY5Vpzm8LjTKN)&Xa7O*3 z&CvfoUu>Roqg7GNiOGG0fQOxlY#MceH{r5m^BIEIQqe7LU}o=WFNa~Ljp+82s3x!hmK9qmtgO{HJbHsylhYz?2# z>Q%omPHw$_%^OyOn61zZbNZ|?-fxlz3F{8SU0(~VNACz`6+7cMp&6EI@*_to$7ps| zSF^v{N60wtPbwxSiq_Govef>LvT-Xl2vg%%I8~~sta1SrriKLL-j@2<(fa`0)H()E zX^pWga|Imj=#GyUIAO2h{HSg+LQ+$oVrX`gAm;g#li@U$BlV83p~(SR=&1EFzf5j4 zuatkQVVI2lM%aGmeyDrl01RJgjv?u*A+5J3{?tOBOh4hXnm_qIHc@;Q*iMjd)KDst4J1tFxv5xNO>NBhNyhl) zNIo3$Jr3C;Ezm1y4U{)<$Kb?+q5(j_@bPM<)Yb&qph&__ZAZ7 z6vuc{%%eAh1ZV03qedl)ejDnM)4My#3~zsx{ePHO5wu;)+Jn&dXECfBYJpYl*FnKN z4@`Q{n)aCBE)Y0Masgk8(bFC%cxVKW(&35XfzQo^{Vy65-|2OKsTnu4&o76r+{M*+ z(FG`SK|{=|a~wSWEPw)cOZ1+<4%+T^!7Ag{*iMr#ox3@vE5+!#_7gIS{K=r9iK5Y% z8dBr@)92Zx3Rzq!H`+fjR{tLgkHRhP16f@#>uuycDws;*tZwGtoDt)(&_K8?^@0XgWqrZ*zt-(Oa z1sEomR_nc(u7u|23ZdoPCU`3}4W1rvi!U0r!Qe?Yk_$w07Z^t|y;FJ%ju1c^^-mP% z9Bw2;`kaytZs9;GJC2v;&3|EnE`(s=DSbRxSO{l!6~m4dP4K{!bs*dCf{RbJ#^bsC zKFy9}rcsP`cz?lI7C;R9CW$hi@rupxh6~cXL9#ddkCT`tZ?7f z^^m>P1$WAvabtyxgmDU!)Fe?%hgKoN?5P1{NKbmp@!mzKcx6LUmpqh;(KAfB2UYXe zCS4md$bj~_(JX+@-}2$iSu6ZwVLAklamLl-TVrTBpEr#;CXHhD*6AyJ*9;&|-Km=8 zJ(Yt)ni0d3pMPPJsL}pQP0Fx_XpnIja-$Bz!zEUDZOD2!Yvh9AKU$(^Oe;yvXl}Gj ziivvJS4e6cK#q2$;XG4p$j|78%JKze|1W0Xjruq`KOf@gDsZu@6<&C^9?Cko;DYsS zu(BzSfjYunAeUlB-0Ck3z8gS}cS#iO7U;-|eLfbF)F#!eg8%8iM=t_vk?Z=D+c{uN?0G=1XDuRfGnvc?kjGA z1vwTHW<4L9^AsZ}M+&1${K*slMA2gCcA{KnFPOFeQ&Ph&y7n&Pp2jdvP`$;RzN?8ZiA#Ks?Q7fE#ijU1=ZnWzZGjw5Jq4E6y(!Mj@))s#wF`WW@ zLI)lEWwe@9ZnWB%59@p53*|>h&qxIQ=%t{)T8H-j3Wa_j&2ZFS`t)74S<3MU=a>f+ zv*2rQL8o^Bxz;IB+|a8XNtxC z3*6;K`#~{VBYF!z5BibCNMkuJq>r5Jl8;oZk>EQg}eXzCTZa6>K z9F1p9f}}s2BA7Kr3o9#0%@=MoBZ{f>X{^vW-;XqAuHO_4 zy%T~JIy6@;XpGdyW5(K<(iytzeJxDeQT;+x|~BsJIg zwq`{!OSgp!yDa?3b$O!rZi88|X_vk7^09hK7MwKWdYELioL%$LW90}`ed6lVt!|P| z8g_g<4JWS%gX*;U_}2P5%$bB3xV{Lk%@|$G!V*$BrWwUJ2Z_R_`wPfWS)%wNcWLqX z$=^Y*;|brdNU4j^%L4O&ceiO@w;eTVnp1 zVW2sZf8t)_i;WA#RIDizrj1%m!s%jjT)VXBiF;77)owE-yHd@ZG*R+2hRGYtG3;T5 zjg9AaEu8#nF+9uv3>PbC?D~lp^5~(JkVI=^Cp{LWvH1(*LoqoTiv&BH5u}qdeaH{5 z0Qv51#CH1_=}MJhm>TA3wK44brq63b9Mz!&j*^UK+$RdH4)nrSCv&0n znHP+1HUMS>YT#RYB~-m}Ls|+4b!PXM)STj&o)nYud~@ObOT7tFOc&GC;;}8wN!2SY z1v2!*oTKSZ{kNuU((8MQ5clb3pYIRLBF#V zu)jkQjCw*>WfB3$-|C~sn`ba||1Qa)D>-H)#k5(pQy7%roqV@Q6sH+=E6N$YpeXI~ zNy%uACnrgm^nm$jH8@O~H_T{Ejn>%aIJ?m;c-MLdXbLT`dAB&|RMUWVnEwiQZk9@z zfqZ&~Q%pkNbipJ#grry{ik<=L@GAJ5@=(cQCA)eI3Re?JF%x?S2nBP3$U>?{H>4-noY9sSOzrV6HJUY}BsFa5 zWNHjqQ(+>}y zjq>LGo0Ia1T7MfGX0*Xo9CN<;EF?a?Xj?ZORDRn5UNMny%-j%tCkwDfw>fs3Z;Nj) z@({%gz6va(nB~Rwg%0yNlYUf9LCCVAW_=bE%}9w-vfDwG3owjI4a2ZY$hCG2abl_x zEKaY1#AViaHF_(&?PZ47B24houuIa|4B(h#iWxR?kPzx0NbGGB#WoKriV~*z7L~Yt zDr6Xs=G@aN`~G$ThEe+V!U0Dc;3$t`=yD|&UZl6eyWgVV+)Q219$ra32uB+xL#l%fnq+T) zwzS0VF&aVqY*BN`1)6eC%chv8>N5nBIi1N@dwPa`xKJKy`bB0sY_F1CLNcSVdjV#& z+8Etly|8ESH>f_H35~l=2c10)@zd8rXtv$~$DE*TkWTX_ym*e;Pci3Tv=&yk?M!r? z62+VEisYJ&jEbV{@&pxzP0xQ~*x0OS@(G?{2F#cm3y)@-;R&DpFmbRIj;m~rddb1q01-T$;8tHg&nDl~PQP`(c9dkWQpY8~X0~ zN=G@X!5C%Cz!0DR&uFCks2 zK&)5*mw#Ab2XQa>Ew{j!W%k%ZmtQ~J<7!@0%onwG!oBw$$Y$zkk7n&AWmabewFN^7 z8=F4MC!<>0zdem%##^f6+N2$zyJ!gk> zGsgD~t#Ep!zJ%GzG3o*8YQqN&7P4YGNYk@m5)HY|oLOk>HR4|wKgZF(Rsn`d7)6^0 zUOoVK1D1lrCtEcAv>uLjH$|gkHfZqPTEevEM$@O5XPW&5i{%~2u_lRPajQ-8h$(9e zCx2b|3&XBd*}O@&`i)_4Ynt(D*xqO_9N)SOzHDiNHfOfM?RYa>zuyk`r?itW=lSiR zDa8z%9Vpm6^Cf0x^i6vHdg7b^#>cOG&EGH|I?c!0Y8d9gy*jwqKNHGc#X;_nCK#5v z6Bb*V;q#OB=y8sJNeA+IV@ok}I(8Hqj`JnnM)afb`BR^A_3uJxw;d8@#=FVL?xC5Q ze`4;Hs$=K;-EgsbEu0Ux#$!FVf%jlj+Wx=}gDUygS{JUSCB?`GbQPv-M>0sC2Kcv` zsVv)Vt=yEc;TMLTq5lgrWK4Y=xa$B+Gh79pmJXP=dNtU4THw%1GyJnI&%Zf7OuFUp zpqL-$2MaeckT_^3iiIvk!nnSfvUyh7((W1dX0r4Y!7#>iMx*U1z7eoj+^fC@czF0G z2p*RLhcDP*SI>0FD=@)Z53TW)A)lVhxEi3CE9w1(2`NYn>(J}&J?+@%&8hUreFkwqZqyDJh7`U&2r_8hAeCq@_6V(K_FL(rf>^{T3kH$E59bcgv@UaP` zm@ZR#2)etGtoW`F%}n|io%?W6KG-Ufuu!Yxabtg-)B1cIfqTpPNkM&z?ZKER55vdN zJ@AI96|8WohG^4=(A_ZrKh@bu6Els9*%v`I$AnPK81-Gk-M-Oe`e%hWCON%${k%7z z9BeH;vV!^qy}3h{3LTM+wJ zqbM$Sz4VaJFzgKNd4rZNpa&@S8O7AFbK2FDTG%#bD6|tNfezHAZIU)Xd-axhq6@7O zr#K;D%($8eikUsFw6NU0Bgwv}5IcrsLSTQx;@914{&r4dYS>wTVOYqB;k2HpAuj_v zU;3*%^oFI{KjA?5RXFF;4v*HeN1+)%bq?l>%^ZrE8hWD8u}?Rmepey3IIS%D`MiFS zT3U*<5yW}%>G@9#TLq#IQRR!afn)c*a4NJu8b;@U%?V2!V(o~Z{kcP5;+Qy!sqW<^ zXdUcM#G4B7+qdDxRi+!|_Qt0qHEbhb4$VG1*b1#u!!V2Vop4F)EpTwU2udZbrBJtrcWXpG8Js?*)r>*2G^m2+B6}w3o6W4|8xuOuYrgkcNc66Jv+0A9YKBL%!B>O02 z^M<_?vQR6AIsM84%MQPQS!4Hu9lZ3>5Z{_MC?Uek9#QA;N^>5G7E((LK`zc6}gbNCEP}vBF?b!`0UNyss>WP|OF-5yHy>eq{27 zW)>vq;u8sTHEhZ+47;;Y87+Na4@}#vj*GVMg)ADZ{K?-A+ud0K0TWDc0c~PCJe{ z&pJZFu<6M#ES7^UHY})5zeNq`9A679Qx-$UA12uNaSpt!(;Qz#+0a~q9uj5{$2_B$ zTccYFn<_ez4-`{el3P?0&{tM!V;~t#g<*@$KQaDSHL#_k0Mz`~!9CirzH3oBSbm~u zB($j3%z8~F%qWg|M=|&FdI+ytbt3AI72^0EPDKOvnUI1jA-~kHsG-^zHg8xYWOcX} zhDV7IO%G1_xlK?=T?QYQS)gUQAujL0&jN&FzERAK(PM-$6FQQTX9`h!bfGdR%E-sp z*s(BqVHkdB9U;X)F$}vMjIid@lVOheYT!nTLYTW~9jH?^je<77mJReNZ;~nEB<=z& zIYv8>u4!|J3R4X_kp>jgw&8m6QfsKpsrw0OdNQM_)G!Pi8a|< zHp7jsY0&ewBQ_dffi*#VdcNb4kcJckFa3mWUpkTCrwZ{_f0Vlf==eP7sP}7ZYGYV% z62q{V+tEMX!5X)H(Dc+&Xm_MBuIsZCG`87ecw1{M`57#YO=liEXhAXg@7;v0ww=hs zCkipcZmSTvXS1MqqD|QJRH^Bxw?HzQUq6mvVb@nTsH1gm9!x)<1V-oR`}D`n&^v$@ zK0RcCq1NLij4JjNXAzx#AgO~ii!iz$jr8Pm*UeHCUkZXTBt8TrP)|1 za7-0;z1C6_S8h51M_;DHt(%sZ(liCGq&2~840cyXW3LzL=B<&A9L6g-hTW>O>u%P8S*6A_ z_8aZ!w;y)SNrILajd73XIw*Is!OR3>%^7U2JLlLr1AnhV9tRsdON zhTFrp!+mQfj96!ZLwfMI&XHVAKZ>Dmj>4;tzU0vbh3H$)PMN*goP=(OlTMv8G^Qep zxm6jBg($M*3x=^ApoP~giXg>d17x2y#|J4}V3&;zhS7&ghkpFsvkRY|!zm`CS+H>8 zKu4l>Mj;wo7bpYWm--AeNRWbInVSE?Jm}vIljwo=(i$3@7QGH8eY3{f78x|>(*kc# zZ-ia9a8KL7F%u}}RL?#_c>Rtl*lM2D+k z_MR*lf~%l?qsAy|ZwB26daq___-T!5oFz}8Yo;NecsZ)8pfHx0O zoJTRGM*@VvZ5@cSQX!tv(pBmfHy~AahY^qWBax|L7#47;!epBAjFr7T>fs2>e3-Uj z9ZV>0gmSa3G#9rCR{AzX^=~`|Y7V?IolAwL-6= zm=#NU2u(sekbVX9!z0pJ@V~N7$nI(_wG?L<781|Ys4&Oxam<|?T9_XrfZDfB5O~lM zJ7=cD0OKZDHpB?y-|~%M1y_?!F(tPB1ocE;GWHXPG{$@zuLvuY(n&3eT zzNYo!nBx>PP3$f#-a^+jIyNuIdkIcLTfuAM8sVQg9t^_*{8?HlOI>uGszWcr@*wR+ z7AWam&C9J@VEI5htfq6Q&}fh}Hl`eNkz(H7q4VYvl7kfUlo-qI*aZm>%2Nv&MwNe~ z%8Fo^4}@csgVj;4xd)>1Q(??{GyD{k0S-W~R(qObK~tXTmB=yW6mvPxPbjiPqMc6< zx305g*)t;r->WEPtkllGVQWY7?xHV{O~)>n34@o zKdpc`T9oN^au)1Lw8OQ1tkCcoe<|F<7n_$9)5i`3!^c2GiaBZDOBuLJU8z=offqAc zs1~ZG~pqG=b^nTDUX98spwHM#$!C+5nEJ zrWl`lU4$FPKrAUHw@#)qDZZjG;>92-X^E++or1*@WBUAsc|3*gH`BA=?jNa;9A}ER zvNplckf!*ovoRi~#WUDtipY(o)`g~HAMGq0b(NC^2NYtX`ugPb{H(&gyH-mWmhAUm z7)Kpi-O8{I4%65TxBIRDAA0lD({Bf;TR7nHYD-+umxn0ka~G&fG1^MH)%eOu+CGKo z@$=8Z6rIyT_m9?uG@KhN6 ztu*o9QwtTlcEZVHsh}R+7{@)@05!*K@!<;#9M)^7gvt0T|Au1h{A9v|6k0!RmqJ|K z^NUYXeOD3#Z6plK_cZ+3T}oa2CnlU|;MPV5;L@9o&}c8cu~o|ioi4W6|ByKzj^RP% zdE97D6yrKPP8$H6Xs0ZaFf2)yWv{9-Bw0ckGa6IVnqCJDvE2#e zk1Xg(3p7{_PlwiN%`kF`K2GmCQBo7nF>VyokfvZQe&<7Mw$SN0B;*M_5Ur67wjPz~ zNwe_&!l=?pS$bUDEM8xr{;WFq$UPmx+ph=bXAN*sm$PtHzX9e#1B{rpOTzeaPb17| z3z`YdPxz37=?bx?dLv95Xe}SPYJubeVL>#9oo)md?c=1cwbNcbrF>6T+s>u52sEQw z08U&ej~TQJj;y!ED;h)b%6%EGKcFjhE7ju|e~K~vqr&I0ZC4`CP>7<2286uJmGAtx zRn9z3N-n1x0mHCUC&MtKv8q-Z-8aJ=4KsMGze{fXA{QR7(806w#v>`0nqvl1O!XrlAzuKJut_0a*3cC1Ra`9s z$9SbG9b1)=&$7N*lI-!Vya>?5PhPky^%LZKH^39U1JG|&98ql94W6YHAUv*-FdEzi z!YHQwyZyqV2p`foTOn?%PACc36UQ&z!z|M_s?=u0@Y@=q|<^TSUx(#zB}NgA6CTul_k zOn7G^*uJGVP+1Dm{?Em5Y>0PJT=xq?7|r^wT`hr4PnMC-Fs!Q8&_VlP#ZG&#kEV4CCoXFQBchD zd?W~ql>$=*iANFX)R-zWHXLo1v6BM|B6u@6Ju?K4Obq4eBBa=PqxIT zlcqweBNjL@xCWNF@#yX`eCbS~7+0scf^x1Gxk|?-^X~lOn1t_zftk0ZG6uB^X0X~1 zEb(8nlw)F>HpAcv7og>&v!Hjq2|j2%1%@v&#?haj!{@&+Q#oc6#dN*5N@#zPkO3R$ z8^NRsdFpk0Wmr!qQhD|7bvgct`Dxn#`|aEW#Z$6iQ-}Ka+FCUb5ihJNG4 zOg;>mNb9L{3|nm6yHrE#F_XY$TQsC^{{}H>}W%s+b8gT5XKx4m~`vVH3ngZ-O>m8)D(j&9E%E z1>V&+LYWP}Ail+ocA8=yIJ*h4ramNesX}xcV^LgU5+fVFtW2tzqN-=ZJWYi$vfu>) zZv>iSe)j|L?venGZ|T`=(QGivXo3MA8uT@UXL|j0hAyL+I{H(Ey9qvI^a6!A;7*)! zScI||FpWu#H0LVTaSO!f*U?+Do{M9ZK^IMBtkw|2Fr%@`Nww9mnvg$cYUBM=YiYc|7I^lp9tKUyf{Q1c z;e~QzJoYk1!sv6OeW4ibD~^Kj(2IPGP>7C8#*8aIySSn#FsmEGu&P$70!^$s4>Owm zJYITo&n*LN*7BW)i-eDu9k!`;va>YUFkEC)*PY!eNU1x zNg-~X5?GuXdy;5cd=pB#_rS2}lcb)-m7k)}<5h%IUtra=Sm|W5%k>1#(3_794vfK` zCYMn&c6L###xW4k#UB>FG%sd{+c2)CKE>Q0=b~KX;ZC%|72=f)chO+f6L~$qTSct7 zBinCS^-=aE%}N@v;~?wx%{J+wd&017)*CR4w7{+Jhaqt?k(b#llLxHuEIQoXxJWuf zbBr0qIPDmq3@?)t(}fDLYqLZgHP@4dfb3UF&9-R8F;+;Ey%8{@F^uO_UVye!f+rRY zbbuNCM#4|pUNmj-4!GOh7$2{pJ&U?jN=6en#-3stciS#3y48%Nk5h={_akw3e|vK1 zv|KLLx&5o$6g#J}jexBJJ{7zG?a-HRVB!^5cz57^(V{zH5N6p8FC18b^_-kBTb?Ij zD!4Owk?Qi$Kpe!}Su?!`^IE+}FcRuhsfHmc(wtDok!m)@|`bDFM; zH`rNBEspYchEe6(NbbId`&l&e_|N$&-kE-2P; z8zf&7xV4BCIb}5=S@A5@w#JHQv8ufcqcz_g2M>vazze(KzM~=5za9c-LM^ak4sGuE zEJMO1@iontVzzkK6Z|f;B&%Z-qWaG&@qBiE(Kzi)87rsD>UFZZgRG>mB)ryhA+zY3 z7Bcxk@v}0GBHL@0GP9We5+-!rZwx!9F;8O!XkWeyMSVjN>?1xw;Qc_Hy}vFH{j2cI zEDHu1XG-U^MI6(IV&pn^g<~JQNqoFQ?0!86{QMWnOUj8f7=~5t z?Uw0?+K=zawWeFa%{d<+rS4%Ech8pw@|a*zy=#)u3OQyd#auS}TDbVRHyJ^VwkS*M zb#eN%YWQ$Y$r=T);=rm^fXy3LKdtLEJ~oCPHPCNmdwKrni}Is2Ik35xJ3es_#Cyh0 z_~q(d33G&x%{Yp2>e1V$Z(9%YX@)}7U27q<4B8@hIan$+reU}0Reifj1!&n(omK7K zc|BG-KqdGO#Ja~is2Sus$Y|Os8tbB{nT?;Ne!h*UDMODk`(ZhJCHE z0<^7lCrV{O8HSxYdzN|P$`$WHK3WU?`whYsXKl#LPshL{{us=<#cOoE;AeqF6tm~> zVZlz`joj!%&jQ2!pr5I8aiOrDuLA6%i*5u`^-;R5v9Vzowh_oax4?_}1#tcTAz12b zgqy!?g0`1zaYN`GIBhdYQd7V&Nfgt`CrQxJ>`a`x(p!#3+EDBkT0DI5FgbGp)wX8+ zj_)_Dmg<(wSgCgR(nA$6XO;o%n-L2cy1E#1u^4h3eevXKGt?MA!(@KhQ!%;M_M61G53G>(6S|-K(><5SU&g(*|n<&JOiL#<;2JR#eSIgPhFf}#w zeny316_r((ua7LT$Mo%>y=^N**3-aNj}C&yIzU_dkI*Y%hJ-QU^Cp*K3=G|boJ>EG zucr`iM(!^56O4-k@A}KxV#9V%R)Cga*havNrot@!qXo_m%7JrD--6ai`u{moX#Y?X zE6lHf&s2WPag1XMDCT1Ojmga?*42pbz#OI3woH6d96S~hQ( z(LS$nz*o;!g4Wy{v>>24=IKX*tCcyub^jACw2zn6 za`{={JjG;{cnPO9WaQkn1hL_r#;|ePh@z<@J8%qLp;h&vYh&0(AgY_Y`uS*GHN39BZ=JaVrQMX%5Mq^7S z!?0@C45QnX8;vyz@Y1V?HMZ?wW+rWgWTcHJ-Ls+JQD=0Q(?$V%`F=B(Z_*DaW<;m2 zg}qV;IdLXIoUC!Y==0@{aIV3o)*%mvukFpPel1LEVAQ0L+m04*ch%4H?= z_O(U>bJ_*t$6QIxI*xfkF^%Sr7e0LTB)g6$h{g2Up}dZ%-0-TW)G>ysiE6~vup+0m zF*;*BacV>sq%RZUNNQbdVn_SmG-!rCLvMhtEr0i%%#HSeV%9vEEmR)$BD2mWh^rKP z>qPP?Ia(eN*mjpDR`HS7BJe^V%5J{3L0T5jHC50b#bg zL3@NQu4%Cgt}JPZGdj^0)*+iD%r5>$pxcdZ(v8dnyMFD-zAFjhDT{9Mp9k)e%5Tpk zHLMtYZKL@t7(X6#DHI(8V0qm1zLw`I_m-rRnA{v0w!^Dlxtj%h|Qx?_R_7cEbc z{3$`a*Sv92=yM0M@oj^@VVDc3Fl@hJMw91SB1~Hj8=vlhH|hG`QWqE^as41Ez{L7_fwfk`yW=%zKXUqnL~aRzl-s zcVcLy5a;EeRXPnjs$6w+`2VXW{e=nkH(CMrT5pA{8HV`h^(^q+)ePsK)5N-UxeH`+ zOizkgzp=TXzSNyGGNo}g5Th(@Jyz)M0($u_#N5*c%#GF1B+gwogR8AynYrPBED!@F=aI-%@ zr_s9Vs2q&CY)kYFF6Xf>s-l9IyPHQO_2A?h*MTQpDkfB&+wKM%%T5@8GgDUx|YX6X3JFQ zKGG0{E7>rC)=MdEsD~!!`PEQoj)|n0@GDlrzV|M~fqL2$ug--(ch^^Hf3A@*tSgDi zXtgovXMFK=Oe36mA{N||=^KG7je%0z3iIyT;a;USPI=0WCUQ&+#ROEi2`B5hkPdX- zcs8?9&Z)j6n=|X(zc89jBc!pJqqz_@kNKiWsxjVZl?++7dts)RF+S^;3SPSQ_=6rh zY98_H2WuXsx{PARbdd`diO$63bAtG-q?<79=7&bNxV@#jz z_WG^`jmjMOG`l`Nc$x(j0d}~~@;i)k=SL2Ij!CANJZ+hPQ=G}=R|#TS!7W+RsiMMn zLAKK2mNllSq331R$3ulV>ccV9=tdCz2Q8!-y$5uA8sfFeY*=1lhgMEnsPTyJH-|YU zgJSv>wHLf{oypaQ3F4C`No0xH&O)EuYRPB}!#c*yd;f3Dz4!)byeSDj1<^OPOGfy0 z*iJBSW{1Zn>0;-;+-TqV*kn^oFK-v&?T|KP3x(qtjI|w_vH^lAbnJ|w=KU7tJ zhs`%9OY^2DH=2@SRz2@1lrCyb7Sodrba|(o+)XL?Ps$?f6Iay;jbYfG&4UHq@N76A zn{Oeec&P<_!QHzb^f#MeURp9-NwLM5hMG9WiMv1z$DE`XZ?#TBJ6UUTfu3w!{7U3e z`}X@dJ<$5q1&cKeV%>ZghJ6t*4C(KSgBF=$yX6YFn7swm-0GpRMm8Kwwa2n%b+O|Y zK5w4zc<54!Ils zwo<^G&0Apgd)k#OJ`+lUn&ZMVYUt~_Ofs4t5AD50F~ z=HPuFsi9LL@9d|-oYw1x6{QQ2wGp+anL|~kE5RY_5V+HE@<>gl4btt=z55Ty*IO!K zp7MC;N{Z1dCBkKgR-`F4T2*HyskoW0jBwRe)*PY%##k)xb5yE>+R8 z(^mt0PyWWRhEA-T55t`Ox)7t5(1x}58sUhAE1+-WRtS$Z#An;z%2yT0aKzd-@TjjK zsj22JP(v{beR>O;lUoqwdFp9zW)&CN78R*QG!V*r_meuwj?*O44OF`GEb04(eS5NQ zrH_9YV_2`z@P2(L;;zNGYLh|HxO@3E-RDmzMLTD z)jeJu6t6CpCv7TXnB({6W7S}gzHe9)ZuTYpqyv4+neKz$OznT~d?8r>8!}*whz{x$EOxW3=_A1 z9y)n;kfx`qBPN@k3={3~6N;`m!KaTWVCK{Y*p1M-s=6(4+XY(6z=~fDd2&okig~kl zS0T|iCmTK_h#u=Y6xA!Rl@Y zCsR{u;*RfcTE$m&0!)hH*tVo?c4 z@AFl_i@QJ|#pEW(2%~melT>|$xYOW^+{su+o>a$QYK_b=%xJ7tC39$|hV_&7Xd}bx zrTRGfX&4+BmJbRm4SaKXCFm&HV)$uIO!6<5)O_cd5Q>?(hlV3n*%A|7g*epZjlA)w z91_vDp1`iV`|O#ARrFY%X2yGcvyPYy!_?%Cr}5Cq-QiGFCXBQB1b-~v1&;J;C{$^H z6Jz=F>a@S|Zz!gVdSzk7W^0;MM=^zlf_t~^veXHif2mPn*x1y@WYa|Qsd`i4hIn75TurxbPH4V14K(~ufnvNN`t^>6OQTxh`mR@DZPGdk^H)iu z2#Og#rI*f681Fi-nC;M@zt;KP9&2+;oy>dn@{z;+%O zbpJcFymz4Xyje~$aif|Dho9My9k=LN;IlrNb}UXvDr+QX?>B5stBqmZu^Gm(qYUHK zZ17lRG<=~Uis6H`@ht7~`$^XmyPf?CGkvy8n7{JYQYmJezN0WY-kzMJS3?2g)0Arc zHYrcGt}kJv6`HDH-LaV(6^4zC^B5~^yIuw>W*0-ZsCsy2$6{DQ3uo=Pp@zHcxTihf zM%zL$i_1KP?>2TM>_mcir@dp5M!*EpNBN03xzp0QbR%HXvo^;5J0F{AH`?IC)F{wT zI|<>#3~=DEco_4#1!hcp0}I`@NopQ*7s#QQ_p#lC@1iZ~A|!~f7oAeZTVEuh4Rqv& zmuU6m{{xdY+6ni?#Dk^zA&Ak}!yZ3Z0ctwqf&Q=HW&@7-D@m5#wyN!S^c6f7+mo|< z6U6kf#`2MWE*AFtJR`L+Cm(R5u_oLqHIbWbaO3hBpc|AA?Mv!lgPzGSXhC~)4gU(8 zVtLfi$I()TWC=4`RturCl>_OzD?!XRYDAtyyb(Tp3Y9QylV;o6e_=u$oG>_k1gvvE z2X@gq7)y_aeJ*(6%vWFGk2LOS4r3(DS&G?EudQHjWKSM%OArh898i`{>*J&Qcqgfu z5Q4_9IHt^K3C@k0A$65^Ya1_3PdAt5*f(wlEWdIDoDXPY(pLr4Yvh8f+El@39ey>W z#W7bY#;O{G`=0h>#g+u|ey42Zvjjic>8NzsGwl%R$idWnF<&Bin$W){6w|6@5M8??pee?EoOD2`EZquryJIX;1cdX7E0x-~(h5lF&C)77$| zj>82NW_YkKGBwPhYh%(^Hph^vDCjcyBKR0+<13TZ@Vv+wz2Ce6_ph0fr_CHE8SNRx zTp0zz{$=)LXl4SfHFS`)3UgKZ+N$}eFxkWYjj=l8gSUG-poaYv@SJ}X(&&|H?{TX^ zZDCvdy!Ip9w&(N4g=5}P%rU>V!rkfi#CUsx7<%*_F+4S|@a1twCBv|>VQTLAaW%SQ zxzX4r9lYHh{pU`F(y9_jsi%&QTvx-XEuPqn#zm2(JP|WtyrkwE#dPiLE_~f?PfDn# z#gwmAE*ZT;=DamT!c4G>`GsM-C&T!!j+f2?e|k1WVZs#Hx&Al=?a;<_`tjcQqzhU- zu7o39_`C_>80{W3N>%g~yn5P`mvr8!Rc}+eB-#izw^#kbFrzUw|HK^5X^Mp#X2G{J z$Dq$EZG13w8O(E|axX9Jv?~z{X~k({H1(lTB@-)rq#pAvdSP^-lr}p>1|n(_)QDtz7Z$u@7+G zfE%rvV;m`FYhPDEZ?FRiC`k}S+HkY}sn^0PtGHikY8&lzI3F8!hGuGZJev(G=o9O5 z4P87F~ASkV=_qU}53!`VGTN}tZZFe;<5 zqq<5B!|2oJ)vW~!;BBP{DN%a3;KmZT($g8+9(fHz!nvC96Qr^6qL@;56nvuXN%5%! zv1FvPFxTH%c0BHjG(Bs38pC{0uchWeQ?%|E4;tr-VaP!p{Fa;mb1mCp+4!5#`v@N! zHIC^>F{||DLSd!@*-Agy*V`8m@tC>t!PHZQE+%|zN(OOHQ(;0*#7iF@SF3H&d2=*$ zH!p;$AU&MvxE!`0cg0f{uVK#c9g@-hl0TohypLAHkv#pPuS`Z2D2mWre$-pJGQQ z({E43{Q%+Fu2foy{E~!G8BM+W5+oUa#{@;&;VGwukX>8|KUeBu+`T1GL#OAN5wAhd zl8=oUS2LVq+-!*ude4s3r7kdXf?Hu(=3&{~PlE|_XcdM{&wpYz9MD?kC#`k=yLavcd%MkMAFS zavY`z`KG%`>6YMM)APSD1sxnP`b8|*=O2Qy>3ZlkE)o33w8gU&qfYZZn3_)he$AC46jFQH-+KQ*bzINBpxA#6EYH$eilT z6T;f$kQ!R5U`}toru`QtbEqw9T26+Y;rSrGsEhK!Ns#E~jOQABhKfk;Y2o}VkWMi# zo_Gllui259jR|6}osEST!FOfF?kh)0UF`Q|6*w$* z#<6cd!rJcK1zK=5Srqd_Aj0c@_QX3aL7d&ciI5!-AV6WJuyh3EA(^_G@Z+Y zacN&=OpOX-v6o}YGdiPZRlIa(rL%QVp4(_L{`flSe-pw zGN*GPGnz_GZKJ8w1p7Im#+aF)e!T$x_@;-$hOGkk`p%e?@)2I#;PXbwjaE)EJMD>Z z{eUewO4X?K=_TwnvK7>NSqs^>f+S4pSHvH;mf%(0NIdQH+h{KiIpWFPk&x_M0Pk(I zFuDuP$^Gnx7Jq(#d5`$1(~V;)C`SFUk8t6zEqS;qLG0biK=6HgP!>_W`xl0J8pHHa z=a>mC7SS$p-q?6nQ}pQ)19=UUaK4QWO)5`-506~1<%Q?aU?Tq_NaL876r=f6CLFM~ zC4tEaV&k*gg5kY5LG9kOUl^CA|HhQ=^TyE*O>t7ne8|i#fyaTmXxAbUy6kR?2Ufm< zhC$q+M{!Iw#cXOP7qXArkg3$6Phvfp@9xouOY0j*n4O9kRAIu#{9TQHl|44FkA+Ji z0z`kLhuam4K)&7;kKB3#+7tLH034&%lLlE(HL@MHWK1gkDBLp7C+x;`|EjWz$?xZO}Ui z)ZQ(v0)HLVjVY#$r;kv&-j+OPm=B|fqn@>(cF4iIHm0t@Qc2C;>wd^wfMK%R+hclM z40NZZ+FZtJ;NhVO(71JbEKz?4N7MN#kj&LsQ_Qk+L^!y{mN?KgEh4tQP||p~x7vA~ z!wj?R5FZ<7<9}l;Egdm0d;~ljTLdj=QO$JMrEtg670qr}fkyZJlA4BmdOA_e(Yk(u z%Mly$k&aF4`D28$%TEZI18qrp+;2>6HPZ%hHKbc}Y#lNKB95GfXQp*9X2ddh|HK80 zdq0P5gSn?^bBr6sB=z+Z{QPW*5%shJ<6YhnZ;$xchMtiviR2jDrilNANul%R$GbVO zcF7UA^gt8ayi9=RgIqDe>kW+k%+G1vxX}p3T$w8u+D@hzI&XsJ#F3X1-^)tQnUMd& zMBMR1l^QY35l8Hef=-13RM*v_3A0Jyz0M8a#nG_RWgH`Nj6cQnc}Y9?1ltmCy4VDz z{*>(u%NNe?cat#ti(_au=MP*4sx|)Y+EINu=*L{*Qbtw$tv*ZO#8v4f8aW8k>9vd~G`i?phQ>TB;6O zomN1*`EF>q=`GZM$1x508G0baI8@1nv)^qIFMcp*}59&*=RZB&UL|;9jl-soKMeXTum6o$Orif)n{nj-y#}h@vyPa zrniI2_Jn9Q zVixSCB@TY+2BncsL2_bW242h!CX(nXIJS209>N)2; ziIRk5b~BTZp=8SR?)_}%Uf2EJ_jmq*&slq~XYIAuv~$C{J#`)oPPD);7Q{i@ zlP(zZkKt7#^E%Hl%m#w7S=*O8Wod!jBNO-^rwY)6+w}$ZWU6wOF_Y$ZOz;{e&6jW1 z*kS4t2u>)16|Gv}-7^zFajHAE*#83NOgtnk+6=ZgI|#;&bLVcIF-K}k68JioD&#f1 zz0A3z?_Y}+beT!xD*NZ61zokqcN!Lex>NyN+ZH(ELjn{ICRX6kYv9hYL;7cED4Spg zo$JYkzBNM|7m;ea2JOOd{T8w?uIMk!@6ssuM(2hN)(D6I_3|PRKT^kAzDptCkM20H zHz_8+!9LFnCQUBEgsYR+N(Y*w*#zTTwMmwo^P0R^+V>wA5AS&V``)m!u4q`ctdR+9NWh*CzuM95zN}leYnns7AT!y zJlm@v6LV|sZNi*?NJBr*-=%4mNlJI(7J_@G45SBI;CV60@UnS#99n)C!uGMf8O$(M z1ao+!h?5abYeq1ksk=qDj$A2xd$Y5EDSR7E9zOl2G`nO>(`p`C;jq1t(BE1P`t#JW zLCcj8o7W4kp7|W^KW7KQ3WljBn09gxu4IS>nzn$%(`x_Znz9ay9)zv&P=20DO;fwF z5Xb8D!&07MzNcGbmrcvzWgiZnd{M_c1}4DGuCDmZ*5@#-C&S!hm>PmP^b9y0LcSY< z*)~#D7W#3WNTrpp=zo1T6r+?TAjJmX>JbfH(iCuNwFaJ;EQQw>d*HzvY9PImeV!@o zAb3kK^6{QrV5K=4Ge3df(^Er~am|R+TTA)~jtmi0;MYZ)-{kd|G#mc3!+Gr@VPabu zJRs6o{78VzTRrfX(Jx^@F;jt|4AVp~E3X1~!qEa*L=Y7?uv@h2`WDWlbKd{NP-*5B zvqgJZYK^DmEP!E?IT-q|CB7Y(088h(;H#dm;qFfdY9BM5YC}|2PS=RIcQxkd%-jTi z*V&Ee?Ua6^qQ(sZW>~}DD)9T>Y#U;Y)r=z{(4B+TV_M+2#$-@y-UC-%ehoK%hK3s0 zccViv&t2WQ=ey0(k2%B_sHt11c=Va)qNVSCT{O$NOre!3aO|2pj^AL5&CU&g?>psi zG+7lJyR{d`1P#LnvvNR3#H_$lc9S+C82S9koW(9PbSFH4KmA-?aq)n)SbYg8Rop2O z=Bm4sJ{wxmwMT~pi)l8BlL*24ymAfCbG`TCxTtwJP%{ooG{X?*I2$$w91_=jJ}>lm zlroGZ!3-YUQ+E0fJ=AS>0xur>2k-qlNN%@kyh1V!3H_dx#F3>@^|K!q2?=vL%U0&7qDZo6-$+BHO!t9Yw|Q@IWrV*_Wbxn*c}XNY zp1cUR0AG7aGVCMB0=;&_caDsK?35GY=;)RTgM|k2vZENgc97!gWq_N2yp2PCayIkc zlVDs2t@LQC-wO?yn852=eg*x*PsK9|wdDD_>!g?vTQ@w% z$_r{PWh&O2I>8>-STMWX2G5QO!UuaT!v5+D1&lVUv+*UEONom_7q{!8TQd{*v?ayl zJ-p)(v@lWdp=o-xEM1HzW=e75@_9n!w)`c-gp!cas#oSD6H*0P0dmMM&w;#=jyO5= zt61;w7~%BHWGTErg6Zbx!L``X4uuni&M)-j4|oh$Y<4ylm(`O>ZgMH4d(&4#ifLtv zEN-B%H(~N#_yB2J=z81-Hmo0thcx!XLu+qv{*Gh8uxTWe$`=Z4K8_4Cj$pPs7|EW@ zH$~1<68JGqc8aGvo`~bmM$4Q}4Z^!RtR&A+cnBDJDWrSj@JfR7PxivvcUR*_hi-$K zhBG!e=!E&h`Y`p}URb}YNNlJYDM*7ECX8U3&Zx_dw6Q^YK?&p?k3twR_kj5RrS{^M zZ+ry|t+SbZSt{JtXuSZ{G^zqYnLTmf5Nl|2xd?18u7n-4o`C2f!ec+*g;IY_VQ<1& zLUJC#SOr^hsdw$saWCRPF_H)> zaB#62&b+l)rk}6|Lb7dPAh{vTJTenkEzrOZhdK(F9t^XLU<|Aeczn2Fht_vX;3uhV z5LfKUl7FA!D(sCCQ(l=Mr~thY+~_F5uH$;*oS7Z*gy=uT4Wll@ai`NBYXqyS9|F$Zw?2;wg(ISC2Y<)o1$;?^2HP%B=0g6fW{U@fO zeY{|7X4g%?zSCC0w4<8X-|#F9*^&u2^>y)#T{9u_;t^rdj1@%uo5u^%7>AMaclTxY8u@es?ao9OfmDNZn!oq1fTkIG0YgPhX*aW1>B-cSmV?R z8%&izXxwo@njs8xgJ3ot&EQ&Cc19!1q`YXQU2BU0=g3?L&|-wH&&Jcf#6sg)s6!t$2y^KeLi0aEWl1$`A9fNRm8s+6ec4c9NG4yBUpT{jCzv$5Nt|@0En0G2 z$`|fxCf6tfbWCI{r_xX>KtInLs%+6{EeDl`8XFH)f4nOv3?vs+@#1zhpi+1eMvrZU z4{Y26vD;Y+Z#2WS3{X`W)g_h-3bjX4@_80V-avJ|oREI?F5y`F9YgDEs$xmL;Jq8J z+0qa9Zyp5PlFx9m>H;{=Jqr~L+W7I}Tv*Y)RFGyn!x#|E*P5|h{t>xuuTF8$j{e7%a3;ipGO7jZ3;p_FLpibI+pC%Lo zbi4&mj+x*-QBPslyh{Scf?;e4M!(3In|8n!t!R?+S`KgJjoO9WijE~RdV0RdXQyZJ zHgXX7F=^;|L-(e-Muh8wM#7RY&p_VhA@uYpfy(PTc=yFKV112U3glmHH}N@*+Nb+g)9C(q^UIYyrCHCb+*&@#HWf@zkBHJ!g=hB><6zCDBC`@wr~xaKC_~#d%hQU>5COAGDzT;4Z0x<@9#%4QjMb20fPl; zC}vfUe@pY>Qx9wwG6!sp?!xoa&*7w12^{IEjg9VYvpLQ%6A4CR;V^E%J}b0P zFM%(Jb(2?)?C4SJ=YxL71Rne6qU|>Cje8rA>WA{D5Z3h#EG{XBouu$`LI4jY^{mLE zn(fU@f@y6qgDcjzMn5!3;n=-XGPg)WNg^!=EfVMGmW(62V zN-)>82XUX?SR$7W-X%ZPmMlgE@^yQpM;aF?pK$TCj69x766M64T zL)6&N)01AK=t1zSu?ZO63*T8H!nJZSWcPgpvz@QP!JKl)J*P7y$&DajViF1(f6=2f-CV#>X_S7N(p6Vt zyi5>w4sa$1@(ZYIdmgq%mV&f}F^>6=59zt(f)(h=E`^^6rct{O7d_4rU8$1t_Et}1 zp&{!;sdJ~uGCH$GQ(~0mqe|yC;uywfdy2tiUme`fs(^!ga-r;|5q_Uj09kqLSnJL( zszXT;c~@WVb7xDm^QM%yTUI7q&99hitH{WlM_#z;un{y&dk%4L z%3)EOI= z;FFlNTP5L&QRFFJaw(kNPD<1c$*7=tB4-75mk&D~lo6_&Frc{g#a!ql0nHv<=Tm_4S1kmdG zOi+QJeQOQ`gXYI^I)%_-aTnNjY{Ji6E7(A zlzq*y=jeEl&8vo_!5g5L{uKx_>xmN#Ka-LX*5=cjN#jZ|L8DZ;QOj(Q#$G93`O*>w zj#{U%>7)uYkxv^jD;F{h^*Skr#sz$ed*W6VE8*>21Qr8NL0x(ZDC*xqx13(swxl(- zQ@JTfvz%doV49yjUO4rRGa4H!<;VB+SM(ZtMQqk}tC*I-Q4Ezv^+F<^-|KHok(nEo zK6nSFL~&PX=;4IVg|PG7afq=r#P7jt?nZVq^u>`}1q;gBG9nfeO;&P1pB33Dt7fd@l zL%;;SST01M=%UdIVtSKSVq8EK*T<*9ul-7_#+^`o$8J`6L3 zU|c5pa^Y2^=GH{YZ&1+yZrFEm`GH(<<$a<8Byvk*o$b3N3AO6YGSH~wiXPqvI= zi$=O4OsW}%noi~3P>geiDLyyn7{pC`3T2-Y;NzA@z=t^Cr``v^FP|N2*-Ql@3FhPe zE?m!HmT1j~c)m;AdikFF%@vM=QV`vnM#%~?X_R5oe?cx3YlyUpXl{*SXvRaiH@_}gD9K58U0(#JvNiC|zL_w?@+`Q#A`dvc+6tn{ z%nA%(m<)os*k(4@xXcXot&iuOx>bqC=5~_@nSJG`v7tR46f?|~sQ@kNQ(A$#cJ1(( zvMpdcq$Te7ZVuQ7U4jEUyO24NN8z#uvjS;M1$GgPWQIL=tG5;E@IIdBf?kOSrzXj- zZAg?+j3MbGpqQ@f7=|7MN=#ncR`}NbHL!7y7T!5=J6xTX4@og*_;K+S&|i34(6qzM zxjjTMiznD~pF3G0{U7ms(e_^Q^J`MXeJ*#9E2S|R`M)vy$Rmzv6A!>9;?2Zv%L4x? z$KX?|b~xDYFiB9d@Wao?>rWEQ&bz@}dk=HutVKT07I|{dzP-f*_UitH5f*Lpzoi*C z+6Ig4PD4XMYg`|?4X(D5L2r9AOu~`ySW&^g8>VSR1XD30jGOY&3^}zUvCa?qqT6#v z$UU;G<*6P1-W$4T)C$l=qn{_W(1UbM@yy6Wq{yN*4ou$x^RteF3z*>_`TO95?1F%~ z!}2%f1QU1EpHu&%6B64>`DGs#P9pD0To!L{)>^q}%Dwp&6FaIW)*9Fbd)H^cnkr3v zbnq@%b2t|sjq8XHcyEX07Ec6B2$SX-!5k_c#w8S(qgZ0o-j{hPyfdGOi{%r9MWaLK z+`HKcrB?ke%@@v_oc;+yVr6B#2%A_Df6br_JA|~yE+qfCh&(5nnPv_AXd3|&#W42> zX78~kPBYgHO&TcWRn1)ZLVvlq{CYEmkM9scq3sWL72;{sLMwfNiuUffE`JQhI2A^C z_r+7*?10F%(`3y>o4|f|d+7Q+O~7O`OfA9qwCpaM^oKsOpFpPhc+3Njt$MP`olY`k z3NOssRq$+R!6n7ey?N{6isQ1I;aTdBA-X&pE~Kl#jerj@*);$kAdTkgt-OSA_a6+? zKo@OPAa}~p1dSLeo7lMt#)ftlJ4W>tFt7%%ByvY%azt z4;I3KEzDJ4%|1`{VdSBJEfYBHu4d@tIw`-?MI!H8utBaEULmJ7w-oc1q=cwDNcVCU_^AccCNGBubbLm7@Cu&7@EJKi>AapC+~OlEvyE+;byoUiE#XpKNd9Ye}Mb8 zo$&Mob8gF+O>0ju8U43&hu4`QufyaTl|D)V-!vg_-afhDK&3CobZ^E@NfJs%s0z?D z5tT;2v@=fYK_1^EeK_@V50goKq3~VX5U)%Lg!mRL4*iBLnl-^_UfagKsWe3c$&J9- z>LO?uH$#q^XXLb%~Zi<*flbI>h>x`;T#?%+^eAHLCc(^9H zS5Lu6!5pY|Oq!7dqieLCbIt8bMiY`?O2s8{Q*yj0!*R5X`p^_ZrIA{t2xAOrEeFL! zYq{fxq6^UKQVNXUu7REICBx!{X)vLq9oGB)5zfXr2z&E0Y!^Z>BPyLZPSpyHsgv@h z_8#Ibugzt9$e1?Th)KOpC5GBGilH`*rtr3#Jc9hOC!vF75nP_q8UizGVdIxR_&8Sv z*AYwMO&*)rS0$U9PB2%VhZV{!C`M^K#}WiK?Qy= z6^J63(>i3%!!l>|?2MHEqghA!vhuxL*|-^E`rS}zs1LolG+C(S_!V=bt10d*e+VD8 z>ErjATgg<*47j0YjGf9-0B4*QFpkXFNC;;8&edFalOtMmO3Lpp)fW$4kt9DiQ1TZ> zMb86IPfEtsT^8VehU~UR_oiJNExi8C1!$pTgvaKk!?x7j@IKiJcYmJ?e*KwE3un@- zC75xVpX@jA@21Cd`DUkWy$2?1qQjy#Tg$Oa(r%?`9vthfv@v z4uQj-mN-R!CA=|_Lp3Q|EI1?s<9Wrx-u%o--=ceC>&fjO+8OD%N%{Ss_shDkYa>rD zutoIrq+<;JYtg=SXoWwY%7Y=(b@ArQN#Op+F)*|5i0{5HhG``w0%jfCn@0q5Nb18$ zj2+NXg4uOzo_v@n6h)8ND5F;3cT8v*QD_BI=(D@D@RVT+SW<3)=XTf#J9{34l-up_ z!r>gW&0$HeT8613nE8%VxGnGO&{HJkSH=3sFWXn4#&?l_VW_MA`=V(%x#1WUL)`ZG zdGH%59CamJbVywQ$+$^{`ZRH!Lgf zga?xJYM0JzZ}iy}SCe3#_ZiGxx?_(fjh6C~bz?+B13|V$=legTSv8Rz1ixY~?rMoO zI_HCXCw<(eYy;J)4fQ&I#VlW?g>!nz0r~6VA>L_l!)G_Vo=PT;rODy_RED|3FlGevz1kHfB7ovy4Ct$i}pKahC&Z77*GbW*1FjAKq?HMd;pqFvA`y;kHgee z%vHb3F!luFX&1uXCDP=tkn*2W6rzvm9c53iUX#)9hFSrt0&7G5ElpdpC;e>8K`}uW zJNvAK1FsK2K^qHPzPbQjt>A_4W(vb}CzwN*MswOTIwP@E%A4&-Mpw&pWve%;2+}Aq zbkS&goO03V758a>b$s$hA(+T@@fekL5Z8Mr*bcD3293qgwv0swpRn%+5zO?v1G(&v zc4+ZhDgRcx3Jq0BLv!Ct1r_)eqr9zA(@8Pv(pGq5P7xe4(88B0Nd$@vohuMq;ff$q z9J~9nAk7Mf@g^AevjaK)h#iXEKyK27hh=xU800>?<$q%CoFtPIPV~e($=07Ls(`2F zI(V&3GGuf-2=Y)%{9^qH*dEA2Lpp5H0tlugZX~zfsWUpbNy@M8V$U6F?k5XxGn4yu zZ|I`^E=}3_mUwx@Y54R+2Y>#Q3R6HH1~0N2B?Ga5`V zW`#XOrN)=Jbj|?L&-3?1Q(mK}G$%=G&$0<}IC)+hA244BHhXtLK#Dzn-Mbh%=df8r z?(FUvN-*Dw{kif_b|^1h%0D>MmU~dV0IBHg{QqL;-blk+W7)$qpqZhKuZ$tB*emwK zwsD+0OfM1QHfBTp3|kx%DFTI?$%qoKU@Y#=3 zU1*QYBc=QjT~}Fmblur z5b9enW240|i3DTG4d>ct*dvu$Byk<>VCombVtdYWINd0!v(bP7WUD zm_mPH(&Q4%;|hQ7^-g=Vj2zMmGJkM+$N^E{x$FPH&|~d)O$#TO9(i)G2jfdjp$*ug)euady@A}NP4?(2k;cBMoHO5eL*%^ZgMj(f z<@j9%hON=WHhD4#pQwZ9o=yh++55q}$_m$PlY^@pOMS<(MSDvy2XX?qQ=A>T-II8o z-%iR@He{Z<_Ao&9yEMOJ0>g<4^f&{%Pmp6xu@+{MMGKQz;%BA>a3`AWO*4jRBABw; zk=&a>cIYe7G*j=*vf2q*T&sRfevJ+()1%`@!K3o)_KLzaqaZzhQjC0PC^=EDi*3j~kW#E%*j5ErF|{le4W z4(U~U*Vzi2ww1xNQuf_UXVT~p%#Z#eG$*g#GhZ}`yqgUaFu(52@0#Xf zOI(dRJgn8#!PNuP-~gHTuw}9pu5>7b=AD@|t$z035X^zp;hbWMJqq(Cm|Ncqm!;^4 za!+afr!-2>Mqi?dmo=V-)7rYYUtJ2kI0njuwXn23@y%>B@k{bn?h0S#*&wzz zjs){&@Gx#{pU&tKxe=Jwp5-hxOu%u1jx3|e2S3>~Q^5_yJf**0Yek{=bCPTo4N+x>{$TKO7DtW8tsJ@(s?-I z@(=Xwc&uP-)-#MJ!HkZZ#W`=3pzDF;Mvyof+z*v13=Ss>(Lq|4KruAdNio+Hq)Fyk zyb$XgG&=!ytC2@H*OFI%4w5EWr*7iSFW*9hlQACZV{jxdZb!Cd<`ott;652_&- z_Tq!jz&Bb|(V#O*+;Z?x;SEU|exQLanvndu2Jpx{mc`wD=qqF{RKpdGCfNAPLYUDs z2)x$}#T)#~pid1O(`L#vEs$W&sRnQ{(_PW!UQ*s@N-f+^*sVx;lP(<6G;&LiHG21? zR={xx{wp-p?Rh%1oVW?1irV0_kCR}y*ETRv72|@sMj#)DuxLN$r;Q^R#f115HTZp}$WmPi<(N1s4aV(9(mSIq2v&mm_<1FU+hhHVN)!tVZuAUJXunFqmv zQPDL4vy4d-MlgGx4dgD_VwBaIESkY!dC^lXu5sD{Av#FkCZd>mJiFg`p7>juS$ZnC zLpcd++v?$qyJkRFm)%g{CB`AIcEXx?=BI_Sy_rWa`sb%|nTI{lw^#A}oxO4L{d{x9 zlcqB9;y%NL@$D2t_l5@VWAA(ZwP?D*&tT1|D!BC67}x5of-%NRVUWHvPJLAjtt*(< zSdhV8s5kC1X3H-LGejM z%6Z7UxO8tGxhCS!*hPO8C($1EKRP{!!jWcp@40z+;^Y8all)k|^*|4(4|y(6&p#$$ z`Y>ts5KPw#y<{4<`=Grs@qA|CVu~mHuEJ`d)k@VW<3B97(kvT#Ii!G{DOq zv=A`$Y|-)wCRL-ZciG5pD8FYsA7ikCyluNd5jE_SFeRRTH#FQ$bJFzlq$)rYk|s^A zxNM%8{9?OccxIdjG5USryxt4Q(H)DcB|Y%nQ7lc=m0^kr=5X0o58IR7(A4(v{Hjmm z72O_?vfk@n!c#7xnM(v|l$fu1eS}yil_o1_ADkM}499lpfy=+%f{hMO#OG{uF=tW$ z#kX0MqmVT)R}jp{*I}IKy(t>mGM@jiMTgH^`CP32^1PVNRi}?_QB9+n!qAe%f~L__ z1g%V&@Uc6#TJA#9dHr$U@|RG%F;#5b>=6kLw-C>E5eo`^h+%FJOx?-PoK3PhN^g|# zb(-mlrP}H8i}g}5opwzzsT~-mQL$Kvawsdh)a`U}Om9*)V%G)tZF2+4j5~wgoz}Rw z-b7H<-zH#|Gt2{mS$?vF8-C3OwS6q%OKrA7RLODl*w0=pjG-o<=dI4}*rOx~R|hW^ zG9DB|!*(C$oPxul2SKyLE6{G?3ZBGqT6oy z34fd?K@h_kV%xl(f~EylEE5)uy6V)X(Y>KL0;&SR2bV%viwsyFQ3#6+p$mCe23*xf?V%NT%z1J1)(S+%fe{TSvu!N{Yo7T%9GLqB8^evB+a z5xH}l{B7-IVSKx_<#J)s=&?rIN|n-tw(N;loNk8s2hH#Zq6QsKo&?>NHR4^fI%3@o zOJQ5|4gtfn&$HzSG8y*%M$ReJ96jJ9d{f#+Md0&SqGMGl!r*3#q3KnMp$*J5^-cGN zD)f{p4V*H!Id;14g0tdsVaPgr`1-Luwm!N7t}ZwtV19l#1_To^?>N`K$pU>oE#ae{ zcSKWgmbhKxXJOj4nmNPJ;QjBIn!xw)S*;O1jc$uGcP@r?%ab83sTb}Yz78f=ybv%? z*`k>ejM3Mz+>%|E=til8e;1bm8AlJvTeZsjoXd^YTE z)f^u@qYc;39)g+UCgDp{OF?Hon-YJMVQdLTemc2u_%18dn^-Y2Msg4kG;)Xwf-7`ivVO7p5r1vf2H!B+1&;rCn; zXl@FG=yuLH(=P-nId<__$uzAW!8}|Y!wpZfLc_mEcMri08+yix=-`l=OE0BooHBD=~C$e#gA_tN_!1%kVbZ5dUdD5oQI(fSy_wE1K?HLowjIeL+aL>_cs?Y;8kVGvMLQkK{=!hxNz<#pW5yMn1H-cOurgI0 zuU+H=yb-y7mJh~7aVMaBJ;N+yi#Cy9el&Ytc<-zgnqnN!rw;xg%M#r$eA<1hfSK>S zT(HppOBzn?K79Z15+1f|gPTtdgJ~+!urRVeUeRSM341>kR3L~+Gm~HzY$8#YvDTOUo`3K z$B@_hJA{nyh=)TO*l3S}h9RU8Jt`FpcvjI>%%q7Xm`xkV>AArM9WjmPlh22t^pw`f zzspgiJZ~t59t6K)Xk|+BhwG4>OGf0_w8h^-;z2Dp0+#LSiwCRhf}Zc|ghj(_V1|@n zmi_SNY>_o;Z5YpI>kSrLI4Y zGeRM&G!wI&C$m*BP{6Xd3mGPdU`(w-x!w~k(ZE^>KWoK9 zbp7IYQKDTh0dqEuVW`WYJa4E2MUSHS*2HWV$&QAP>f*k&h zp;bdl%#wxz2!$^YYG;U(vo}HOaVx>^X*cZce-ylQS(T~*!&DN?=Y_spd#z4rC^jK09C_FC3sle3!)o_7f~QReJnrC(kK`SJ%*|JX&$Eh2 z^O|6;oEgj=ceX(D3naXMpKjv!ciYH3dz|&4t~y<`x1@UOR}6Ir>7uD+DqyF7Bix^% zi?4C%P`4%tJP$kLzR!!m^Dc`E6f(>wg3%t|hqKQ&M^lN{`TeGIf#>a~y#qFwa7s-6 z}ClP1T?N;3|MnzU79{}*OtpGr9PQ3ZbQS7Clqha4mhj0zO`=v!uCkQH+XW2$JgGF(GsyjhTydR`{Vk2?&k7j4 z=PTsw)5FGRx53RlaqwxP6Ep>WcvKYo3)3VfoM2`W&`G|hrwmhJcD zW`F2_^e;*HviBi!Jymsu`rnh6NKb5|s)pyT+Kn>|*%ep8Fb)Lsee)pBH@sLhj~E-x^DLJlx8Vl6!1uph6ae~=}G6=T#H{S^mtHAQHC3?%qxe= z@gJbctPs9FN`t`9Iq;`lf1DcSfU8Dr6v7V&7zPNYuCzaA{`kGUK*| zSvbeT;wW1*8W#wjA;p2IONFk8s=KR%NqvRY9NhW(5^_&v!6&EPU~+y7v_C?g-&tdh zH>Ifv(v&ld55Yuk@#MA)X^S>ANq9cSUv~IWjQC8dk+5hqu|g+V(5~;ZHY7|$YSrn3 zPBfUZZ}Ud*pLq#FBOU@5dj)FJ2SY@GD;|Q#s|)8d1WYv3v|$9ZF$aGlx(ckFJ6E#q0I zmxxI-mSBP{EIH|%7N}f3p5HWcgIvA2RFru9o@~dh(U|THm8NDd>GvdiLkq{6_QnX2 zTj{9l(2!OORg!mL_OJxLEa(R)4&$gF2H3!Py&z2ohM7VzmIB}*PnoBUlL}x|GPmIxniR%jKo5gg|!lFEcKo?a3q3jyP z3YhAa_u$0P3V3!<73;s3!=C;2kYVeKZEu<2-ow@km^g-sB$)XJM4Z!`HpssX@zY8T zIsILl;!hdZIeJJ_4AnF`nx*d5Qo*yK&+N?1>V@}Y--RQ_C!xSV4Qu=Fgbr6bz!3<* zWsmjn#82wY7o!Y^4gaPbb4O=%sKnGo8r1d7F2^ zX7kVDX7_@z%ldBsoiYW?Pt%z}FcmunaH+N?NTe3eZwPOcIqP*ockbi}Zxc}rwQ0U# zN!aw{GEC#p^yLd0fr?g9#nv%Lpr2F^5A(_Z{@n#}bISny?rSrA!h?;NSi|;a7s2TK z;m4JwnxF`BDGcxyp*xq_iQiV9N0PnlH6Loz=;`U&emORL379?s+QM%}9ynTA=3X`wRhjiRQL`p^_pYxy_k=seQt)h!1GpE1OG zk5|Kkr*d&KwMlpsdG=sfBsU9*GVx4y^ZmNPld4jzB!Kl z90@&jv&5TDj>rDpDj_+O&4=#K1_E9q7`1~FIMpMakSX!gu2y%D<-OBG@%`1swE2Rz zVEvAvGa)Ia$jKDz?l=PCFCFmb@2jA4>;dttsImA!?j5+4&Snj{Fw8xIsWzFyO;NE% z-%b!stBW|qyEolLCrvL<3~ea;FU+($L%eR&D(Dt$fqyic0zHz#Au!S%OAM|7+L9nF z+BUXmwFIO4U@Et;#0C`|ChlPTLwOgilVW!@xv2Jbe|&A?Vj*l-Rg@xloy)o+!Rw^Y zg+y_i@x(2jSXR*tFWD6U$aXhetDR0l;yqydsEcxH1vW5g8VF{z!DUV{dlE9-E#Z5W zJyR6fw8Yly{A6Xt1BL2tYHVli zaf^m+;tvBX1ZmRPHR>zDTzOT(ZEwFAjXosdJKoe3H_qCt$gkLoD2ARlv?M;efMG(* zMM4idZD9U%oV;1w;k{T?-wm(nmI2oy^h7&ndE>GUZL!_HZvy5MlSX}%s!E~x1kPyD zVAOM+gs=H}7(#Cv$UW7z7SaJtG@ce-L*67TW*8G0d7O?6n$aU!kg&rxI3;xr7`=E0 z6LWLLqPeT!^RN}zuJk3G*vrCplbJMn1moW~t?)xhFC^b8;WLJh6|euWQh@^^g?Tpg zNeX(b(M40UB7yuM5zdJtPgN0LAlkkSelw*%M89r1C&Fv1TnZh`)<8^qg1emJA|ez@5=K)_64 zn63n)a(*ATE6oQTx**|qmv@w-HWOqgJ`WNw)a#@eY6a+`(VR40G>Xw~j`6O-Gq7X< zaedcpfrgK*;L7)*_y{S6HS8H7VA?T^JHc$ZoWd1mcq7%j65iOYCG1PuCJ(aj`=6L? zR&l~x5$!q{VDtP$xbx`?Xp#4ECB6W$gD2q7RBgO+*meQajA8l`OyJh;+^J^X$mflO zPdwfpUOf3z);2go?p)(9bQ4hrikeQPG}PG84Eqp=cVKsF4W!}E;1L!B5k0(N|GdA($}F5H5KaLJ}K->6axh9o|Qt-pNR4TB4sP#nAZzR2rK4rgPOPX7!K` z_|v#blDBDrv$x-Xgm-NK$9Z5Eo!7A6d6po}8z#+kg7ME=!QCH<&^(8DzB-|sSo8X2 zQPBH8IclM4gB{}cFz|aJsOR+sGg6r0_eBS<+soX+ za3;-sg6TNQk9#%7168^Z%(DXVqc)M~#bX0GEg7L0+8gyNhPoUS^YzSkIMc2S?5|Zo z*O9xSY2X~F(H}*gMbyKWsx}MKR4~sbieN0K8gXB+J6hBuo<9*I6|3di%3mDgg{CDX zhI*ZJZ-hkt2J*bP3i)Kce!z`!WCGj`GScX@0$|^AFmmjV^;#R?D-F!p++Y|9!IUoO z%njJt3srWG=e;$T$tyB5Wy{9p2yfw0jHHrHQKSa}jjB%!V-Gq#CRr%GsEhE&k+)Fc zb{o7+17KGdSL_G+_@Z{0Ak8a=SxYc;n-AmWCA%S!bvzFS68RC;ZKyFM^)C!vG&(}> zSInm+9ymb#Bdp$11%3nS;H7f~yoDL$VU1q++$1ghr#6%3F~e*nn7+dYbMKnEqb)`x zs_t?f?Xa-)7+D_3dZT{s4IKzbF*Mdmom+a|B$Dcf^fQ-WjN}q*54iySeCL3sq%XeS z#SnMxFhP)}Kf~-J7>z>Uu2pqMc`f4kF?LHtmuI(-Z9nZHU}#jG&bg%-b|t2LcZL}x zRl#>RS3t`5KfzUc7Pk4!0q=e!bkw0eE|D;dH*?jG5lq3}Zd|g1D=Hwd&a|FtD59N2 z_PS=lKcu0UJ;#_dzG@7!Gy6UGFDQZ3=)2JAatZ8cI}N_^eXxT;d;DznQbC&O3{yxj zPgZy0aHR{v4<-DzkV4Vt{I;^Y-$x0x97;|5RT?FxJn=io952Ew(}!T$`U2d9aj>D< z6K}uL7N5Asq*=-q?JU7~KJ(ygIy-`w0Q=OA6{PWDm`eoH(RL8$Zs3d@c?rK|?rARiTRV?E z4&(pAP)(y{3Cg`OP+^N^Y^;tieLe+2qC3!K$vFs$oei~NeX#Msws=O~OaUWem|Fy6 z9tB*IpEC+PCgB$p&fq*hgcW`$tN*Lnk7E9pG@ip%aCgrV=zR7*WRJZ7<$p|tqayMW z!;ZH2spT{Q)4(nsj|fJ72Dsj--O$}V5aaksYTHOhCW!U#L)9b z$P^MQKrOVq(gdFzw+G_An&T~pj)Ct0AIMwX9|!c)$K5_LSG|N`GzrGT&Wr2O+X+2e zFX8(n>_mQVb2*3oDXe>yI8f9VP#y&I!cI*m^=uA0>f@I;4#N!oJ#@iY5Wag1%x@Zm zOB=QDx8b`5Y4X^4V@NPvyJ9Z;4<~eci-b2-FOfO;d=u%lNR!cHP3fmmOnTB1Aucd| z^J>AlJ!)=%UzDAM53f~mS*ILmpWhw!F7dK`pRb+0$9<(Ei9hndhr+Vv$nZz3xg#&N$PexH;JcJE`!m+mM z`)a|5UJz?cKG`EMbo_UCS-v0A103Ovn;-U9G{+0}u{Vp~utn=mFcAj*xf*pRlzvje zhu1z9)y^#T*yF!Pn9D&Ijm}H~Hxj%ju}&HnpuPYd(DX{j3{O$y!6;uf+}9=>N>tlJ zS=A_f-o6PE)}{#3EM*u(FoW+8;pCILq6H)sal6|Tk!zQJqVP$r<@6B;it#aH(ol>t zEX%#(#>T;RlMLBf^~y zncz1%M}f~&!^_Et*a=;|DdE?&dnvCO zH&cvVU=X?D2y;7+tNtOs9sc`3> zLlM#{+Lct=q)q##qI=PzNSjKLREna_>vDy5?P=A%Y2WwgH}jhA``!EVd4GSOzu@^e zXU@!=IdhgB&{M9EiYbjfahcMV&E**8Lo;b6d@{vWiF-jdr9M_@t%KXEjlke`f2^(d6%^XshYsPG zXo^`pri-vf?n1iIaQFCg72d^hE!?DI9S*A2hGAF)N+pd7)A^AJ78=qbvg5kAt=ksp z+_X{}89x9YFaHGt6L{Dzh+}3^j7M64aO#{hId+rgK*>HAtJU5(^6_~G!Z51tJPgCa zc1&rzXwQ2ljlR?h7Y#cIWn1fG%(=bbc5R0=VsbDBEI$DkC$11p;0I5*Tud>^r_7I`l7B^B#^K9BgeUk^BE~HrBnkxKOc%8j(-Iw-#k%izfQF{f{xjRGn z%P`EMGbHWncn;JPF3m2A3CwpD+9$h_l?u6X%`d&;8H=W*z4ex{wI7@sb|LeGGX#ABOWx!u)Ex~0a6MCLsI3&Rc@rnH!5 z9JBfzzX*mcGR2Wu+u>EmpJ4uZJv@;Cocq-u`y2g)tgUIH2|VZ0T%wqp4}1jA{T+#% zI#8CKHj~36T!rI(SN;Rjz5MT^lf?ztMNlX-!MVXSB|cUitGzZr&#<=8^27iv@YKTF zPW)Qi!KJCDm~P{|gnlL+NlB_)8GX7y;e6Xr@pGX2Ul?}ZFlkixjS3S}-xMEZ?tq84 zbuh9p6O7;3!IULIC~d2SKr@I~bZ{mw!Fob5qdWtJ_J`d`-(UrCfRN;&Qhop*tbS7%r-p$~5Up^s?>G7+QT(r68$vCc|wArU%~ z=~QW6bvFrlby0XbZ=Aq-4Kd80o{cKX!KA6Ypo`Z|mciLM?;wyCVCX&U2C{R3*tfq9 z{-7-<*xHoyde8b4Gcy#0(bS;ttdc7aH~6GbJ2AV+GJm{?Vb|LKg~=S#2#XICL%T_J zkZGoXFnt0y*3tnSv{jq$SuV{QUb<*XG3%whgg#T!bQ!Iy5IZN) z->Cl!^Et-^hdCXEx*=~NFYN^MeBljW47y`^v=+9cUlUB404|Lc#RN(F3m5NoAluf` zqjS8!;5xs3QRUBrqBN@LAoDs^?jTzmrnHz34e=7~K2FYmhWgKnVac>WsN3#~!-s0& zw*>CoT62sO#UwxOBeWjwPVUo(N6Sg=NP0t5ywxleM^*kCW`2>xAr5r zrVH@qM-Mn&KLG2z_0ZrsUmG2c=|nM$>b!-equt45Dova4vV!99566g}(K@kn5`EvW z7r~#>s4%1I(;3o(s^GHpF*FZT!rPPQp{tDv-py!+9{KmgukYV2jl3yld#tbUX@onu zNio&(GsU5k>p_pe-HNX$#R|8nV)s!N9b~!cEHqShM1};U==Aw34j&wcmp`O{&9E34 zCO-??O@G~X#9gHyNS)p)YjTBi* zJZlTe4jYz1tiptBlcHvc2YSkj72BOpK=$X=puJ~2j5^jE%}d+ElU7e8%mk+LTHFwd z310S5h`J;rUA9xtMgw75K}boxw3a38$Ab-~VFLum*YS2!%vER7Fif4RA7=JDDg7xi zz`3SBU~c78sf(Q(URM7CNoOrYOAF$dVH7j&*g4_a@WG@XmFBZz54P-+Thj4WC+RE` ze=$Fe6)myIEvxZRVQgp|XXR>LG)_&GcAvKjbocF-=4^Zem0Oo!ZcJBv=f~Z_1{^b% zVh)tI5L&byLB7$~+Rz5Wz`wdh$;=4{6$8)t<7ul!_;x7$grpdjHN-x>ioPxtKUSu; z-VGfO4k{U-a{$ugQsAOw0_f+3<7T%=OwZF7(?>_}iu|b*6MMVS;Tvm%$ehh`<=5Sb zB|Ex}g~Te;;_LJqn~gxa7yeHSy9ijItL@I7Xi-!IF>~*LqI5A3X&O9F48yrQ>G)mS z1W{?3+yv%PjLWNf!v3EAWMQ6M=~NI?V($`G{JvReasIGCacx+XgIxqHMUnYw?Dk}s zRS!mEW#9@ZXsm%}TU0@hx$VKO)*IW=0k$(UGr2)?%u?e04rH|-0QL{xZrR87z zp{jZjQ(E&Ld>#SAum?MPtuYK!no#48aieF@&b^!AbafgG@r;5`v;}t4TZVY!F8}e! z=Iy4kD5m=Ahob5RK1Az-Tsc4Kbn(>mf|6=$i8w35Eqe*FPJL|r?&^YAu`q_k1=x#V zjEf=07&j`OS27!|E2d(!cWUvCfu|rM%ND=J@K3KQj@e5w&&CfDPWx6%_G>37gUF_m z?OW}XF~N;XSnqB&F(%**9S}rwIhd=?QbyQ=oqc^LOznhu>1FWLD;N(N(jSm>KE-Nv z(;NSUu1jfG{@KmM7U2xTzE@eE4NJ0M zQ?OK+>dEwAfkS~g-e$qIo7<*A6jt=V@C;9@a%#>th0J0OBbt3=Lz#ChfSqwq1Qo%9gEKKiu5$0K1 z;lysIKyPgmQ5t=Ysic_M4Xzd~jBHIFdM79?quzs7(^k@bT1UkRWezb*#M_g#I%a_` z^E2H<3`-dqzTOnA3f;g#xC(C`l|!p3$H2Ot9iEjp!%cp?S>rLTw5t^J>Fj}`q~I1r zKO#YCb##g}w(gz6V?~F5VAvl4!?0eeDrx5RvPLhHuCRRnQwEUwN9i;@vdbVObxqwSNkxoxDY*J?EI`6w~BYl91o8A=$DhL0R`< zcuDo;Yedf~Rh$@ORj^omcrXl$Krzg=RGwr}kA4greAo(0Y}L?wf))6&;VH%G+m=a@Q*`8vs8$XBxlc0g)2e55+7yPEm!S6yV?AG!nbeO|mYx_CIoMP?{9WL}) zW=Y&=O`*>FC&l(@@j|z~KM1?lR2bInS|tth1sKM-)E||S`Cx6Wf!-G%!L|nhF#doU zo;iOFz9sN%yWgik8;W_O%lV=SG~^e7E5$q*Fic4QU`cw0Cn&pr zIV-(BGF}KSNER_xU6zPS6E6Z9>ttzgD$J4{Ubrz#4{AQ&gD(f@!(-z**gnGz2S$E| zIZnKQ*_bQMi(*1PISG^AwK#pOTwCF?A>~4l(O&PX2 zO3-hVBLtPafFC3BVffya(5Q@8WB1Jk>XtKiP=zV74WGo(#IF0!29x7#*^uJ+PE(cp1tHXV;wuLKvpQDED zv`e9F$|CrB(v}vM--L%dxu2HAF#{>)Tt&1n?368eNOK4EX2uj7U0g(NFIoH-hUKUI zDUAx_(=rq-D?32@Dh-?#s{oJDOJK9D9e&Zg1y!dw#*D8`1jRhMI!X8yMcaS;qz!+CplNbmMk!${Z#5$>ZQvk-7@ zbrl#QFTRN8m?(<5b!@PZW!Hx6q`rV+qDk?+>K4+;Q|2jhVm)XMdJLA1X)k_7e4Ir8 zr)g(cR<6L5ru=jnkB?17Yg$4#YFx7l@R zU7$sY=lg!>zJE2^%jk6=6^cgk(bXG}C{6WaFnRJQaI?HlHphdN`N(_v;ij<!(H$MFlH80f#oepI#fyNs z>P%@YYlsC?*qO!>$5_QmQ}u<|!sZgRde#Xq&b$c=(u$--R*xXD?xi$$aJBd-EaI5` z6yw{tR*18Njib`W+cK*ct*?n}eZWkOEng+dFbizwMcOd1I z8gx7Q4N`*lL%e*MXacTWX$p$je(HkoLf4*@(_qRvtG*C7zy?Y;5HB_tmtmN5%ldMt z&NNla*3S0MwBSD&=I*KnNohkks5}Q=*?mwa{tg_t$usYpa?EjxG52dIg!Hu`otDUz zeg?N7Gk*Yi-|MS5r%;Dc$QT`T}hJ4fCN{wwV!l+IG=0mg06qPh)>5cLDm*!A){yj8{7z&j~kHXyB zv?}7M1`b|dEh=ppSDMBUnlG^aY!PvGA`5Bw;cHDBhlnAoU}_;8aaPPfj0Rx6FMQPv9hqL~cc-n(Mavm&sp+9qPm zIHoDZxORyYx<*@*rF-SdOGlkcyms{~UU%)Gh+&5flSY+rSz*ZgsxuSN9s_uMbUp+P zY=Lv$Wx?TR17O006SZaY$VnAUjADlIPAx>Av2$uVqt z9K*1LON9xyG?mhZ*LTC{QyaicX@(Xr_k)-27#MM)CGOc#34Tqv4}FtM<3KUVqY?zC z&vqnLkSkr5ua`Ql8X!%smn$$=U4>!&p_vIVgH~Z$SJ`2*(<~^duY;ch=Rx|Gt>BmL zj!pMH1fTbOh=V$p#+_nX4RsRwzqBC+#q<}qNlWQG+r1KJ8y|60B?~{WByxsfk3xoF zoh+ErPV{b$ip(Y8a^pR;zC0A3cpiZ~+RtX)ke4u8hbNKS@M{eyrpifMNIGmwE|t)l z!Yj$eY1Z|MW2+lV*mx=?&3|IpeZw$=N7`OB;`!+5+wklHtoE2b`Jp1imVG zcDEhJ1W?SO&O}&hY)4|~r`Oe`M@xF_v>~MjI*G%!SagtK*tMpTMulky?Q#F9960RL z6c6~)nbI?+!?kUeSUj4h#@*(xwGDi2f+^-~!`Z^y-L^!FD(!(ZuDIJs3+cN1Cq!x3 zCCxDGT4NaIr!frkp;HFCEv0@1e4u{Ql>PGnt#VIKdoS@12$W>5gdYbamLaWU^i$Z*!jDl z;@eGVYI{K3H_x~`7)db$J^h9IquP);bl;3`epvdU&kM!ZLB|M-*)VCoCU9xk_EbqD z`p}D8;GTp8$fIN42VG1CALs25<9mN>l2^R*_$$r_3uC)|j0MLW zq?m&({Dd(vKP2BL)6&I}(vr8627~*u?SwbZG>(|>tpMk z{K5W{V@^{{#If$e+(I4FJ(5P%m$^$%e>Ny4*0ho4wO-;pX=Z5*Gpb4XeIGlR+oIF>o&IK4gi|r9OV40c-Yu^PMa03dJ}__zBVLb;#>6a;3lPdTGZg zFN%jgeMH#A7&f+=VOTtky$Hk+NEy6tZGVvkx(AGf?Rt9HBl-m_7a}0Sx(Qycw!|5x z<3x-j$K0Wq_@)6u(lrB8LZyi~dRJ24$4iWR@mAaetS`4e4ozW-t~; zpH@d%&}E1=jRb!SCmie00{wG%Qs3|3eGSD}HSrO$uQebIqU6dGpY{l)zg|h-E|3Up zFb!K9CJhU8F${ZnuoOk6w91|xaOac==vZ3|Hx2iIZKv4~*U=L-@0!J>~a3 z#iSpQ2-k8NlSAX>%Cu20ygiN|t0Bu4Utu*KDruUY;uv-cuta5skx)$DT7YA9y7x+hE+8x)qvl)f9gUH8@6R zC=I4KqzQ!<{Yg4K1%3`5R}#GKC0tRyP>dZBBo-~PgiH2?$EGW=w`Uo}u!Ku%qhH`! z{Se+=ehu>Xt6}QGO)%tUHyl5uH-w+%Ca{`c1jZDTV!T4AQV%Ctv2x|0y{n`H2FI3| zJ^mt2U}nv;RK*wU-&2KQX$f=BS>keh2p^RGc;Ht(9PaQ?((Zaad{bKkjcAh-X3#_U z*LQP@u_&D`j3{YK9!;VT_ICxaX>pSh@595y3CyZaeX1`!6^3okgXnqVVrIc)E;VzgKx)*(nvVQnPTQ$ zZ6eGIX;0>lkSpIGZBbk!bc3>tgW~pNY1b^!#V%>l7of!#tp3JwRVOS6G)I5iLI|>` zhnDH%Ap89wIJUbt&ih#n6Na1|*YkX%`|+@j<~=~LwlzwzFC!a?j z636edBnyUN4-cbJbN+$3Qqde+W{iaWV_M>+j`6VbX??J7<%<(iA45sKYogMA=W_I? znD>LigrrOD$m#Yp6LMdmH1@+sXA|bpVdRN zsz$JMZ5Vjg3rD*%m7th>OT^@GX~LN_U#x}g@9l})l2)%)q)YcWc2~TZW+-KYo>}4; z^K4X6jz2M$iLUr!e^X)087{!?J z!dq$rzkbP-vkz;KY7=cmNaz|7!&0r7Gn(sDTn!DU(Wz3J80exHwmsQb1lyjYW3914atiF;XoIWGBVZ^Ull=a?50+TaVA*-z zeN>H~0@)N36*yQ}Mo)odwKC=9P<=&9{V`H2p`C)A0;+wptsj3$t1?sAFYXQ+>`JC% z_L69!{|`k79G%w#=3S-z2i(iSA?$ZPG{@vqOo`2KVa!Gs5>HK_qC~sseZ5tRZ7+(& zA$6)#fE_lh_<~&oH&@8S&*JYF>~KZ@eNYF+_*pU!!deV~aq=KM?|BjSx98d2XE>&a zV$N(HBqZH*Ba;p3!=s%bZIRNT_`B3o9J$Amli0_K>V#%-=u1O+mg=`TP4VFQEs%TN z1ec#mgjr^Tph1cRx9|Q4SKIRl)LOna6%=#gTrZ)`IXCj&SgzFXY)$f8w2*8*{9Sa_ zS&aw7s9NYT%;Gj2U8?l$PzEPlHS*q+>W4VK@-jf9(S)gn0ah|KL^Rxvj=-+df2U^&m z)oQSDp9@oy37X1l;8bHC7wF3|*C|HFIZzm6??gJcrq8H1Ns5bWmM9)XtrGLoR2b&j zFbs=wu*5Nza2Z=+imwe%gZ;_|Xg+-nm_Lq$Up55C-2VWzzNw-?AL85d0mXc2I#{s3 z?o7Vf$(2T9OBK6&J1DMvxXW7|(}J?_#XJ)-riQmSWIyZ-(|3U$Iz%6XS(f$CP=7C^ z@0bjFMeeB6=o38Hwp_$~3AFDf z^j+VUETfoY*Z0KLw2`FG^}b?Xb=F0ZIZ!OmM%B`YC0Pu-<$)ugYT>)97r{OFJM`JP z8n(<`0-Mfsz{m$WbbKW@=!yJqO)ZS3#82!hEc<9rwz$fbCU!xJi#010`F$HpSQ`V@ z4US>h_bN*qV?MO1lq9><5LYcd1*QruTx+!t9+Sl|Kgu0nhW&)#Qm(WP9AiK+>0|wc z2Sshkx^{A;M4@*(R3EyD7*A3{Mr-Acr^I^q+1u%iOH(Yr`2Q5bPpTd_s`@w=@GJ}JJ zS4Z0rb6aX@qYQ+A%}&GyE{FwXHenpY%6!;2kqX1AiIU9q@LAq@cz9PG+w9y14Nfcv z&0IHp*ir+XpK^ol#HF#Pm?WznLc30FNS?V|+2c;`k?Fmn6-2j;c(3gz4&G$as4%Q+ zFMD_}O!Rqmtg}7?w>30zN6t2wD#)QS$Qd>6>*5MJIDq-kzm?`jF%|2&39IL{A=8@B z`kQsy#Hj3`;&a@d|A}cHM~js#%iy-PHtL_-4#S2n0yP6?oVQXBf86G2*O&Pdmr%^D zrQL*PPi;sGdUTG`HSn4z?I2lsS6BMKq#19kgQqf&!`l=cyf-2fMmJpoYlCdDSA;fZ z12=*59Mg?rh!7|oYhX=GH0Y;S_fx{J=5tB^x93D@;sXA;HtdP3Qd(}Cde}Ml65MaE zjgd1mpvT4~V4y|oxkw!p`0&ho6aK#GLopYU`U)RvtjULOGG%z{<;3-yrDB=Yqra3E zkoEW4{E2b4q7!5C&cMadI(WQlGu)Cafg8Cl7@)6)(sMj(NWxEn!4&g4p{GzvgZI^X5S8f_7MbLmRuB zuNO@qjAKSo%t>0Yk~GhnWW10m-M@Mg|7OPI?UzMjYZleya+Rh1iD9!=VJB?|-asD< z^0q?Gz}fJ9f-|lfppF#-c$v>Mj)|t24c~hS7du*!@<%ddrRTe%khaaq;PAx1q{-OJ zmB#)(|HQ;s8{s-S7~OEc4(jS`02kv}IHqimOYZ-KPBf^`40<@n%wlVEqNm{7)`}$E zmnn5T-b-T5hAF(&10?@uX@6pV(5RrxwQ_K((Zj3D(xIO9d^jU@#b=5-Fuct%CLFVv zV*0!H5gtsiB4_T(lzX2ZRm>@TC)8Xh`k$D-0}L@#pwqGM7-06hO)%)z6xibLia+T8 zjbP3Xn}s}>vW#L*#Pt;p(muCgw`Iz)-tQ!&MpqK6UUNhxjY?_%X##V?8sgfRY>2Ng z#JDLNK|OT}R428^^Aa`O{G30dW^#j0qZruGTNvllnmoNDQ(hST)9d_&TavNo3Iv8x z9i9JX0?@lYI$0cs5`P0MGG7b!@27!zQ3s5;UkhJdIc7FjS_Z`ojp!vTskI~t_hia- zhp*5PZ}%jY4{rV!=08o~p?yQN(G+0L4+C6E(|dPbnFgoUbwnHCGi;D;6-}TUmu45m z1aI#nOlW0Ajy$B8zUvgbPCOF2YYb4Rr1`(Lr_KpeIuzglw6m{|-e1?kx}lLUVUas- zUHTaUTW5%v-vQ!6ih1+4pU`BM6}kMBo&xG^CHKw`FUmd9MZucUvo_T1_EahD&l9>! zzeco3b3dH%H^F|nDe!YjIAl9|pilR&a0+;6NQX;PLNO`d`v`NFwkBif_B0PWO-ctZ zkqoS9Dq>W(CrhR9JS<9cg=0=q zOuL@}!mZwx#OAF``J~24;=Qf%NZfhPe_&M7Os?kl4ZA(HHqg#Vz4w8gr!nsAz8p4J zj)WC7WK?kf9sIb+o!eX71TIm`g~LHY%r{FC|3RjFAbX}*XSdzU!|8y)l%|q~VVDW9 zIfd+mW|)Zy&Cv5q0W3;rjE!_w!HF>;aIuRgrrExR5gYgy-tSzFYKj@*6)Z%3XiXk{ zmMJZ-%vEg5Js?SR_@~lT(x{ZiFwsWMFd{M!_ANKT;%><><7WuW{p5jpUa#O%G=F%E zmdv|-I~NxjN+1=*8_b`VwoKL7v|qAjbT2f zo1$CDZaDFZ=Gi=ngPO#F&@>EifA{CmP|jZjt2yR7#ZSxgEdZB1(ojFEpn1)){E8T^~y==%z zx;C-)xsrjdYLcucjYJ2EnZW<0wCPLDu;tGz=vdSQea|h16Ayxbd;>J6{qCNYaf9~e znEDiR*Q}=y`NM{!Q%g&0`AZQwJ)PXMcM~!H*Y+G5N=+cWCDt9>4ZXrm@z=eDa3j$d zY_bu%9=QXighL~JI^NTb7!m$1V?6CP0!ve&8=QhDPleR%^L_Mr`DHW=wj)qx* z-Z(hoDb&Bp4SFBnH=QV^+5PT<+BAD|o8F#ZSFP~sU%pM!yfv-D%jkzOkLHSP3|R1< z%_d@(Gz;D{Obgl+xPi@Hh|n~_F13pxX;vuAU*?6SuU~?#Azzyv9OF$fH7$AyhVJ&H z^Gzy^cW=ebUR9EVF)5oPUC)clow?G+Qp`A$ zAi-y?16g-QrmSyQK}K45C^Ghbm9X}Pqv(Ki(@ZI!u`)77{E&2rj>CLSf+r8u!-cQ+ zgNxD-BbRT4h1V9*&-_l9;am%k@9`(DHOEY)m_6SD1TQ}aQtz}(nY=cD3>Yg{475KX zVJ*TL=H6G1`8g#9d!+b_UwFnd2=++UN3t#t_BYW((}io`wgx&{ZfcaUcgz$&^=)?w8nCg$rsG>RzlxIK!}NBGwjEg?Z4KmM~CE=d-jv z`bjy&KGH(z%1zLJAq_tybigHDby4#pch%=|X_ivVEWaSZy@Ml}NTs>!I9PJ|W_RMP zxKYGfgtIvwtkR1WU$99_;a~j4e@}+lVX2Q*u7~0JLN(lwu>*9>pnWUhTy1K>bP`O5qw#ti<^7pL({yaut?VpxA)Y?hfyoUwfUWM zn?*5a-UJFI=?)}?8nn&b+d^{J5J^_r8L^|X?|?aC-P+;~w3jNyuu>9+VO4m0Zt0_B zt^#~QH83G56YBXbfiRg1PE6Fn?X`U0xbe5=UW&71&P#^3l}6i z1dm4p(B{MJ|H81AtsirwSa*pw%5YM`^95Sy9=0C(javjud$-4_lQq%XgIih(e-Rv} znArt>LW8-EWGBUZSna5Iq}N^WXtP*gy;K>-H35-H6Sr|1W?9oTd5U3Gc%6K|L)=#Z zW`EYiBWpLo#H+I*+{X#0JyXY5`}j+GD|ZLWC}#4Mu0pD_BXOe`uc^ls%TCxxN*4u) zEn8KXM1v$$`27>3{jedHr(A(PzKt=i!BNmJTMy6o(~cycjj(wV|0Xi#mR8A>HlwSs z$IgMs&dHP(hTt{yaZ5?~Q!|N5nt)e`bJRIzU=uFQSRFtMt)|#$$7P5pF~sE4M47^-4X`+rKRklD((X}A_c;NA-84t?mYxEo zeU1x>O@0ai8doHxeGa&} zvk|_#$Uj!PaT9n>F-ODvh3UEuWWjNnvfRu>QXM@{u%ADIu;##QZSL9mh!|$jYK62Q zgPK5&8{(Nu+W5Tk0;I0i!C!Zdfa}d9=+V>_-+nW~fEb>Z(1siIM~XRU<0F(?(@XlO zOgY9agIfzLs@81rc-T-Qp1OMdQn zHct=Fn()xjJ$?$*Q4DP&E<7A;N3s+$<&02;WbI2s#pH#Fgmt@SXBxvWgJu}}c|qd# ztVl!ryw?ExblwXVXY??`h&oK=tH5zodvtGVfG(@K(spu;-f#`I3E>i>^NMs=p&X9a^7u zRXhfpUTC4?tZ_m3NV@@$O2|mL1TsyKcSElT+?4hvX>KRF8 z(4@aGH6MI%mlwZp{>0orRUcbfmw|PZF1iT2VDa}vI0PNBVuuz^59ZSRj;FPun7Uuy z!e$+N;*%p&D%W}z-P+Vh5w)7O)T3+j|C8pWtp;Yd$cFUZzi6AbHE=N?9Aem5x6z+r zVjPdBnR0`6rI?BHeT3l!_M}giOqs2Q%esq>|rFl_I14S2M&Nn)HbsK%K=M@WkOVf$5u^#!lb1*W` zhON!NDXsTF8m_yY1*^xZ;qn=)U{XyuGjFzggymX;BziHcY{ z-*detng?Y-&huDUd4PBf#|&g^GqtbKq1uUs zukL2Tw@ss=x7-o;XnugT12|?NmnMp093%q-v*8Y86vgCAXL~09H1o17%kpAp+7&yF ziP)5g%jQqT>WP12s&*LRhpELdbe#^K8NUu{FDwSNO-?ww-!pjLh_`Pyvgf>WiG5L(#H|% zYoUq3Xh=6~hduj#fx9QT(tdJGBE?wE?Lt>d_Cj6%~zLWUc zs4!I}Mi{uH03P?Dx8=oDSU5BsUVUzd<6pjjZyh)$g=11F=E|`Up{TnPSxHZUpKS0R2){ZRNPPeDcUWw%^7eTFWmWVN#!ZBdj7LWhhKcJm6ZHmm5tCsVCd9V~uGqmb9rkHs$8Key9jb>B8k-?E zeIEGVvcnBI-(ZP6NxW~=`0e?KVgk?i7e=eMC*L>7lr?YUBx7ZHQNZ21l7N{U<9fIY zj?YOz^8}75qPd>t)J6O;PaQKa7lSZP6Yq@Q4pr-9pdIIobLfwU(b+^1(}-hUQ_R*& zA;O|&?Mca6neyJPSzbRM2MAfS$C6REhTs)nI=+Qs95VmL?DglE;oiT%_D~W0h||U* z&n=KXIu>;AIpeexbfb;Vwp_odSZ`|v8Aa{nC3!aa47zX z`B*v$a*QR#n7`;P?CRcrTVI zzaJT_D4S+R-gW}XqkSAR>k-Xss`pRK(0*M|%Rmb|1uEgLnmVS$=fI-ZtKd-=Yiu=0 z9dj+YLD%O2;sA;n)OwK6$hHG9qL}6bcPQ4Bg%itLQ-v(uFi{#6rs8X~s5B-`PEZ$| z`)yBn{jiodvhoCxJtd0~&|_g1!s6JNS@ef+=Rr@_vG}!i`*wl_?GO9~H9R z43~UOz9?ZB_w4D&Fszvg!~A^E6C-ymLMBalxEg*AIRm5WYof1P0R(+Wg0rDEIAod@ zM(yLyZ3f2-rI-$h0|YmJH}Y(OO!??okfKyOR1*7Rh}ZwZyqr&y$1hjVCT5!WEhPsY z%%W4U-r3`;b#-til3Us@zBZ8*BY{w1j#UR@zK~|y4SS+E)LViT!S1aNcscY3$oF%lHRjD4CsRzfs6Il0r8^lhU#3iV*zDDB z=WWTr^jZ-US2!J2nB3HVDs8}KEnKtu1WZ_|j&8J5-=N<*Pn=nvV zGsT_km`N>dJB{2bmPkx*KmP~jeU2P`t@zpup0x-W=6;MeR@oc{7dneQYjrkUYQGAy znmFOJH5&LSg+B@hb7{6w40P%v-00Ymkm)jIUyYFxJsrX8!UAW)3_7kKUz>l!yt%1` zrMHXW@;GhG-?s&fi<7{r&>5F6u7wmMuC&e^lS?r#qIwFwCwC;Xr_%7l({RN)4=qW? zr)&RHn!**epfjri+>P`w@nSX|Sib~z(6{IAl5b$|#rI7n#~h>>>wtj*sC6RKCd-tK z*Lw)gUD72dzceITbHY$%Y5yjTXAdnjpxF;8l{y&TG7BoFErEx{PIx%}8+2{XmG+ab zO)143xjIlNS=Whdi>BER%?6Y10WC=SS$$GCAx!L+kdy0+3{z1tQ9Nu^YvU8CgD)SQ zguxmb=wQ4BCMs4yD-#zqy!jd4f8vJ<; zke4y2!nl|Gjak;BE3UNH#=cL>pmBx{wz#(ydOuwXpK|FR!O(BedOlBs%jVKtp_uXX zi5rvBnH(HP(-N*qNzOYzh4K6v$)D0ZnIT7;!5qUXy%^^BL~V4)Du!_@b#PD34(Qrt zIb3hv4$p_Eco;1Bj_6FDjHQ2T&+iIRF5Z%yij5-X<7_UC3S;8m z3ssoji*>NisT1Hue>}Q*Y=dTMi7;*%ec$-gNlRO~rS0Rf&Kin2To5WOE9^{0j*%(# zEbJ9=wPECX*8j#}fgV2iPyvS(x;TCKHn{Ra4$7HMNP@n=n=Kr3kxTQQV(vZ}AOyO2 z5Q|8fsQlbqQn4vdlH5l}a^-v&GHLW$(NS(xXjL!>k^~=qlIvTha%=mlNdZ~%rU7y zIi{NlUz_iBn%KqpBy>DYM~Bg&+wFyA0Q1}72R9A8TNy93rQ(DEoX`(d$h8a_? zh4W5afFsn)yq22@i9Zq`vXvvoFZcnEm+%*XE5|gan7D@hg^x$*+E7g9_qCFnduhmS zd5WkslTwa(ZTz=1UJqE+WLGq*P{(UO&p_t1TG%qI0GzuogY$iyG2+lKFrUIrAev)r zD8|(-MA+ZLi}a0@SSzEg`chMqxNfp_Xmz zbv-6q;@)K#7WSNmIkPw>Ysuf3!wP+83`vGb z9j1dl$5%qIlOBGUSqL*|quW7~+u{ZXHGEjZG1EAv3&prB8X;``R5hQMK zpb)+zTk>%&mxf_jS?PabEPAWs#2%-i%10Y_U)ce!-_qe+M@M|^qlR}n^E0g}cR6}c zOmya8;o~j|*)m+FtR8)zXi26D*N=B34D;yARCImHF<09CElnluHuhzx8WyjpgvRdb zSkpWkmi<@-1uvZN^KA{xd(GFTkYoB&jM>+ILf`gM@+eHE4Cwi(=+c&z662AfqBN<` zree)?KfIYM!-`WAM5S3Rh((6EJ4FM18qoe+Ms$i?!2z&|S`Au5+hV${E;gCPrTM`z z;S^((9WKlmNyx7uGNsv6b%p23u_WMgmBcrD7^*Nudu2HE!UQ_*pf{>8UaizHqvRfJ zs-#VTh7`k=1uJ0xZChNoQ5&Os%@I!l3+@h%rfDYW29icOhN(&$&`LZGB2B*W{S77l>drRNy9LCewsLL=4B{P)x|~MfDlKAb1CNpnlgzEuff`_%NaKRSCJ=U#8rdu!&sw_1x?Fo|=EfjJ?*Ic2=Za zFDd4D#d}CNa1K5;(Zmk@_d>qIN+^8Z2BS3faJCs=n|LmboMI|72MBosB_tzMru2-q zkz{u@CbI&|B{t#1|5Dnv?lLSKJ%J`y{EgY3`wQk9UH}Unbv$^#2+Fptfry)S_~3vB z8ja=B^yh1{nqr!zg$YxpONd#BOj*#|T`*NUR^;nyL;e#pYQR4+`6ilp+V(aWw$Va| zW(6=Oas?C{*x{wwwQ#bWN1!x#tK)Qv`L=MR(7O*I$-(q{wdJxR#ln4p{p$)*8dmRV zyp^`i`$L*W&AHMhmaF5i&sQLQk~+>Ce*i*fB!bhKHs~CyivyQT6fLb6pGS~QF=sA} z5;o-$;zBX=795vkv|Z^Ho-stk6uL~sfqAsops5T~)hEzCoqdpDzBcf~*rVz=Q1d*b z&(pw?afd*^VH#9ivBEg&!uS65`E74j*jOnZb7YE6iDUzxIZ{T?KvOQPrXJEfAi zOT#gwc#0^^e`1z3^~2S@zrv8*o1jS_hskuz!L*fWu>3_E3?npmeWOg2#+;9&D59A7 zR)d9?8zm&Mk4zc&{27Vf_fxnxbCblq;@>e^7Z!@r)V28mXIEW@`#01ve_H`${#p%v zJG8-2b6xDO!=+iyl~%!|aTz8wdE`YJQOvjYVS?|_e8GF}0Se z>LpWNuL|~Re6&j9dUm*o@h#$O^KY1P`h|CI*;P6MQ3HjzLtuS41vbvM#_DW!+<%8l zQ@}9~C?>mRv|zB@i&#^P{cIOm6BtM`C(%~F`nPY3!(L?rFEAn-(>U=a@TbxrWptS zA&m-?tJxQsG{)3FD4Sac-%YQaQhJSJemgbC~L$ST6lJLthhZD{OB~Hm|6#_BMny(MAi}iG0MWbx{1h6`Ft7z(uXN%VEitW=}Dl??nsKj}lT6AX6Gn9$D-$ zUXPyE!J;%FTeviH7XLS9^O|2U*Ypkqbkf2-uZ}^m-YN*4ZixfvCz!1v4-lW_N^_%_ zp0^`}zA;{;EtSSS)?K*J-9l1Yy4s5wv`U&kG1a`gid5IhSS!#}JC?W*jb<|MVm~yU|$Z$Rx>-t?wir_0IldZT<~IV&1^PQTO4L zw>pmge}vt6Tus~mKk$@7GG)A(5<=!FoU_h)B?%#vu^W<*kYvu3bWTa7d6FbaGBrt^ zeNKlW$y5mqh9o3Yk}1<~wf7xA-_Q5=?ay;P?(^|pd#$zC@ZM`RXSb=TBI)Q0eWAX+ zIi^k&x=tUV(99Xr*v_6i-GGvXdl57lS7s8UXE{2oSw*Yw9$wgYm;PAIgcLQS(_%%QH! zxmB7Xl4Q!F$$P-fJ-wTIP}GHIn)|b@q1FGLx$LC|&rVO-u6i?s{bC7ZE=TA8W|BB|H%;i<=65C_D`Q~|V z=XYvS|A1&{y;Opj%}NR8AIpfp0>gIWuN?i9Od+S4=`BUaH<+D@gJ| zr6~S^F-eaS3hjSmF0$_hjJlT6At#%`b+(*dD+r^TJq>_OS~$8`c;BcC(QIRkM)p!} zpO=`l5qqgHceHq0=wY#=adYx#75Lwnhir@6W%ENCB~^#N8b?!O0%_C^102ZF0C_7! z(?fWBdN4*k*@1hEKbfYQ z)^D&A{>jvYH_~?(AJF7O8o1L*PQAVT>9|w_OxDtb|8Rl1BQRl%IoQIHYrB+?m@!@| z@d@+Cn}?0(|rzoKbso^$W6{wta$CaUl&eZH)MKCe}W zdE5o+)Nq)loal?E`qdI1D!iHh(hz8O^rVKd9ZH3i?~28jROw z)7C=+sYgU#6!zCZ-UFdeyCy`F<@y>$o{}Vj^M8=0qEA>V_&&`(4)JlAl6_{@<7Z z`+rfV$Wkh2JBD39a&+F^K>B8DKXyD=bNGsc`Axd8%2CXimS(K$)Mv}k!@N`*D=f+E zPQIepm;V2w(Ec-;4ToM+ZrOb{JXeFxv-9*P`*6v+2OFweuyedS3Oj`zh2@6_jOqPm z30Kpfklu`Oc3n)i^(v67t?wcVnY)aCt^K!X6ptq3yZvYSN%Jnfzr7j6J+f#jdt*A( z^~dRh8mQ*>XNIr=)FMm8kZvu-$=u?CEF4rD&KDYlL=bfK%M2~bmH|!YX2pj=5-FC9p@OrVwM&*Uf$0anwL-o+A=05 z?RV~dp_r%*@KTj`{;XK9yd?H+%NB?k(=fyZO^kgnp?Ur@nx5^y(kt#2G~c}$%#CyC z_)EU@#^%0Qzy`Mi-wW*~Ltwfw#(Vw>&bD4m7WHRU;KDEN#*TgBokMiUW#!+|G%;oy zR-Th@J!-aV*p$@QQ>X$4jA_=@kqfaT zWTgR{5loF0%Zeh!i3g|rRcIz-g=qfC%#Ah2LG7>9`h6Llk=zW8>`DreS}66fH^BFO z%@MMnC6Tee-9j`&81q7XIX6T^$V7cF)xJ=DGGg^pQRdj}zpB8Wh4!CJyy!JcPpqJ( znyl-bltum4htkIheX-@d4iqDWaax6t{b0su!EBea$9O>1Vja-kr$h z9`<~@`A;UKVi%gCnd-vwX};d4oh;SxI4y%FwF{%CPWQtpt(J(<5ts~tF=0%pbP+e% zUrbi_VDB53#R@gMUla6?y%PV)xQDX)Jo^6qZ2n{}?fgO~bzoQThW@0B+bF2!*g#r3 zxG$XEHAkA7P-yLhtq2RoT=-(oeQ!ZX$L?OLvH3kYwT_=MO@90MFUIDz^sg%LCzIIY zD?1&boa(Eo;Y_E?bR9bu{J^mu$eZ6BTE4=>!$C-Znah~j^H*_it=Np7ys!PN@ zd-#O9z{>y1v<$JrpG?Wyk94HQU0Q1Yi_Tvzr?WP(Z>7DuW9k!@+G{Qp+8?KnE@6z1 zgB|CkCL!Ouvc;6b&cxyBQgPwvnE$~HX|o#tWU`#=X=(f&dNJ=i9W*+NI`@jE30wN2 ze1;azA!8Y%o}Dk&D);8v*O~K7Q}b+kHcf?A{nPPZOy!pb z+IjeGy3Rxm;uMbVO%9_2jSSE^M+>R#g&z8@z_>Ez#lofB{bWLZXH4OSNeb`M29b$P zdr^tIJwoK`d1m(qDgGHvM1(msBi_-P+fV4_w#~5Pl!6Xi5<=4l_C*kzRt2UDoy}>1 z*~yq!n;kf7Cqkw%Mt?y^#m9iNV)w1C;y;;%kwP^8WST1U@!AGztNDQTEmlKOauzLF z7fJ`2^hH^NI{LW?%x?lCV@$t^E4c4>2pQLf^#bIvc>JoL@>s{)e?=4V_1}!=R-xTU z*yY>RY%wK&?Ry$BoTE9DL#czjFS>Wr#&l0%@qU`X1Tbd9+a=uRyMz$NL~%#NX3Iq4 zLZjy5eg}m@YhwOcXibb`^C=h`RZl0ixJz&EX{1gTayo*B(AJfGk@2)8&a!Rrrq0Gq zXg5)e>D+HISKJ^b>pOX=bTS={b&lKqDzrbNx!h5xX@4@3fKT+?t}?3X^NTiL znnmZ$3#Hb!-LY7qiIG-95B*0?i)V~}_3vE9DKY8Fm=W&>O^7d_#|7N=7B^JeqdI>* znivbYPz8E?vBICsB=%ZsZCXahxBp3vhF_xJt_9HrZTi5gqbAn85~7(Zyw=V(721Kt z+<+fqa!Z$O6D22cvrV?i>&^}&V?O*{Xik|@bUNvXe=`NHOX# z?R={@^5-_k^LGN%QeZL}W4B~67n4dzV0)G?Fl~ppz$IN=IWL)yrl~^z8O?t(w>&@4 z2|G&Z!>ixvu^a`xj&M5ob{|wJo8$Fdp?UfUOb%n#X)WcPbR^_mTb2X0Zz<vkeR)dA zBOSI)WU`IZ54RR)I{f+{%;|G~7aDPyf`pp)w0C?3Z97;E>i%q9fUVq`-eqUqFKvOL z4|ni2?V7;cV@%i4i@9?Ngm`ItsT#uDi&}1yiS@(Z^UNme_4u-88eaweS!nK#Z2118 zfjT-rpi`3H(D^YO{q0&9)v)V}gwf4$t(h=@`s1vjO2!n;UBEqFK}hqKEK#{zqBwSO zk$mAiebQ9ZnhGs(@xK{|j=R`5pi@xb^O3$wuAtMpey5i53)FvhI6ahZfaw=nA-kI} zVRsawsb$Q0cGFUa!GvtlWLc^`Qn|txt+{^c>`dZm%m2Sj-Gx`wu<{X|aP}wN;>Xdc z?Stvdo_(RmZeWf%B)ryE3RR$iF;j|{aJFWIjMrcbT@9VMi04=2H(C$>ugnNrYcxf3 z(QXR5j{QL2Jbg&@U;UtGa~0IHGMI*L?u}m3=7{SfObQ_|KN&Oc>k@8HM+s@E=B4rq zWBE_-)J2sgeR-zDK`1oWOG3M8Vw$%W3T>?F4V{!$Odan0pp_3U(5;s2dgN*Yv`W*$ z!!bg;Q5OoWrGvVfc91QX8X+NBKV&M$zRkrZKVM~yVBbyuXQ6#JbHty~G(DT{uj}aA zYsFAvkP=(*&!z$V-7!F$|b8y$k|4j zs%ksoDrZ+tsHr$2{=cHh9r&4!JzGH~Kh@E-mZNJhKxyZ zw&z0HNyve(GF3p5wz%?odvVM9%DXLz%w2_XFLoiTCq_Ej*>bh!|sZ#D?9AD1;h4Y7r`<)S(h%0|bGvlIAp{vWMpeUh+zS>_--LigBEzN8inHoVip6dxGr4}N3 z3eD3?V9Xd}u-TT|vRXnee`d^>ya|bpsiJ&I>|e}3qxqAGxG@Fg)$HY*TuN8W{zYSt zD5&auIBm1055DVbqU95zrX3a-OU4{v`<@vd60(gk-QJHB*NuE3_qO)&bcH07US-clZ;b)knrooyjldibn1zhllem<7`9?zaeUhn?T`SqAi@mx0#lGTA z+;VKHcSifde;3-^b34%#%?7VJs@|`Leql3$5n3FbP#j9Xk2XM5QcF}G6AJB+Fyydj z%yHRr?q`aGI5Nhm`ifZg*pI7;_vfQ&V*azx{$vu~exO5lJfvV7l6m75bR?VK7=P5q z*flH@UsGTj1ZFK`>N~9Do+V4j)sL(~FX}_w<4=rlsTayK>1ykF#_6C?p_`t~pUjwX z?`cM98SU{)4QY*X+V6P?m96NDVLP?Zd%f`X94qu`TNqI77_3YX7apcq$(*G-C*KaNw5`E?L)iUZ zy;0su6Gi?4lPg5y!%eWp3BqX3trYgBZxB~5DuJVvdJf?#KUj_adO%wBHp(Q?g zLoal%p!d70!LC0?Im2MO?6p1`2CzK>slfCQYFY?ms$bf3_1+Q^`&On>Gs%+Mc9n=* zYPTl;$y8Ua!atdDnRRqaUMbaa{6T*oag9m~4%1Pi`@np(7IG?t<%b}FiD68dw>_t^ zgc6OfO|3zO+=jfHxa2gY3fVFH%war$cro{`(cBzcfTf2bXp1GBQ!#En0`OoAZ^A=ATT-&VMts^%I)Qh8$wcMjGgo zO)IV+rv9#d5a_Li@D;*Kx=~>A7<1`^J$Gr9grrup3Y~gG)b08}u1@=x*lhE^qiJF` zdCz4@dqOk`&EC)!H5F86%uhNiSV5PZh^C60zhO>l3*25P6xtnuDP+vU-pe`f7(!lF zv1qzXnXqZyDbD?5H}d~ubdF8M%f9tAf5aoY)A1*5Gvg+mFfNkrx!MaW25KRr$cZ0y z4i;8!%Ng_GxFhH1L5R~6nJVs5o_Jv^aQXd|;<;{rN2AqKinaUxj;4v}=2}O4+%Kbk z6MoPcxtHkqv`E^{K_7!hHplhldw3>Nh^Cq`YW-JoKe|bXStYA!p6t4vPbayB*6+j) zW&dXWS!hj6c>5Y!b)lTLZt;UIOHtC}dn0LIHk0o6K?|QJ3D0J!P@&&4W{kTX=lh+I zR*z+>*L&GXW85N>kF-HBQ_)q3&#A`ZYeL0;L{FAO2uANTf?E*En;jf_UyM)tPM*~d!!g6r`czYfa7#+sU*uH{u`b9`| zxlCnt?HG4`^;dD--CO^Prm4_8orNmUiQQV-6isyL2bx{;fPTyVMeSNBsk=0kMmQMY zjW*lA$q=4Rr7-I3!kDP*E4gK?hn`#}Q~7Eg5?5{wpAax?|G$|37R|$w_cZNADIMLl z8TK6DsFp_*UjxPortD-9YTy z&>Ca3ge+BKff>V?O?y^yL97Zy-IJ;Axtx~U$-aszr>_z_JaT}Ukx&I1Yd!gz=KFds znrd1TQ)Q@z3U`$J3Zu?EfuW4q*!4nLdw?X4~>h7_B4r-P1tN75C^G)fgO~HXJh>6L@Bj&Igw!l%Az!wrd00(n^Koe|WpvO_glQ~l*X9c!{iqj|eho_Qto&?^}uzirDk921eX z*JP?Fi8aw5G)_^T97d|`ocNsEi@j&_`DuJ=Z>bHR17+)OiQGHm(SA5f^|^6K80 zF}fAzsV~8pv^j{4`ouFj!e+4xW0V1_xnuDn(($rPl`#H=L^j%2Y&15RZ0fm={|ay5 zC~N*Zf~N1*O1>;c({}{zkIuoaUA^#-eRyFypg+28)xeiIwe(&GOI&>~Li&^EJo87k zof~6%#ZBeL62fbLiQGY zz5uhzEwOdk68P?wpz{qwy!hshyzWlW(fEzO%H@weX-~$e-ItFim2( z<~?^>l1Ju_-GruNs9RdtK-ZbwP&{`pI(=Kh zpLX4J(Q`?EC;qf+VzdMU*@mT=*Fv0_z64iu2zs0thI3OrP&IEA>elt(nf?M3!5BB4 z1>D*R6N$%hnM&nYqTKGXQBoppAP%El`RlfjGv@US`InwKpfXqMMp$f60Tw zt6ZvC4RKn$7wXY6q=&QP^4o;KV)8zO7;eVTW9&|kTaH-t%n=sHmp~(vRgF>$q?{ZF z-w*o{94bTnwV^z-P+(3o#$>=0u5PJ0Nehyx79LtHDV?S+>0O{E(VgK5`P=>IRJI=W z1z~7hA;aY(ZYYRkr;FrY^lPn_coay4?VF0ZJb<_Vd8XW6RNC)}3b_3x$@! zn4nYI+`9{AM9W8}iV6EB892O)^3n+niNzK#I9d84#BMXJu0|qf(0-&&cE`&3K?s?% z87q3Q%N>8ZV(EEz91Qy%t1af^Nbg9T&Go~a#U?y6L5SueW3CZoLwiEZxM#JZ6&|!8f!k%O#}Di!f(&ct!>e6#7ayKG)K)UV>DatjTZ~|VbTaTLSTOf zgg&i=F&axpa4U2zNy2)WYE;fGMe!6WX;_m^tf~Vb?;eKo8c)c6#zFUU5cIbCp!mxn z1kI4*{(zad5iuCDeWuv@!w3<%-S9xV6_c+lLmVeuBN{C9(2p3C8?Vo`_nt|9I?7bG zy(Wso4xZ+^IA}?<$A!T4Oay{jdBcD^jz_OUStNdNdl3VtP2O02%p0w~?#Bi-DXv7i z;K7TpG5)CQyi`hA{~f`*K%{t;u#fnd*GcmXcd9)JV)x=kHV9{gB|l>X0-%)nWk8~=m5If_~2OJAf9<3 zL{rb0ElYmMQ`oMT`XZTX_Bwxw+c$T`T&u4nYEKmV!XX9*p8g0satbyYtQ!0lf~v@P zsK4{a%|U_a-ROg6n|+b;LWVQ#cOgmrIJ%m}<9hIHp1CJ5-x(7-NQYbgbUrDbEmK81 z6iDuSwN}QCyGGo~4x?%odnWCJV1Dr|^yVLd)5dVfFP%X4#2~btv=z;6&&Qcvn=vS9 zGxpk8V_*MBSgeSF?AlpBYNtx)c&USv=ed5>cKTfsBfDq!u1WTm2ZA zYoCS9yhsc@xd$gSmm|@A15{skU^Q8Wha1B%pf(&UcL~k&wGfRSW9(->lINLPlM9fk zZl@1c=95WWc2*pz(oTfP{}f!?MI-FS1(@a};$HkwG#aJA{!uiH3=^>6-3dJH5REY} zkDzi)06J)#hyQ`|xH^3uAB|jyrXOP@r?t5^+#=FhBvb84vwE(@d7 zP9f&YW#m+5z-M_f>X*h@|hhS76^uhG=kvKACKXmL*;d}H2l$fxKpxECt zftkUWk=NJC4|cXB_Pu4Q5f+7#!s3ex`F9zy>LG{QN+k?@&$3G%^HIK04y&3psJF^N zRiAUvoVOD@$Lz+a=ylM05{M6jwjd=s8rsdyLfc>}&lCyFe8#*U;UVA9+=5vB#@1|J zc2p!ReaTguwcx=87pAaQXH(kKbaaVBbOe#`+z43a#CoDH@K>oG^ zm~P{Y`1D9LYZHg9Z-qYXvG8o{7-M)jK|ZnP3?k{u+Rfyktk-n8vT*kgabx~PsGrM4 z&iL~%a<~OI{Yx;sB}al`K0I!nhg0ZUWPNl*@n~C=+k4?mpZREc!3!(r9l@Pf!}(|| zg=m}@Gh$$de9gycWMn6qYBl{$>8N}_^&O=n{Md+5@M13lU{DrO@|+40r<)D=1y?lt-4Qt#mmo;#h3xa}KqsG2tlx7S>?(JjkqT2> zZ^pbjoGkxVAtAXen*5?kk|K>g%JJvZ#7W`Tk-CdLlL;3Q6j}*>=`)p{R1EZMz=T7FnE^(gK(^y8V$0u#iTuj*m)krpBn+(xE)`s1wR zdwH=UV&OTl>6M!p6<>&|Zj{p%_+m zx$w7szz&Z3DP>IT_DU{BnnTpOP_cHmBIy3SgE;pqC{K9^BiACRR~N7g(C@?9>k3ky zEr6w#3G!^lW0u|~_>LJ1drx-pqfHRb)Cx?3z$7zfRXe5Jy3=U#tgTGdrPpj_;T%t* zHod>d!mJqfws)bMo`+tK9>KM+80PJ7ph{AP)U-TgAGF4}0yA`NA;yUA8*%E$XteLX z3jx7C7~Hla|7>0eQ(QS?c6Y9lYmFa6rm<*hvO6j~mw;2-5i57oxdWem_aNGN6}ull zM%(;52zz`3dgIISXvbA-Tr0!r0o!oYZ7a5v1YzXm)v)!B#)yMS=x}~A&o~L~<}zcl z8b8Z>-55h;ESl=^@!Z1d*(BOcgA`QUL2dv02%4UcTW2dF3MgTf`zFlQDxhtakGREb zwqWA|+j&kH@rB*3O7TPUowao3@l0Ex3RE$MHYUgq z^`oTXmsDlEPE2C*zL0G?D|UT)G^Cs)aXDGq?!1`UmjLT_I)UHDm1j)8yNpP9kZarK$kymm=N4dXg=7 zUJ+5@U3gTLq48D$Z1SI?zR!IaIo*ctr-#V7TY!(9Qji+YMxrIrC{muqiMe42J9!%~ z*nfL-Phi4@RI5*n`JfvspX4=#^nWK+9m;V~ge`nZ?kO{g&B}X7O)AHzYu6E!Qw^gY zrLa&dghkyWyghs!2mP{9tR0K2vJ=o+oCfFO!+4>=IwkvC2ubzlquC}L(4@9XUCpNS zg#4ENOp^aXs#4?|%8e)VBn|hfiI3fVG~TN~YS9feetZV|E@kj&EQEiLO6Y#PfzO5+ z*f#JG`m-UUll>W(_KU;-!$R~taSdt4zC82YhQCHsn=xLla`|TO*<|4(scN_Myt1{) z0EvI~Q&M143X#S`R1LfZi@7flXIhRN!(x=XJ;84F+sK{wF}h6#nl*5+54(!T&rd?# z`8BS@KEat=@jNq5IM}QcV+y-pl5cr#P5kakRW;l(GW&Tg*{1oNXnU0*=f)$5Sl<>` zU4zEr3W$8~z()5es%meer|K4Ly-vaHQ96S2<@juw#4eG&1c?U@)uTi_?F@Cnc57D>hcwT-7P790RJoGfaU&(-K!X-@W zmL4=#|X$7&M$7LOrHsYXt- zdl)wK9ac)8AWWwWBr{z8Lopv9utO_HiM=jjpa6)h$63e_dLtDc}h`~t4Qtcm)*hwihdFn6wiQ`##S zTq%YB5!T_v#K36PahT|)K&RhvjNe;>^-*OA?|YbM4qNezIb+;&`)6v0uO}a3q^jiJ zeoE(_<0XpKY{IU33Y)x_5G|;H>$C>AIX*|yJNDk$`WD%HEAWY==_6d7aoFZl}B-_br?1+y^FdIIk2np;+a>o zc*drQxqB)rY4c8!d_bzoe{fCd5auAM*Zo4ODr!*N{T+P9JVEibuc%kPg0{<3(3c-T zBc8x|6&q7`^F`X`0E`NWW}n3QqVVJm+?<_(d7s^Qrq+^Y92iqGv$gzc=e?xGKB?*g z7finX{*{!ssU)r|U%@`%Jq+GIg{$m4Jf^b3YW5rk>7Sr(TMf<2r;*ra3+7+(g!b11 z$d7bKh))4dZaEF>`sF;cRA8JLGy6?amUQ+$a>`ArvgFj^q?H5GlbuhQ7K?ePbEgfE9tmScpnyo@FB!pFsAXVq4c>QRTJoKNuB@DlSf)l4$fKA=9U7WOgU zV6p8bl7b?!?dKd=9J5Dg={6*LuYlnb4)XMPoLatsXS&Yd84tz`pL~D9+)NqSyg{mp zxwA$ReP)0-dfWzLlUxsjmtSC2`U-<_6< z%oXufSI>2ztI;8EtWBZw$2r$ z5*aaM(U``MR6bnzQe3Iqf{Tj!3@6Q>aC=jSmz$cKcx-M&RK$B6j%#M})4LAUzq83; ztr1?kO-8d`Y_;8y-7?1>|A|;1v>Q5#k47d`fh5NCc8r=Zje3!!^-|U0$G@)zRt>ajsb)1)@>8;XPKp&YMnV!ZD?madj!nxj4@IvZiz%$aDqEnDB> zF!l!RhU2ETJYz0Ilg^lft&~~cefATRjZ)S4y-rHsOKl};y+3n}wqH?v^%u&|)x*n0 z(?o9rE5P4BpzOT5iSw>{bQ$lBRek%T`M8nTk!FUzefyxt!J|mK!_H!F-hpQZ3QRU* zrj4?Zhj;ZQ`K&^3=|5DVxmsJIxY9zQeef%!zp0rtPX2&MPSa%A-S6n4`hZtz8YUi3 z>hW90tr%dSjTTY8aiU=icI?+du5&29wsAm87j>SQBvgTX#w;paBHy{opEz%0olW#2 z@y%D?iDPjah3=)V_&Q9@M19)_94^r`F`e*(XZH2fFj-Pwk5yz3CY)`Dh%kMKT#fOS z-L;bK8Htp!4mfXjO=}-}y>h#`fXDg5FSj}>u-%~$bEjY3-A-bI?qpP$0(4xl# zM2vaNGt&j;Ib+;pzVgdm!ieWCsjBMaPi4Z4781336M6Z#FNpi~6FJlC*=6XOChBci z_nFIH!ncH)HsQ%&>{vCDItN71l(I-#w5&hvxoRe=+r6RtRgWc2s~olhQ^%OMzE$!M z{Ugby-7FgCU?rDSOx!iz%0-c%P;UMMHv8+aqFiV{NCc|M-7w4Q(q7??k)TlG&6Dj`39z*X8306K@-_$B$@If^h3)G$#U04(Cc-X z8kH;fXzT>0xg)!8?Z9l#HY%2+dq`Cl%PbTx_Ro>nX&w`es(BB+3twP5_BG$9McI6U zQTi*)GE*}-D|&@$w%kx&EvJhce$fdhi|Md?i|MivyV&sL3w^zQHy=$OfoaQ_W~5eWYfq^va@rd46gK%NG(5)H*T03$hmUYId5QB`%}nlveSnp34QfBJg0!r`a@B0) z*hJ79PwrCjvs7w3q9a|nd@Z_JJ*2&M%;%X!Lc8h4n3raYxDcHaWSmT@a-G|eRMHj_ z{X-VwrnhHQY&}xt&oI_N%|y?v4n8fO!T4Syx?HTrEw>DvJf86oqA_61^@(hlF)4}EOQou_8ODUnA1S%mM_(Ryj*XkE-akf@cZHHi#(~R~f>DMO*;4@zf-Dcn5nP4HBA&fct zj$OH@b&ibplB#BBTvFV;7%Azt>I7$X=_y;)s6}zdM<^G4g5s?4J98e6oYiMnimJ05>Em$OI~e<;wfSg< zP30L2#xx%v#NEA)HGW&9s3Zevx|^D{te1W1?a8YunBwt zV|gKn*ICSXHw%qJ9Fbl!p52Pw4O8Ey;%1HoIxG^FhTcu#nYoNvyDXTqI-5hf`msX0 z)m^+LWuzoF!iCfARLsw$qrTtZ=Ql~7_n*v#T(9kM;<#;@&?<1x`e!$58-o(Epnx(*zDjwESg=ythi$Ac07cyY@_9vVF(@% zI{=5}m5AtYjJ2cvJfk5nI~ij$z=b>ArhqIAld8r(IY?|SPgaZw%Hzs|b765kAB{(| zp*yr3KF9J{%~Qbt9h<$GWy42RiWU9iU>trP;^{F+)Cz{(w`$;O60%jo#N(S8AB~JL zfyryRj~A|z-QiM|y?H8`^?OI9+Vi!X-qK4f(TFXpPE){Y^?m3*%;gt|>qiwqyQ>0z z7jLj5!ebGA;*sqi zgqp5pcvO^*4)1*ULQ68`nJC5-JYB%qwpWp(jJcn%j(Duwu2f65%S>`oLDwo5#Wq<; z$hrf2#YOlRXF{DVcDb_Ou2n@Nr(q+^TFMaj)){jiTBF1v3Cq_8!t2u%p7EQ=Gx3ah zF@7?~t;-?_jA?uGgQV_puu?5LQXV&6g&dC@_$V`BkWvie1{FMFGm+zV16G$a@!Qg1 z>?w7{%3nLN_1ae07TBQlWFp$Tg@NlW>=7sg<}71gg%98^)ufWaj2Yr%E?N1?Us+iz zCOJ^C9v}xE2Qu-grU+F*0uz>c9i~BRtCPN%l0+HyGTuxw0=RIU)bUJ;whN8 z;S%4c{Vp(>j2S<;T0T;Iii~Gf;G+D5q#*g2GIqSBxG9<-`6bv7$V8q#TfDE&=A*Ha z6`--<0#us^B5sd1*05CGw2kf1XF+q^YGH>5wF@yzCyQs+3rr4ULfhV!zd007G9#s` zTr4MRH=j~ol%C<57$5ITu*kiDsD*`)+X_s*=QTVJxPV($$Ea*Pp=}q4Y4i9v`dPz` zjxy9iXDxQ)pNS1W7FZ`#fg6m8`V=4!H;E>f4og-2kEuyMAAF&V_g3(X({i>a5S{_c z##?Y5q2!}!+VSvF%Rr{*dOC`Iuhwa-CmmFlOFNb4(x^#oaJe5vr+Hn4XoL!Vk1?@p z%;mG2hm!lTQq`53(~4)UDwMQ$ioz`}o2@>vYQQ#Daz@;QVKE1%9T#9ciuDdI>9E!F z6{{{rNwS?iB?E7*qs^c8q@Tpc>AH}P=%Lk3+4Nc~6q;uxV`kZD%GYNcAh9Rd`(|7- zg+q|7XpUuBX zZ5v~#OIki%uyG7pggEhq_EcbM8MCn2Y0hM@8;oi5Gd0wH!4;~byh@+inxnpJ5g*MYf%(Z8-GRI1^X{)A z>n=)FOB7ucpF%Q}{mVZpjP9nh)s0lxv)x?#i7NEkcn-3Sr(sxr0eO~e2RFYH)je>7 zF8IxkPFT|%Cj0Kt;dw=LM)-VO(r?XI0i{rAEmy0n?KRsg-}YoadB~RSY93pNIL|xE z!{1UBM$eKF*WoNI1{}kv{c<$EPJ&bKL~O}Pg^$Bg?9B*c2WE7G$%8yv=}qydu{(Ni z>53jJJ>lIxmS=hk(daTJYg~|gxX(0lphT+rJ#m)Y!7fQT$@YapJMc8*pH4z=eGJ-e zIuH4{1Z*ijhG7Y3VCfc(A4mF1raH&ciu#|Dn~L^$f1!l7?3P8ZK6k{EFYS5ekPuA| z#+WYJDZf0PkdiW~s`Qt)(z%CJdG7gsg|==YY_`O+4Putm^5Gm@pT|N}6NB;viO@C< z$GOfM=^D%7XxpNgDhe%d`b!tM3{l7Dd+ykB#(`(f3egxcX6CXYxwE-3Y5Rl?Ifiak z8ZEsbwoTupNVPf!o6kq!S{w|g`>epmMnl&=3PIvyNNpFyj-B+UxmCR|#qT1WVl)La zyxXA9+G;v`-)=Z;ap9Ry0yBa!NpqWVB{_pgRkc(Vuj#FD?8mYnlAeiD@36)Aqfr=@ z!FB=nABWNOaJ;Puh3T8aaQfhjqVzJlIb=1&E1H3u;{=w^gXoWXm^CsG@>Qukb3$N5 zjOkF`l^b$$AQ{D&69E#%u!pfqtr1#^rd$s7tT2dH`{2{YSm+H3hWe#I7)3^6OM*B0 zSSQoGbWLR-Th7RjM-W4SlQ^FPrmB1dGcGQ|53Pdw{8A17K4 z#(4H`Kh3G+nLnDRC1WCWhjV2;49JU0sj6B2NafF&{Uj02oVdz47^ChSgjMf-7y2y`=FrPei#@9!eWFwuHWd2 zA~&{A6W1HB#yGPpcxSSFwgCv8Aj3VYWS;3HF!qemO|<4h68n?DyX>{L*;M@bPA%B z{Y+$-^ed5PT!m+|mN7$j%;U^o3?N@`N>$x5mXp!*nv>^=$4L@P<7rA9OOM~hGfjzO zR`u*T{Wypl6+5Bh*FaD7F~fLSTNK?~fVU5fkolt@;#q3ec5fBW{L$HLVax!36RyWp zLn6*z_Ixh*h0jM17jlH0wY zANi6YRb?SWx#8tng>UUvo{^vSo-fXSNCww!Vd&IyH^LW9!KyU|*!pQYb{F+V!5A%Q zzFmvmk+WC=%ul}1b_+}%V_tq)$k`79u}PGw9z?w-snMFmq-8K4jXXM#?***PW1z>L zQxhYP569dwd(dj-0<;}G8uIOPQDi&-!@IXaTiJH#if7^6d0|QQj!D5m?t;M^*)POk}QY<}@HBXD-QSe~D%}I1a>m@)&*X5vUBaxHY57u5RNwfbl=sYpzpUnw@ zsb)+kGL{=OU?!rfah@PI{d9IA!|!PT23x`Z6U+r=J; zh~EgG&I4Hv?p!u$)I)Vm2h3+Lj*f%oz$e~_XO;@j<}G7p3^nA2Wz8YEr=+Ups}~W+ zEtiQ&e``@w4{hKd2G{fZP+$}f(|}-PqBw@+|g<^zZYe~) z6HwqC3aySlEF0nol9HteA9N50yG+OGiC!4EW(tPrjfSpTBHrY%Ox3w&Jd-69nz|E9 ziElQNdnK|b+gTOpw4zYlE@D^f*u?|?T(``xbKCx zx=Fb2yBA|-ML=X_2YnAK1X!KNqE;-~FMlP^v=O4wX=17-aIcD169ZPEXY~$~OkX%n zQrg{~jJg>DkK1evz=j;ItxlnMLKNN(^+%3IJf27S;HokR-{((9fA)4A)yfnX4@*!J zn~2z|O|aIU%QKb2+p`N}YP33V8SB=O>|<XiT9i%-_J_mD=Lm}X`=M># z8P@Eg`D9qp_XN1v_~BW_F&umBiMFap7*AXY+mux}d@vL3iVot?WFgzGnGlUWW8{TD z<&h&@$*Uu*&;~_GdTDi+ENr1i;!>i}m=?z}?E=_ZS~5n-k6`x;HVmmbiIphoPdHXJiyH3I82@|osG8xX7Jg{$`4Ij;TfiYrCtCGX=rDYq*b2j&s@3<tnL#*qmz{>ugJ5twLNNN#D%_tc#brZlG;FrUwIgQ{ znBjv*cZ8hV+X6F&F@yC~a+44@@+_DQIl3zqCLJot)J9i68P;dmN!ScwS*Oh}K(3yE zULjG)9+3>)fN*R!@x&Mw&D3@4(eQL4EH%er-H^k$H+(xHErm_5p#no0^H5eKub;n@ z4gc6{EnvFx@yXGW^pG<|+aMkWS*M^qGYYj=vLO4C2=%vz;bWMF`j>1(I{1Q#`rvJl z_wvBDdX@-lzX*Li;_*)5je&K-PT^yr3QT3puJ@nh{Sx+&GPZJi*}0P>(|EtAbVUX+ z8g~+=NQT9@BhX4wvdjjSc$pN-*z*WVIE?tjnYjC!Wz}^zMR4i>%zk7Jn@1;c;j1?u zvEz`MrnudNv49n0W~}QXuI{vtOkqrsnjThPpCmDI=s;6hKBwCRmO1=^^=IOXs82e} zp3^bJwaSFktyr{ib-{_@%OGMO&fHLrVhfSs&`}hzuaM=48Ro$=a)GgBjPjGK*rJ&? zp}VB2GFKvret%tD7id6&UYl^6{J<(TYz#TU~evHjx| zG|svJtArD*?OcK7;B=^WPeK=#4XM531cuExfY2FR&|{r1uAF3tZl7_*n+F*vU6KO% zj%&rj$!$~twR5}GBW?~GQwO)#CPonXl?J2m- zoW(PH1;(E-oU4>uX}Xc!vBEM_G;1Y_0c*w5l8zF+Dh0ourhOt6#$mVkWjmwx7m)3f z5ADP>7>4+LP4#1ywA+)}wzB3U=o}9+d@~%mPG>%E0#y|BtFSkE^MBXYc*lGG~qqnG&JQ8EzsPPEjI7qlz*_6hi3?osc9%A!KS2B2vaA&vo{G zzQ5n|-2Zsp=YGBJw`=XS*IIjBpU-u9fbFmtsneIhZaOKv@9jd1s5V%N&)Yv>UjNBm%TD5p>cb+g8owX#V54tk3lLJ&! zzb)kEPcBi$u8UzDI^^NT*8yDm!G&H+aP9Jb_{^J(XwDz=!%m?txu<}+C1MH)V-VsY^JFJ5mO}zm^H#LX zzP1ALi*WQb$wc;h@W5OIZ?Itg!ier_Q0jlkjG_x%xd{&&?Z^C*VC`4n-BbfiV zf#N-{;AvEZKqcLCral!kx0^?}BBL{%2R}I?acm%784SSL1?#aTBNVq6iuVF7M9gc# z%-`f7w{aTHbm>-Np}HQKfn?^&UL)UkK9P3;pK9&Bh5; z{-g2jxDQV4Cp#l`H4R^!h={GC>^ez|MsE$-RV6zvg`dx?t_8lzj- z%1F%TI`uhR{cj`Vcm)z1X#m^Od*t>KHL15T>7O6MZ~MU8V>_-5h=FhYb{txsh^a1D zG0bS15KV@NX+s#Vq%hgh1AUoKZ39$i*B??UF6PMjUJE5^1+mw~=Ws})y{51NvE?O5 z8+%_6!`8o{-|F|{I3Iw@SZ`<-$0Bp>8jOCBhzIql(AN?(g&W10W=@!iXSC&U<$ahW z8ni54rriCilj6vP47nPk7Q?DB6IN70FYqZcwvxDi=_@q1&4)5E6>XSgbZ$z7oX^7C zm|*yI&BD>)x8R$zO^C)1u?8zsNAjpYp4^FtCZ&vv?~^#Esx`RS|z=(Cui|H)EY!TZi}@~bFt@soYg#3coemW+DV%^AO_-UMtL1;c4PX)p!~e}?40^U; ztDLo%noW-d&8<4UYCqsD{LVke=M9DM2z&#Fjdu_jC&!E1=g{|PDwqj5)K`L>Vc`!@ z_wEUF$_@yaSFC`sC(MRMR_+r$gej#dki8|4@gwcv%gblwCU#F?RrFGjU7I*pBW+75 zO!OWgEximWn+l-U=P~L7v(bCC3Pv79Na%GL5idSq!tYAVv`!Q-UgDrlCCuvs-Q+cH zBN;=Q0&ahHu+QW27$2>@GKb+bfk(cEmgZebN4yg>w`!qsW19*zKDdjE^!w8CG|Y*< zf}w@C;5qvY=EZz~y~zsSfhbjJ{86IzZ_yXKu?nv!0bPO!_Jk zD(Ag{U-UiH_}UbAn=tuN-({@EbSAn{s^YhsDy#YpV>{|iW1LUChQ+=22)BKLz8~w6w4qv15EpK( z6%@qvrnRVAl7sI$_pzq&G5))G1wVTHhVA|;9Cy1QL^FDnfZ0cw6VvqMi+txW-5aE; zvOS9>t7bJZR_5;+!x7~$x$_Y=Kc13Jfd+##w|%2X=DVT}gMU6lW!`I;aOns?a~;cS zb1>{cGP>%1$JWiyQSdfNz^oZ5V8RI#vZhuR*=-S1_(7_=_vtR<@!gbteM}`Nh{G>_ zCPz^zVjuiM^Oujv==mD<&J8Ge`vSMyyh70RG*GWjgn8e@_A@D%d-N*;#y*D|eFv$x zwLK#QOdMf;7G=tQuUk%+_fl1^wi7FF>c(o%Y{feJSHt7kS3yDSY|(_%uRp`FHFSXIbU$w=OLy&jutR$hYOg~gwgmlMmA@=2V?qJ zs#?yEU`#7Ev!2#ktksSWu=xFrM3&{W=lp}`W0GDcRifnaZv>90KpR9N|SeJ`i9SUsuBCM33hYe;yanj4h8sQ+sz}`HZTGw=z4r#bp?*~$idS- z`vpvfjewC6X6Y~wTf5Nz7@1tE8ce3Y;Z{5=bLr1|&i#V)&3|A&{yp6PXz?ZOe<3*V z11=eB@W#8}Q~z5P6qonm(dNS_pBxF7F=4P&l_SV68=jh?U15rd$tBEaZ%w=R{@zTN zi&B-l$uMU1*$%A5qcX;hWTU}Ho2hifM>vJ*@C7EM9CrAGvyU}-wY0aM-kHVAHsDX# zKHM}7!L?W^F03oTpE5FR{@f!(V<}<^33EudtKGZNeoWmdsp`h{a3(XLlDU{@#uk@+ zL#JC*!prqDQoHN%D+wS)5J8#27~~XyW;z5HBwV1& z$(;g5PsBVUOxC=?b^&t&n65{qs)pKV#;;EvGj~cEV|Dx|e)rYlgJ*rkA8&nLcc})i z*4$R+>F`$cTUO0ESerS)s%jU^shwEDsbMYuB)B zAL(qQszn=nF!P7~Vgh%bWYoIO@oTkt^Op^j$85ouCu{N+UmI{|j2{2l^c%7b9zu8M zKGcpmhW}2)p;0>my9a$oLKUfr+DD0)p#tU;VXnXC>}o>xGdDt{DuwGvCbzSMt#G=- zBu!~T*Q+{w#jzi-iRef^JpwbcpS(n${7}x2|aBI}%J*<91cdrqz z*;R+<#{a^Cdo6gaU%%kr@d5fS4#dCRacF9J7;Pwmk!yY+s91$IQ^N(!#K8haW384( z&B+6HPuOs#)K{w7rc=Z`cRS0xPe05&AF08!R{Ffw)jybauO&ZrvM!%y+lUeE4f(Wr ze=v*9#asK$c%2u5yFnr7vG^eTBT1J><_nBACPqMEDD!P zg+VJCAVkxRFopFAcHu>FjDe?A)p=J3Wx`5tcGsF-Oj}EBK46t0ziy=_e_>r4KI~Wv zzI}fU-r!y=J#VGM-|{lzPq}FEd!%jo#qkFGWCKn9d4(~*i6S+s zQb2#p41`;4L+!_PNKSXf#N98@<~PYNmy7plF;+q}HiS`GB-@@keUb@VCsh@MZdPu1 zZNnblsKe-%=!ViCr`Vg zr1Mnt(0q!Npo17*v_Ocarx*=Gn18R{j=Gth%;>L?s^<1-Qlv%D6u%-ambLTb~S=RF?{QDZR6tQg^?frz>( z8vhl2g=i+IF`+9nY_n6CzwWfHZTFW?bL`2^jQ5eu8m`Bee`&=R>Fe^T<4pPQd`sSG zm^L5uye%K`M2FvcJrmWAgW+&|DGqO*h#gLLFx~MO```=PUgG8bnf?N1CSh{s-N>rU zPh+B2N>vB$j8F!|&12ilG-UoB)#G&ojrs2xy8Mfl?fKLO8o-O%e9>_e-qKf>*Pvsd zYq1q3n=haQ|3sA8Q>BsShtR*d870+r!l3!~6EMz%x$fg6o7na;6XGUSC1)&D4nO72 z9zWM!?%Slt_tb99x232w747+=pjLd4DMhia9lxoY9{=l47ADT@i&liWbeTmT&#qY8 z?JgXiEQ8a<|2KalVpb4lK+r|m;+#w-VTDu`m1wK9e72Z9^1BTaG+3V>v8pw18Lh{6 z>S4yet!>5YuF&B-Rkz~<{Pg$`*K26`vlr%nT7XD9Tg;fz4trt?@ZtJwTzO+HMB^u7 z))S_6>3do3Z8>vfnN+3M%2Mf-HIMCa%UcpQQJ;T)wKZ>BsmBkIn(;qJ8}qmJ=$>J2)P8iKbeYt6fih1E8 zRW;2|P&DkaV)?#dl64OH{It8R`6vJM_@ZJnUUQ9zVRxDGQTO%uQ}-`}{b!6p2PUJl ztT!~w>$t9dIcOqJLGecVclyUd#P|`Wja5f^DtnVLULsXZ-%zSJso9;~*v67kNAo|- z^N%8C!A>21Vw#AF%0CJnznk0|lOC{tRL>zSitG3;85d_8quU8l;D1WQgb-%>{=xFp z3wg|nMN(C#pef48$KBW#78fMyDWJxv2kn2DJ`VpE^Qa4XpqOjix9H)J|M|py)85X# z>3I<`zYOu_k9cR}B~Iu_!gSAYlxvN@!yH&BRrwtASEd;0u%F(WGj4nI_%Si9`K$D} z)tJAtjQJgRw1sGP%+%w%tU3pMGbOjmeHc8(6>=UWE}Z?cRP0~!j4OOD>Y@Kx3KRM` zVG2p5inaHd>;+QQ^R~m3p-C)z@km>SeW=T4b#KjUe$eIb92aNWEOTvs#Bx*q{sUcp z{unvBbgkudUB_bKF>M4t+QkKb&Vu=hPaONVR>jwqU2V0534NA+yVU9oZng;J8Y(&=#&;i=v}r2a zoNx-dZ`N@;Cy4brE5t#&LYUG{@$#ohFPI1O=+wE}RQY-HM>fu}2Q%iYHh;^r6@PZV z4*zvyd;a%=mi${zlm9-l9lwKqD>#{njRn`a33mp;_}?Y&?7dFh{b8wyw2kC6|B9-i zQW29)m}L`E3v3Cq_KR_OB0ggax(TaGp2+qTx=uREFW zvzBV}iHXCPd+bTj*5d; zO_=IViSmtpI&3ImxSYN6TklF(4a1GLH(Y;VT{}I#_){Zvm$c?*{iDb3QV+K$E%~&i zjqtv65~{;>?9;Z5oV)b4;(qVG%Kf>CNc)?w(A+*pz}yulbRA)~n;e&CT{d7_I7wAi z|2oKruh8LKy8o1=7=Od!4|KRS`iZSOTk)2)T6|JzEtb79q?BM;9_NyK6ps&rvL)=OR9vM#4C4IW51{!kCSq34Q)=vZD5#K9`=PsqiEB z-Htp>UTr8dI&Q?DP1WFc&-oynI_Gw(2gYY1(RM#q@~$5eMuf5v=e1dV9T|RKjc4z; zB?-|;M2yZlGX9S}Ay;L#WBbwT`MX~X<2$$&*KuL2-0@)z{M?(7ZuuEuI}CVZG{N4Z z3Ll>8@ivERF{bblB*$NH{iaUG;5V~4cg26)oHGxxK6@V3zc&?@D2g=*d&4Fz z9;B#AC__zigYfOCHv4%beZ`H(&ym$#i+7}JysjrokeKqFt1+ApuOA-N#^oZHKIk=m zI)-zeUcH29x`|W3f-v3-1LcQySg>Yv7PxjQhZ%mLne`~&tBCa@n|#1$*taOd+gL5$ z(BhMDXJggtpYXxnu}OwAmx8%TyDhN1;h*CE>gil)$}KEk-ORR&FBYE7M{&OyNEoY| zi{#nXec6>BQdRxKWH$773cEVqUZK8EGl?bdI$b{uG0;FHTPt@&h{jIDj3msY7f$kHM=jZho2064H9eRKi!<0$ z))@+|YEpD}B3nG&U7G!9gvEj~q5Mb6fp4&Q@)%b2k5KibC01Lypm*^s&Mm2dJL>fo zDRxh}oTs7@^LTe*zu^h&>32x_PR1CI%MYo7 z#dqNn(sfiWrnmZn=|K-rGWadH+bkk=1K{)d9+$eA&TM0UBH&tg+?^p>eiw8TFb;&7 z{(YF-=HUSLzErBpZzZ?$sC=Yo++L;ddXoo3#Zx#Y+=bVEau89$4D-$^d=4SIFWq(a z8}R|ArcOA#BnB-i+asfD9`v4T^HU1vU=*2})kh99F`7Aq36q$~FTb#4uOF1ES}c!c zRMT!K*G(`~dJHBPgrr!gGU7PyBWlJxK(#BSwYe&cymIl8T&+*bF>~NVjdIQ;Bc)%p46Z}&P-QDB$n>Zj8HRa+h}|sjCwEeNxC>j-e4fqj($#9tsJiTzI6JZLM!AN(v3-F-&Kz4%2z^qH8SENre7{Wtc45(vM+eF?>Ii!-a?nTQE<*p z#>meGeB z@eS)DYZqd~-d0Lg-m4kbaLlso>8V+YaIz_+bh|-*s0<bnbci~CTpE40mj zjK$rL;me>5C=_&s+TkQsw`jx|ssl0Q$9VxWO2ix@%%0&>vNkN#V&iX0RmXl$WCvGy zXW!t01&rF`(Mb7c^9^*v{!1xf9CaVSl`IT%kL1H_YYc{sx`dval2CczB(`TXpy~Ew zjPN-nV0N|>qKQ>w){e8a(yM1K$zt)e>YK-e$N!FBsFBTsMzvEz^H3< znN!w7jWOFEh4m^w>~0Fihw{D9bUuW4Yj0qdixNqP0t8I4iGVptm>%X5yN9F7n8>?Q zRnM_=*{tr9v!AuElG|U)5(Z6;sqgSau#z;+OBZZD9v)ZWlM#S!^Y&n>au0rP-wUs$ z`ytz$iT!oi7`@256y-b5y1Qaj>qCosHR{O}kf4%#)s zq&LRdjhdIu$SImF{SxHbXQyOuH+U;?ZkY{>@wtLAMvZX}&Vj{intg;(8)Fvj?~VTB zrsC+<-sohz5-yc)7#Oq#8$C{=eWvJ>jubIB2vdB(!%oXTjfpIfs-_NtLQ*z2Tce$! zAWQJrbW1QTsR!-!douFrWC<8MmuoOI{lU5Y8i0bezqqaam%`O!GP2?(qxoSHZao*( z-6KWJJ;E5+ue9527SFiQ6tL3qW=hws%%=k11Yu6ZLlLDppy@IR6-i=WYt>hsG`U;o3h7&l7ra$Hq2tZ_k8twTl4V zKb_G2js_mxia_Wb(XLQ0V#)~9v7w8d&%_;!jY_I&oc&Eds-Je76jB4({qZ!=pf_(^H zBigZ9F`8yICQU1=P20}Q#B_Q#FN2i+>+Q3BJ}sB1t&8eva0T=#dfj+{`UyATJWqiF zMLrxJU%`{W_saXh=egLem)Ph#RLWq`Id1yFD)zF!A2_qsf}1Ep#I#sX*{E_ona)fN zCgc(=Hs@L8%5l2cF1h)3>X~MDHWwDV(gh2aGnMve&XWliEZO9Ad~@o+F0%j2IgQ@H zjXg92i@$&3o&@`Ie#`gb&4z)(XVkv-!eV1WnD}SWvgKW$N@D5q-uUKer4CcC^!c1D zPmdGLehzak2o@~$DzKipMy9fxDEUI(C|;_(W&Vs?de?{>aE}M8r{K)D>Trc6yYS*{ zAK}@2HWM&i2$N#+RF-z_nq(9Wnud3b(&fTorO(-awpzOsFmzQ>KKdN&&2MALJq5Bm zUq#`b9J=a0ht2`jZ10twsQB4w4vj9DXaA2&7<-sgIUK~=P;KG8@ewh73FDsERzC7s zoW$U=RCQL%PxVwP*I;L-pjv~;f(1+VieA&uOQ>j2pr-0Hj%tC^YTXl- z=O1yk86MbjUK=f6UEva+2jS_`U&5djh?t>-;U^4|_q@Mf5=Fab=86#tZrL!UOT4|r zMB^$IHM=Hwqx_z#kT53$1!N&LWV29kC<$gL;;wv~j<6y6_}Gp#YHz9U>ZV36Xmun; z%?%f#IVDbLJHm8~A2073>n}M@6WZmEqawrTfTHYD54qZc7Go9)W zQaW`H3H_J^s3u?MmVX?Fm>?b0O!7yYLEUkChBoeJhvT8KSi%2{I0eQL=3d=Qxzj#B z$wk7f)(lYeT%%-s3i4%Y3zk}?79%L)nd?r!crrIwIf4fa_p}hxV>;CM}2l zTB=n%co^0m7>woXqoK1XM~Egs#7rm57avc#xpSz*hcKOXY*MZ{?a%sjO|rAtMya`u zRM2!yq~P?j>vWz@I*Hh=a{+0?BjITHf%AVUfnQH!gxy+-2ibb~JJlE;6`oWIQ7mJy zutSKwMv8nsVV39y$RqY1mkholRgDcWR(`C_WplJw+nLNcN%zSqupz;+{qA(^&Z8oy zB)P7bcpe3t$r*8a5Y8@jg~x^=u>5Z|e*ZDUt{2vjblm~>w97&?>3v_I@5o-4n_5 z7moGIPeWE5gwUJ)5ft1F)*~sZ?yd3gat*g>fjuJP>|r1kjWH|5Q>PDM23QBkQ|$Da z(dXzgWqz#WnAI6JXMMe0()CD$e?3l>diNrD-8pF0C&2Y^DD-HynUkS??)V zS5&qLIR?W^0a$V>1?h*$fYE|1S*uPWy&?eEI2HOsjPW9D7+$nB!knj1IZ4_Y_^%iO z)s(jaCRM~7A!iF>(YURDUsJ7a=m{#wL0h2s1uxA5TK6onRmQ--Y=`@#jY#%n2w!(sUdcvs_ zVl?T5=^V3MZXZ99(Mpr5+BEKGy8n(~%goFb4&OqMJ{pwo@49?Mi9 z?EV{WK`$*Knx*2`S{`9i;#v9VNAsDkwBIa`U&+jF?Zl2wn5dBb3Wj;yQKSs@5vG9O zi)f+Xxq8r~O?wb~dKESgQE=^bN8?BMPHxicIBxjF0~l@7z_q_19&STK%tOL3g?;2( zw=ZMzY3ba&{w34pd^dLPl>Q38<{+vCc@({4_Fzd{`VyN&CW{1;z7b~J!`=9ou>ty) z`CPN1J-)VG$+cPUPc>6QkrMcsyQ9-mh^Bp)5cSeoN|^40d&qmfb7wk|UZC;M0f~-x z15+}@Tj9Doh(2v&p;NRQ6UL;#p*#wPCB6biZCc8H?N0uJY%V3v0r`8qxrN!0T>WV( zp7F4bYb0;3`kW>azoe@ObD~=h`N^#tn93Zf>h66zMYk^2?4$^9gXMyWA& z-cc|g>5E{46VM@B*3z9@soT{JuKnCekk9t!_F13ce7!@Focfy^Zz#$~9YxG%!gMj~ zBDd+Yh3WZRs(N_73v+m&C3{16yuxDrK2ku&;@esgW6>!JX^(vbjN0jS{Qg?hzqrn| zIb)Ce%`3P)1LC<47sGKj;uF``TEyHDpUp4AT=6!RXY)H4t^4%eT)4uNHFRY3E_V3RK2rajnzFVE)imT>tiGx%O35&EkF&7g=g54B8Db z8m$dl8qZ_@%Chvl8UNR$8oKu%Gjzx*$!aG}0V8`J^M5dgS0hny)(4)aM9d!hrMTAe z3YT1JkLi^j93Pg1QTj9*S2(EeX@CtdQNhzMDDvP^xM*dndCuCxI!u zI9skBw3Or+tk@_HnwJ0nAM?k;1@=dk+=C|6U>E<55=C%f~3~4W5u8J5l z!ld-Blx3LiVU}f6(rfPuMaH#Nj7CWDH8m!QKFI$!Xf@qL%#txlIAZOMq4zexN&hpq zDtN#_k!T{CR$k2%y*nc4c#_bttAiJt3<(tx3KekOt&({npfkncwGax zb5JeE!(ve^Rqc$+t zj}xPDUFi?IbA(a(AZGYR{ID2>d5hig#-}$f9PEpi1H$l#TLw?_p#tWFcsn?WFsJ&o zlXvd1omo^WRn`3|k~j4)Pz>FFnNhFM>Os5l%@;MGXw*}HR%kUw-NYdkHDF6 zv(af=f7rxy$BgLxczeTCNGCE~am5qU>MA2fIvg=n} zR=wY-C$xI^RAbbyr`jQ@#;AACi7wkP*=hj>RBb|y=S*0P9EHk#p{Uc|izS+Ug=oBb z2$)5L!IKX1rvuk8nN@U#-WbBT-{h38x4W_FTooE;g!sfk5W}q)Kx`r zrmk}J<36m(4ys(KK}{U!3P`w z3z;L0bZ4XND*4vbTDc*Llsrd|z_35L@J5KIPR~_wuvm2v=0{E;?RXFxD;;1qaVln& z%s`cV4n{lK;B51HglPrgi>J6k>x&pEVUFGJCST<^oB5?1psGANoDE+vRjIHa&HCj< zQW^F{cs-`g`WLx~7ADX;bO_yyprfrrxiy|L1}$e6WLMw8Z-%zkt%U()*m3@;xO&d}-- z6Mpj!ApEKWE_yG*i4aFjdAt&n$B)FYH7jr~EEs*2e}$9Hc@Yy$82wZmd4L~3Cx>!5qVb=k#gY(QZAi^Vb4(Ht+j*up=oemHV!JY zW$1j)lKMwZ#eYG5SgP|;!01~D6FP}7r*fyrH!R{ATiQLB1oc(AEEne|Q*sM#9UKdV1_Rgbr&Q5%*#-zW$qvh3qywX&6Fvyl0@^axYHTh7h*Iygc&epn*3JXP-Xy4=n3D!PVd!4sS%Z$Ws!dzH~ObQD~U8s zc308uRrHU)%9 zDYBMtyI{q*83w4nrHy9CXCG3y3_C6N>`RSL_MSsh>=7yooFOmo`cB4Iy!Iv#CYhIQ>{qQYStHFn~W zyLT&W$O7!XMLZ4;6EUv|Gv$c6{6(kUOeUF@{<_}H${+koKD|2>HZ>L%i7hBt{&x_k=01 z>nl%OXu&j&rlND<$%>)80dsK0D23mo(}LeKC7906av5Y7Q{h=b1JdIPJRM`;W#f$_ zUOrfpx)m}qqE8&L7>;ue!X)}QT4)az2CY)W)DwmqIYjRNvnLZhJ3w`V`KQ=-XtCVF z*-TNhEtz!CmtbWPiyKmfaG6rzNiB9NuL|zfHVcx`j{Yix=A3}{z)L9G8IGm1Gm+RS z2lLi%6)XxE+_`Kd-MvIr zL{6aC{u(^n#3QkNB)(>aVoqrUj#MS!hh89R-P57hMMkTEs8Y2OF?t)RhvWkbxy{>t zjLktRZy4^(ey*9p;3@Sj-q@Fq*YzL5on689u}Y2*H#v4S zi1nfSiP4x7#w{yKHtVSs6S0QMx1ayVBsuA`Im?er41LM&OMXwko+q(w_HC$d2bXkB zp-u~w{K`Cu%@&t&>)L6!Pd|%_TW4{ZgyTjNpP*OxE!_TlM2IF#JgWC5O!!=HS-NT{ zleLh_7#u&!_;AzMGyWZ!^bMEcuqa397-RRWK&a96gRI!b`nj-bdj?I)B%HJi0ly&< zYkEe(dh2)4j?~b5<-Z89=h(hhLa2#xR4=>$v@a=>s zhFu_HMiVB~{AreJp&hehV1Q~&Q){-231tG8A7g9+vxFRhiF2Azrp;* zypJMj%_(-#G6iG*P63%p?TWkvvovZ=K}JlI^BGX5@NVo($AqI%u+VqIw3)tWGjT1M z{+7dXN+v$h-A?)0Wdi1l_=!7}FlBdZvmD!uXZFpY3C-POW`-=^MXTir zc<8hqr?>YMFiS;@2VuG&y^wX#bTJd<6rlRjFqZXvV9her`J#aQYO+ry&?0rCp+|+# z$0N_{x?uK`ZOg{>-+Qrt#9-9^N5a=&4y)*bSkvbsM(FKBQ2+| zFJ~5y4^Z`ed5$qH?$3_<6vWt_px!s;&nXv^Ls_UQ1b-$=7JCy`&aYt;pM#|x{NZcd z39m0t#=geB_;si!E-O+|bbyLy^%ZrUnj&Vm8eWlW(nN5Iv(hDokJV6x)vGB650};9jj76$0F}m)I>qwliR{Iw5t8Di)aYd0OL*M6iOBT#a3o)i zy8n&Z>80)%b1VEH288s7t?_(x95)mb^#@>r+a>r*eNmgl3Yh0&G~tBV^TX?!JL|`a{R!*SIss&RV@TGb!OSyw7lA5|AQRl8SfdR#)?tL6CHybrUx zug04%PKa>4kACrCn5H4ht_wv>9APG(9WP5b>Bq23sK{x0pfclYB6*AtR0aMeDOBF*PfH7O8`ayK4GDse735k~`p1&o3C?Rk+fqcktcj2jOyTUJvg^7M0x zw6~#bSrjDcd&#i8xQr^n=2IH47E2;%0KbsGaL_x!A!%@rifktD#OU5f5w$7+!nZ>n5w}=w^wj6S!~Catp#VXT?6?C$);!+ z^%?0aUZdc{9i+IthjY>$+$V3&{kNC!J^l^`?mLgqmy=PO(t?k_atFH6mj%o{aZSr5 z%p24%Y2v&VF)dx3>VJZW^(E@1u>F@=P&XG3Hs=EO7BQ>pyNgWGbK z8htj}+ne#6LQCY%N@^c=Pbdy-|D{Z58Z>wknam2PGmK>$zEJ-GPQIwYy~BmrP?nFF zrycnb_Engc@L0gC6fw^T)45-k?9`tm#t{Lk$igQI|J0T&Iqw;@<=1)QTPmAJR?-;_ z^j%XSwAr~awpQ>IK6`7#Yur~MdR;Y~x8}k5S0*yLner-+7br%7fYBB)6@=l&RmwuA zCNrki0V>Dk*2>C)BsRtK0%Nh3N*qhx2~sO{MP-LKRYDEo^(Vf-Zf6lrN44X9d>`TK zpgPpo7vbrOo0#0goY%NhhO5sW3YhldJ@hBSoLOc@pSY>aYl{HYM2VGhW^y=t1a@uwnDxBZM3OLaF;ZG=~+#kVKb;+Lk$FGyue(!CSTR< z49qHT!SL=$49<_i@=GoFQ$OYKj6NeovtCTE8WLtl_b&2dA#x_FPO2KeY7R3kZ3UYi z#IW@b%aBw|&dAbNLQ4vDiEy)TFR=dMA3;0l5~$0&X`Vq_pIZnqyMX(@k74Ks1KwfN z4RrTU6EG4HV@jAvb0c|UZxz$2oG^svgC4oSCzSrg7o8|Pp%#d@Kg2_i4pSLnn*7qPSMj&2=w6kHm~MnQmRKr#=x~F% zL&}u?l^YrB54BA4`3Y?C`*(1z{Eei2Z*i`l4lk?wfkK^1gl*L11F5&iha6qL&7X7V z+2bDat*&9sqchM=H0Jl2-iNA{7)_;!=}(w|*(I`qtGUeS>y%+1{6W%lc?mOmhdrBg z>?0gD{1xP*iM6_X>3@x=h^oecncBQ-d=08Kn=xc>Gjyo~z{O$&YA@eK8fnDz-fA0I+> zbqcJ>kw2&*7$avkqyLOFn2Z*!iz7v;)da%SIn~Jqbi2!(A|+(s3@63L4@peP;$E!% z-5<~#O$`DPzT?jvBfe9T7N0%19!uZ0;Dd|kza4r{4Qc~n{h2C}CPZPWi7$#De?!lt zMC`vOD!N9u6~3fr5~e4kDKGAOpP9CiGKGPbtliRWjF!ThwVBr_*yF-;e$y$Y6+gsX zhYx@I9gA}f`GeOR5#jm-n$yPcB$keYUq z_f6SM5Xs(^?gso>Uk(0hU>kn%DSh5KrU|L$#(dX@8vL+9G7MQ^i%ssUsD0REg)h%H#6quT8iC4Dm;PG9KtuBkkA7Pdqv611>U8cc~G9DH0 z7>qN-^U5IBM}%dztVtpLO`q3&+uM*mrJu%OU7- zcQ9njOyC}T1^ZLxVcth$0dq=~s68KlrX|0a3P{#=ZO0eA*X8wZ9|K>njrfiIQFW#VOxiVb@k1{|FM2$J zCW#lsR;`3*6G<3H=OEdDk9U~Q^lV~RJy9&t>!}#k-Cwcpk{*9+R%?C`{W)Zg+5d5R z{Ur<5elnZAnnD%(dVb~R4(bD^QJryJ;}_>QGYv-=1|w{BglMLUnB#<5v*Ls-V%{Al z(^0CL(;-mO%DaQ&(D_7#+O#yQsx@Cu9x1iW=WBOkenf;0ul7cr)zIe^Tr9HUKXDWG zSYoqxE6i!ETdZ=$P9XKqLqwY$}~mu<^n}x zxIX`PN*n$Z*?ntgbl}&mGUmtJ*5Rk!Hsvo7T4zWiW~{5_{9X@*)T=96cKO5o%TU4o z)GP$nbr+(^6){%`^DvN==`Xm=Y;%>WQg*gr!it>~Pd64R*nE9n)2$8P{;)p(+qVPX zHbcZL_$^`zHl9TM_*(8jUyy0J6S`aLpjEf)_)_nHw5MV!;<|{*CXB{63z?(CZN_z* zRQ0&pI;&$&vcxRnv4Dy36*2!}|1aii`}RUK5lc_w{-h>uW4;~o%DW<{v;_*Yb8s|b z7UD*Wy3Pg>lTR4mFo|r+zuU~4{Zf^4t1!i)wNgekvrxe3?iMiy@gjyzBWDp|QmyrQ zjnE4)+VX=-d@}({zIDgH5FMNvaufgNO+l~aeS|@q)>3#j#e@lK9VavQyu+MHq{U|I zN@ZYZIKxj0Q$)Ck&qh53{uhnfP^QMjSL^ZqI}~`UG{K}!RA45z7sl))nH8xd^EcSz zlb#sOToLn!~)Bx$DxqwCWbd{ceYDCQIQN*P9w} z>Y`zHF`Byp4?c($$1aJ_rj9V|+Ya&@E{~Y!6wRJ%T@;B)A?)#x8i{p+F5kY$nEy*2 zHOn<-{H=Mdc-ssu{=lDh{PlQU{!c$rMDDY|Bh%$n3V9%!FSf&+-p^^H9*42PX>ypm8c&=btwV*}D&X|AYsLQw0H{(xSZ%Kb@@w$Gr zjP}swzf4h~VptOwwP`FeYcvql`wMrw^Bq(=cc5BO;;niM5u@Wt6)wMYmUs3nW4eUX z>)A9~&J0(vhs+-`vzY(8bgI|155_I|T57TLL8l!bbV7%>-H?Z~`JG|kY7Vac(}Roa zFYa9ABlKC_1FLiT3(?#VF~)?s*`mLE!N>PZ$YDA_<#;PjSJto&{ogWuwrKN-H(T;* z%dgrbtDIoO4+_!X@9#C?-O1d1=>263Klhf?x3+>q;dyS{!xNmvVJfuszMM;3_Ek)* zh*O{=VHUn0E&o(r$E>Aj60-`FPSG#fljF46-{-XW=dX?U4i-IVk`*L$udDS`gwW1?CC{2@B@1DwBEq-rAJHd_}e)uoc24>%IEneO-6YtHH+~6() z@nF_r?tT9tZk@9n64z{QfwPz<>LISs0||3p?jkqU_{Vq?CMK|lV#DQh_QoMSwl-FS ze_n0CAE?yiuU|Cb6W6!k>)rm~>VP)<mh%kqt8y=BUNomIm=9VmB3bQzs96{H(}aVeZGeOhiNC;@b16p9PRf5iSJwS+g>)K z_RBr|eyRiZ@NAf-<#MfFUFRH!P+Qo{uUx-4G2;;@VjKvgx8651c*s+;bgIFD2-Jxu;q9tEFtBKl)Uclp`gWS+}<`{UtE0?)u zEZ1)AHMp_+xHlU_iQ;z=Glwu`ZI{WzwT#)#TcxUJJuT%erk-Pm21^+A;kHwp4xiGy z5z3CnytSS-@AWF1;l(42F=`9 zSfQ5?Mt1B!xw5h?`)#dM)phj{rp3Q3w#TSEyYQ3-WYv?yYxPe|zTA>8TBIqM{rVIb z2xsWIJ1!u7_*!nxGh?`R)8M{DnR6jjs*>?=<0?Lg*2Ow;3alnf!ix>^!=u`>d&y9C z?oNQ>;n6hq%%S~qb)Q0IJ5An(|Awy?REVMfKV(d=f$d0|apxMa=Ofi2Y?sT;EVG4g zqYwAFCWK?7axma^66fahNr+~=7>y@kYR>w|S5NK8t|O;c?{npLep_PM`q?`b^?#{P z6q)_hE%(%Bzt`LT2&Gw`Y}ON6?)Bbv9^Q%jI9HV^67L>nvyS)R#{9j8OW)dZqn4Zy zFco4ny9hHSYm=P2*qN=SnKr4E`~xnb?CG#Hg_b83Wt!NCVCqR25i6Sg>WwP#DpiMX zjQ)hYnF@?~^n_cbH3~g-+_*FQqPY%P1=vy+$HmNeCt!TUXaWgyX7d{P$h+Oxz(Z2i z@F;(F$RA(!ynDXjDOC6LQa5)DOVSmZJE}c}>Xv(IPoZv9CK5W|;5r%&f=)KiJ*|r6 zLaeSM#_c3`X1J&w)E6;_2&3_3j(q8{9_$3#)`tF>B$++76TA6&Tct$|wL{+W6$PPh z5fny^=_XM@pu$ot4b|Wc57Ny>*E^WD%K#gP%)#|nIo!)B<=hDE61@DP0l%Z-0cwRf zXt9K8wS2OC)ybZ0!fB~$;O)=s^VXIB4_9X%P1XMYe?tisrIJdLG-;Lw&OYaPh-MX~ zL6bDoM6!LkY3>ISvw1siYDmX_h9~PQJV9W9rab8CYh=ZfF6z)PG=tdYR$;!oOY%oW43;>ioby>nDCUGDk{-*>xZBz*xui4Z(xqR?Xy#Tlb8yHtrBugBWl?-X@V4Wn zi`!Knke+o92GK>R?@|wU?k2)d6hTWe1)3Lv;4-)e7Poc4-8YpO?KPdk>s*D_H0TSH z&2_>wg_v{OMs}4BYeO#{R?V5dEl#P@oyV!Xyh{bMM&8)WuT=wbmy^EmK>_N#o(ng%jG1&r zFa+eKi+l=JLG(jd%`OC97r|`&4m?{GjnTG2NdHB;&)jFYm2d)mV#IssGkQX&)f47m zLmj*PQEO@Dq!6{PQxwz5dQh%KRWp^BX92z1mI^N(OSU}5yJp3LXsO^#rJ#_^9F;)B zU^&_zQ=mXbhxUn!vBJ9$p1B7R-&1@em?>gD6K0W1Av;B>BlVgRqJDPX+|DJVckc0a z70UX9v`4lphOf6;um$B`3V8`uc^A^K(KC_z!8nB9^TSeuV61$kz$(YhDAG}5;>a_| z&=(Dwj)<5)gkf%Ev9s}u=}oul)q0D#x7X}*lT(b9dnk*vNkR0ZQV84f)X%0@ z4>8lLtyegz53EHG_w{g-2jW&gx=hJS!S$qg_-qtCAwP(}jqX}<9}P@ld(N+CI?x+| zWlKG#>dk^&kEW}v5P@VuuTO7S!5NlUNDgJ<&DyZ;^BBo&T+cl^dIRl*r z?!%w7RS4U-1Ie2&!m_cifH@>$dJ)F{_hL4DT^6&49`X}?en`i*bt89JrGW7ql1FZ^ zSy;92CR}5b0w#TC3E~!IA-d2KubaDJ`TN0m(P0PnFJFiO5gYM)LC<=4xl`U=V`6v>uDcq%LQ?DK4K(S9n1Vw^;1!a$ruTg@w}7Jn$;r4jxc$nPURSy9$*qZL)6#O+@!jeb8|=5 z{$ThaQ2sR+tWGBCbgsi_6(&yFVCS!F z++XuvSfqD~7)QcPJ`j`BWtM^oBTPwHGv&p5PPug&UzkYx2H414dg{&~)k-Pe-DlD3 z#3jLo+NkOx_WAvlF>-eVM)kt0)+EZ%U5QyiavW|;p?0yN0j+`f+e{+N{w)(XQcaGDG`gf0Nepupb*D+tOy5nfHU)Um_9BXFj>{6gMxaah zSJ}~SBrElDgzXMWC^?pj0jp06t&xkn&Y6VCe$k%2J!U-fXkm!DpOHj$>_v~<54Ybi zF?JN=c1VTJ<0+!*T`>yC_j&ZNY{9#m*R554OqG4?IR)O|^l;-q7?eLIVn+;JLCi|W zu&<&vszzMaJPD%_63l893=!Ve^z^Khhl1MVny;u5TH|Y@Lc!Pzun4AvztkK-w{|c@ z4R`vxWcNUs#Zm_t&Zw2eUnGB9J0~p8tdouFbOBdO1BKSi6EQ0Yv#RMhTm7Xo<4*Mg zb>2$OyP$cl!>8i{hA$cMGd(XDo`-f2F|M<6(V70vG-9FbrR@xK?EOi$E_M(6yr-gA zS|dw+lYyZ>g9Xeq5wn3XZjRZkp+uKCCl67dnA$PtK$vFkoEHn3q-qk$-s9kUB^BF? zFT-whHry*O;a)z8F-e8@c&&?UPM8zMc6%)248vjVU=OX`WwPm4QxIvgQoy_vF#&{$ zm{7tl>HJn=O)u>Ghnp%5nqOCC-+mxyaqAzjNa~eB2@3_#_rD~3p4%64@SmT8cG~-7 z8EtU(7&Ov(o~mzoD?+gc9bf&NWuA<24Bz)*h&ezQlU6xw?zL1&*HIzrq>1`U^J&qlfLU9)s*4=ljmTU5&RMEd zrMeC-6EPtfs87g7O!FiR_P8i>f9!?W!@3wa=@85(&%)@umhdddLE<}3zyyhyoDZfW0!mL9s{61v}!v78SmtakQ_ot## zwsG-Fnp#aUJpLH$_qyYTuL(}uaQHj^nSgmN-rOb<=2+`j?0|itl9N=7a$`mgQU#~7?tx$c2#!`YPt@`lYz&Pc4Rg# zaed&}lit>%e+n315tB}sXPa7bSGR4HJf+9t#5Yq_BZq0LT;sYbOCx9j=$|D71;oAM z&@}rZcnv$RDV*2kG%ne+gstOR*oQdaSKp&}>NN+yr;UJXbtWRRHHE43v3T9BBuoeN z;=0JaC6WmtYO^ADRcH4*oXN^E&X3+P`8)!z-SG&T$)V~>y5KL+)HxHK-^b&caKSjgm}t z3{kts=W)t})zW1aDUu|bnSC#3pkVI*VfbV}zBNfrv9JwwftICkl*_nV|CwCx~b!HNznRqs!GWK+b@=4 zLOJlQaX)tsW|X|hSKHO)JE2?e67hd;uGFG!knnG zD;Pbx@Ms#V_`|=7&LYA-_5`g1=!v*6E(qS5gElHtA8AN zh52JvXn$DfkiB7CXUOe3QqkCcBq?T)tGwtnv_@==6=AN;>&~^W8Nm2Zr)PCC9z%rNQAgOiY(FDon~o=K*oZ(kK)# zNui0T@2NsnK^#;r+p%I_M?8JC2pe45LiSP;*{|0Mhk0GYSARqrd7jEp7B;2dLa;apGVD-Gx=5z&&}J040m?F*OqPE8eB zV|_VJ*xAJF%Eb6xBxt6cO?|I;I1kv1acn23d#uE$?_Xq-H)!Md@KdmD&Y;?}pU`Ov z5#vgj{gYaAzmNJdUkG#Y_ajM<)+N%s%QbfH?^6Vf!xySqkGKLJW8L!%yi~bpni-Fx z*?S?;X@e&lmXkNJ2KsDolG$FOEU8_Zxf;}YyXFl zc0Vr-7;MHl>=rS6TB+8%E5dJMmY*PCs`kW_C0GOojM2r+gUe8m^i1Zqy*d2XB%%A4 zk?0g9V$#LdEFnx($(pv` z%ZwQrqCVuHqdaSHSZZU{PwDV0nOu`D39F}dZ;BFUGtgv}0RQf47^vbg$b|AfZH+O< zej^Op{+9hVX^9GpWZW~9pqZ7O&}nWW#*Z*>mCd*z1^bx^w1KMb)K@v!f4#Ky_;97s zWy-ywG#_93C;8U!lTG9I(*lNHq%Ce7!UMO?XlmMs^*VoLgOUs|<>5Jeel5Yh<|3v{ z!~_#2?z|rN4;#%G(jHnd#8KIdWto}Z`wAF-PV=LGlE?6&LH}WTQ7LxB;|Oe)bwgN) zALb=$qj|~^qtXURl8juKl8q7pQy}IbLCkeI^D(mefwx*qkIYgL2 z*PC-&)*fMes2En`P=j6j_(_bFmWkM!a9YCXpX6IJFzWv>d=dG^7Ln-v*95vh{NOT8 z2a`NnAm_(f9DGlUcf5#MFP2)x5vCxgIXCUq5hiwihgV1l#APg zT0{RNKcM-2+JCKaeNDCMz4v0MZeO%cTa8!F?GZP2cQ%uc_E)y?FH=@7(PBKiry_25CZ)xk20wN3+d`W<6ZKC|liEwf@H2FHE?Iw>CSd)DjfiST&M)qBvCOSM zVoJNVb zgn2csJ$LAG1oL!j?V=(f8IX@0&=drK#^`qh$-g4 zJHT|lx&*IoPe7X?bJ6$3LaMW|g;U-xOsx*XgFfPKqb;`P7h&|r7;+hb3g#D`2o9_^ z)NeEW|#E9h6H#;L~C+ z9;b>=5zEEa=&UFGjY)H^_w%hx5S`XCiqp6^E}^QXAc_;EJv6^nH%d-`L2SOznn|0_ zK~_X3X=4(X4O@a9BNw8_OK(gF*@mFcld(`9iu0>tV5BQEKcE^|sPI-e1K&2x3Cdh!}_G34+Xr@3d8h$-;J!k98~Xn~ljIm*RT(e7vbvP$IA! zK8y&0{qqt=(Xa`TDUUP3G;5v8p)?wDXM3-F^u~$I&{zs-T7>y z&>DW~EFF+0VEk5}#czX?XsLez+FqwI_-PSZ+&&AbT)-$b>DP*{;$~C|0-Dm1K}Lb?y|)Xk z`9~bk6A9yzeUn{#Zx~bBD@5JR=qi)slBf)Rxq;#DY^+Brq17i0?U#|T`x5s%@E4PRj($UUBN2PMC|98SGqxfs9@sy6!Hk zQ>M0fL3lDoYc^De4=@G{7 z99<5dL%``8JX_)?VASHF(1S3^k;QDRaepSwiq@N8cecxEBh|X7P{!IOUoZr;BgI#* zb)|w+-{?gg*-jL~l`f4B%-)XfzsR@4dLLGG&cez42l1fhIAX4p<6`C<0n<)wjTd3; ztx8$rGrbvqiVmw7v{o7TaI~`7orw(pOvGD(8Ij_varq5I2Iu2za4tNXiqKd<0ZyN{ zqN2kAaG?S8gqMmD^?NZwCmJ3eH?Y&)LBPBeTeFTZErunr23xx`$#f`uXEvHCv$R&V zifzg8k6w0_q8nVy%v)66RtR3^qfe5B(s~y1HS_UxQvhbWdSkxdDLmg1f=`*DxU#hX zQ`?CBWcC z@yUMfl#lmv!&F4i-H6X0W@9Nu9<4vI6#);(A*NV`yyI3vYgUSworKxs(wo)0YsmaH z3{f{650w@e&QS$4zO~ira|3am%E%2?Exg}k?JC8<0X*uakcDTNHyoc9%m&-&gvY1C z(1{N4mdE^X`B4Tk>cj*484(l7x8{789MdcvX1H;P`s=qF)wQkzWq6iSF^<%sIMX>fiRf;GW+q_j}kl65H+)Go$^@W z2jvuBO{I{xHs`LOCgOE#NzKdQWp@Lk1Mgw`8_L47AB*u{Jr?#{#xSHn?~AIiK^`JWvl15dcd|WZUe;E&3PfwIA8G|;D_Tbg4nK)|_0JpBGC@U2A0;5C>OBj!YQS2M- z7ZN|~5cTCxp{fGaCS_%!jbILJ7ff%QwZ({g@fg0LcLj}y7TF#1L1-CIwqx*$P|WsF zKx55Wg!kV8>^X*)Q?KCd(8%d#f1*M zkI42_h-^jQiS!9_U)>{V+$|w;kC*u@_YA;@`@tkT3c`Cf7OEv=J~QYT%&0u>{BpW6 zq(61yEKo)my_^GVRLyIN8_j7q^G-1*W9M<^_quX^-|wSbP9hf_3e`GV2kS|dm#&5eM*mf2ESo8nKcCI=MHZgd zDAdvBI$lIPM?od&*7{J|-?Yc*ObVliE;)EXrn7~lfY|Y=5awYCXjgd$eRk9#v*R%V zb4hGX17XJXld@h5G?=IDL)1E1dd#yGmzYHj?ZxOY&&NoosnEgVCCrvTgu6ur3XGq? ztMCRw_FX`g?Gel6;Wi~@`9D7>V4jGWuY{>>_daL0OEcz?ZixDW zLB7(?q?z<+hd9PJs~Xn%wIsPB{n|6i_A28Qd3WKET8Au)o47B3g7_TLu~GR#hc2~n zbGVG1BmbcF{wB2ltr9Sw#F3`4K}+LvXm|Fsb1Nq8C;6u}(_~6^W-+b0Wis`(4-uDH z2hYG;RP|5~|NW0q<9AO`;l22B3vIM3FlRv)EU6Z%X2>1n(}KQn+ZP<1+eo#yqMhy$ z@r^*AFdvo;V(%2SXZ~pjR<}&trSvy(magdig&FTd`CU(+p>b1wJMfV}Zpj=x(jX>XRk-BG-_QIsTWN6GYLHgZQx0o-hk0y0PcJc4gjD zWlE3cUAexmy`)K0+flcomZGU%3Y94i5%1Bt<1?z`s1kH*4&HZR?^y$%WgHgVDa7iw zW!Pq(O^(=Kk(2%!$Mw^MPP;A^Cz%l@|L#V1Z&4qnC7A%FmzJt7PE$%v4u4_TC3SE; z@R}r7G~w)ML{jVv%!{CoOlg3@f=aAbf5EREMX)$f0sGe!NJHs9TQ6wJa}^)3Z3HV| z{(X?_LzvypXDI#BhWVBktWF)`rnDS*R(h+awX{6v87!0yB)O`hnAb0G-S--Nsg>Vd z3gIGc)QjfNAtzDHP|~;imeJMGsthcw{0Ctz~K=T&RM7Zmi$TuPra_c>*Z(WLs7P#d>R)+MStAC1eMy0V zO_YHB9Kkx*(CckDt~Mqh_G~NyCPl(%P%Yfs7vjgAJwj`oMa&e!)Zg06e!u9!RId$I zPjGT#rg(-*KhJlOCQbQ3C$S%}Zubf)CpG0>-M^yF_zlVHVE{Qoqrk z(D@9710=k`=F!@6hjBlU+UlK92KU0I0UL(VRbH3vRR4SsUMYw1_jf2B~(FqA0;kKHn@Ui zKd73k;vlA*AH@9|3OMOkVWT}g{2Ph~kLNnVWAP@!xTLIR?|%wpN{0liJIsHj41m3~ z&E5A*Oz2N^zo#Yl)ct~Ue_F`%+frel!&m$s)m-j+pK=Rt(S!c<73i^j2WoXGR=n9d zL`L66jB`A04)7LQvr)tZ5$4s$AlBGxJ0l+)tll`!P5JEN8mVbfC}Z*TH-4K@gxepA zcblUp*PEdwpI7}I&vPknZU1+4ADxH&6<(;_9|pTWA!I$d21jZt@ViGW&h1+wV6HS5 zS`$W?)Dwr~yIrXsdTDccDcgh}dHV84+qLCYnm>gq z)r6iu!F0KViY+dfN%7S)Uj<^g(E_aPc@59sAHij2x`5drVh$3lA4D^w%8J;8I6Uuh&(~dSL#@~p%hMZbTJDp!C)xgr6mDZF{ z7T!YMLfYAJ@7KC6uk!m1kbmkPjMYK-P6S z@~-yedT_d>ASkPqrr(9%)B)QFf2!pM7k%4vKa z!$h|XR)<r_ci49yITph>MmMmu~t41 zPA0Q)%*Tmd4u|5=Z8biUi^9pdwgSedg)jti3DbRnj9nCYoY65Mna`O&s&!9iO0~5V zN?xw8vR+T#d@Knr?iTj;1`&wY3n0wk|Ol#*fYL)p;I{wVQzW)jbeopAWf* z56-@{5ioy6ObKCfI_zUNYsWJ#J%iOLNsX$#k`2<^#e0-LNcq6Wy5&F8l3!UZ#=7xA zXnd`D1pS?AX)>O9^+wRhsc;%*4{m8U{M60EgXATcJkDCcSnCR{DJRU9AdbEC=nV6g zW`UJ&pQ;ka?UY77IHlxuYlqYI>Nt1Ch`Bpz5YO z8h%MJ;FKA{b@Q?J)jSlM4H7WFM9f3NI6bXk+q_L?jtvc_W7I=Voe(Hpa6VkgOG!>Y z)0ev>Xv^2Tww32h(i0+(?p`&JJ8dLo-m?qnK<}G1EoWk&_efNbw&UJHGDYt@A1*5K zg4j!((_Rqflw&D-_6j`Pt}YiKwRrVqs9T&lv@rS&$752ATgrJ%$g#Ha|1gWK4F$~Rvs4XnxjU{OnvZ$yhvJr{1={tb+O;zt z$Zsa-Y1?DM*H!i3OU=(&9^xx@VX zej{QG2($LQA$RmzA+wcarQSF6{(8zEZqd^A zu_Fb&=Rd>r<%|1k%iHa2D?fHyS3c^4hTQo(DJ0ry%WwX@fl9v-csz15GHvZ~sGui$ z1ycOh{ciDtx`DhVl0sYVIgx2gAF~bRCG~1DLl-DwkXj!|{uvGb0S}AP|QZaWa zP%9!Hh-^lc=khv7cJSgZ6T=NwB+1 zwd{@bitLQ78q&Vn(0nMCTJ038?WPgt-MGn|&YI86#MZ&;;a4tk_l~cWI#!l3zV?6N zGDJsibpJ1$B1s!fG9O-!efWM$dEBYLcz=~cr{8r2nV%Wuv69?3 zR>x3ijjnja-Ab6xfo@!vZOx@!e<;)%*M?;qzlf9utotEJAO01~w`dBYrD1FI<@YZC zh1Jjx=y-Sp0G9%i!4&aimvU1>D6@( zr}?afH1mT(?XhDLGvN0wX`9UlB|)1$;bR94VRQS|N>6Ur;x}Rv-{L_SMd>{HjH{!P zQ8cMib}7IbpZX=r2DL1ddB)RIdHj3Xtd)O+`m~?oy}&-gZU(}YDhQG&bHXSEFzLlMNZ;dmFsWQ{S_hfUoM@78y!EK3AykEtQ@BO;ZUz{bHSG*()Kx2Bemo@ z*Ban1V-Z|!in|{sV$h^FvRqvaXgZbP+o!e&pV(1ojh%R(mP(l7D`PmbZf&KNjS976 zzz(U+t0l||gK%Z(M#@x+`9u$r^@3=rk@+B;qI^{)S)B3$#9_hGkVx)Vp}1-;s_eYj1{wW6RKmEW-zF68C8nL`(r; zQaYM*F4DHr`)z{N7rjSHbMph0Nw$xbo>%BlPS+0>AD`m(3=R3J#jgd=6oZvbC|&Rr z{fz05-cF0m&d0&Hp%yq(yZ?DJwIo3vM)t;PTN3LLI z+2t#>ql{GSy~nT{Oxm?uwRFMt8~zWT!~J$8tY3V^ix#zXy`7HJ`a|KIKM&gWovF^V z4<=8zjsroHP~KMDK=l`Yn|p*=Ho1}g9cCykqdoMJs0-3D)g4qWKTK71sSn|M?l~ei zJfflS1Ch>kIQWR})7(G7D)S*aMWkUs&M?gDIftJ4tT2(DzaIr%N8*S1h-oik{)*pC zEn$pjR)U>aKcF+g;^qS%si(b;6yEzSCEfmeio}T{(CYph!2!MioH+W9J4fA&Ev8jWLFw*kHPOB%(j$I8bliE^hJB*gK8^@Si zhayxB{kp3{>E@~6dJVMbqL{yddaMPk0Bg4HI|HJM&R3RN|u`l*`YD^O}sP0B8c z*!lTRxF9Z|T%xSVS2)=64u(sj(XDbgf_jgGNdzUvx%9x>M=6N)SpZJaNx<9`F@Fft z>3tKsL%X?jEo}$K#n&)5FDX?;j{Q^)M&)QSsT7=(g8q3!xe*o6dRB^<8+3hFe-qLH z2QcA~Ei!y&Vfq~zCKgLE$2|@64g|rvMBEO35{H29CM}Ki+pe*d>;Ez>XHtORP%Wut zVwuY1q`r#HxrsPUQVvDlfLHxXM8@8R@2nD(k9{K8O%0uX2$p^e(Q5xPT=SZNQTB6D z(Iy9(`}bgP=s2M@^&-ZIFn&W5*@OMQFeTn}#I>!L_BS1nyWG)GWfXRU2J>w+9xa9c zyk{snSB9b=RBsdU2;<4O>*(SAh?u+-5AuES=I=5XFI-129=Ui}lz=xsXA77MBF2<3 z`4#SLdF*TE*VbUQOSCbQ)K#9FvF?L1Df${ppOj&IDw#9Z*1|$XvB!5V!$7AB=@*Oe zh2HaUG%ch2&~UL4y6R;sxnD(qG;ao{4_{UWaDS7GhhpJDk(EVo&eI z*s5^?BRpgAPsk{tH5KA3?qI@L8*F2hy>2lnr21aU+>ffqf5weBB8Yted`l&rvveqmVZumK}F9K$xcZ7&QEA0$_aon}WE z&sqD~Klk&Ql{+Y>@Liayg;%fK3ho>i)Rt6uObLb4P-IxMO8B?ABB=1J2Hr+foElxv zF2v-Ho8WwCHddB}lLyf{^mmNJ%BpkF%@q%Y1I5-j@|{K!a=RfH8NmCOk-fyEh-_RUsH_vlOmt4&(Bk&Dfv_ z$HA{Em?q1FPOBC%lL*tvC!F1v7SH?>LcdK_sdRhTnA~T(F}6;oBff*wcY<@d9f&xrJa-xf^=yTnUR~sR(``o(TSZ$e&4=aUqM? zMRyM{xtqyiLRBIi8#^Jlt{?fTzoE=1%3JH4!=h={ZLE5ihk{TQ_!O+9X)J1|bVtrw zZ(M9P0_UnD&^Bf{_S{{F4?{0ut-WY8^KSu+Ct>vd@nORYw=-cY=(MI=Ep2^tXl{jb ztq`_l(PD%$0{b*$by&M%Q@5p$d{=lkWe_wRg_n9}Xwq2fihv%lX_F=yT}k;6!+^iho}s@w1n5u?K_ z=5qfNl+AB6#5jKiwzr~B@ooZ!rudAz=E6Lm-hbN559HBX?Cx_R&7A z@sOU<%|26AzWyfTT1u4;gh@BP0J~RoQNK)yff}TaaL$7-nbJP;XbJg}5UhJQ5{d1T z5&zvE#nDu+Hmex$7dy>YY)v|0POkaPZk}H(QG8XXa}T{zPCWCED$nBy(|LYAv}kZP z2A&smYZeQXf)+RRHK|$&op!l3+Oa`Un1ts11#zi}DI(184;{Hhn^PrWbiR3P(@8mNtwP!Va37|r zgl6UN{)gcsUU|$wa)8xaVT!Xo=wan0kj}>AL&!hKOki-ft(szzJ_wkPVyE3A z%oSG?ZVq!+;`3UeF6n!l3*Ql;{Cs)~!z+vVPIKR$2H7lfASGF8&0rB@LFuvAE_TQK z{19w@D94q;cw7ltkJVFU=vteL5jEoVgH$XZts>0CLFQa+&}q6ARH!w_oKx=Gvz0Tc z`7Eij&J%`!gN4`{yDL-y`6mZ#7gDrRM{2*f#PdLZ%zY~(qlOb$_}m+TQysAD-X)y> z`$=exrHFY(n2K^!?!oq0iE*7mowsiUBfFQ+4gRx9QmR3pW_TXGN2duRjo0E9UC$A0 zsI{mgzhw5tUfm72R4qY^Er;-O`(o5S8B6g8nV6HVFRV9{Ma( z9}7RW^29>P&YzV6#;cKRs6V74J+~N1R-|MltK+6IG&BhFqMHpKx~{~4ePc0w<$lNx z&qcGu>1a5cf-0Zp;<6_GHs1+j^SB##E#b7}Oszt_uIFu4|BW9Rk2x)b0KxRV`LN1O zMUpf5spgTOd3cT>E9Eg4GNjnvX)QAHUC{2{ZhZYR8Jl*_L5C}+(K}qkgoqfe%``)& z_T_Har%6hy6zVTeM{sdtTS_bJ$~a!V$|uS4n5qusr%DS!czHHlD+|yRl7?+&PB2)% z7*FdagPgK4HE1FQKQDl0<_T~yVy6ujJFOLAHm3~Y{<*1?4^L{g2 zXaz0ELH}afm%^%mwCq$k#>XM@m@(U?z<2**yc+BRMXNwGP!!Szb1%&Abr>Blh>LWX zh%qM2g9uyB$e$c)>4*!P`P@y*9nx2BlazdBan%dT#SJ471}y}CpN*597I`uYam+VEVp?F~bH*CwCFzzqxxWuSulAa&wmSfv-#%yl5 zR9~?|=~_jS5tGXT#_J^2ZiLc6UU^Aa*7$0>m#^j{pxZS3a-2prQA@DYeHfl}2!_MB zaHI|t{nP#pLbD>w-s=N6-6Ovw7Vj16p=)rgZXS+8?Xp%pZmbLkby0;ALa-5AT?gxr^Se!WutZW_hbjO8&Vrre%M zeHa^>(>(slnJGt8rR!#OR3`ax=-iI>YBU6fA1p&mRz8U`Gmy}$M8Mc@jl{Gg?#Ry$ z!f3_=Q~Em6Y;X>fSBK)Nr)XpFUi@xc3G?ZdDfgq>NG6{~T1NvzrE~H%>CWZ@l##}q zupM;RpDHNwg~)kE1!My2g2jqT9jgm~>i>2Z3q$XQl$j?WPE=sTW%_ zhcI8Gx^r=}#xbj2D%6A7Ba-$d)l$bf&6IxWtWcuJf1U;NZwaOh^E&gDsw6b0Auzqg zQN$a}LSXq$+&3GA(fa_Ok_^}m-HPIo;%UuS#4I69oMR8pGk7-BlBUk|oPDa-LqAJT zS`X#C0$6y}6$(=)Z(~sEUjSF~Zqj>Du;tG$$LHM{yhO8qJ_~Ih6wr;>% zm5BLwq^%)L>3ef-&&gFxTbk2Mw**Q0wfiBJYrM3J+`+;fq$2uAF)q&K;8T8ij9uL| z@axTo$`gp|I}L+>1Y>ryerRhrg7yL#2rpQO&4VTioi;`sX?}z`_Pss#CLn0`n0t?`Yg%wk$8`4a)3B+Fy?N=SZ@HffQ7&8M9a@-PU`#}CA@`9tA* zJr^B%dr?M_I0OcZm|()_Y3Os^Om{KP*A(jhn!gx*gFLBU{eA(%%8LZ4eB9Uy@aG#I z!)F%rJDaBs38?Gr0RM3cwEo!-H=2`ud%YSj;yh^3PZnA;K@36*C(O^i8eGEC2*&)1 zLe0*(z`UHECN=IB%kZ7X=i=&{qzlo=<&Q;-_3APlUzZLy!X#dnlK3JJ6;WNWx>Fx$ z(^43+elAYD5Z|OrMdRi}gvpkCU?po0F&-*~dS(kP=IO#1>DHlVgw|-)5Qb{jn<~j6 zo?J%w*327mQ`mL-v^|5Ul|%8~CBTV$9dRA*0 z8DtRV*UKcy%Bg#$i7PV&3~y$_yCv|E;=|X982=kLp`UmW7ap9#Gy@x~y|)P?UYlTc zd>`np%tM^B8-|P(f15pGrzI1nmsuUFCyQskq$_;g1B2KVyZZ^ESdx%Mg9&MK^Mt3XTJ33yB!@~muqM*+H;xM!qua%l=#xS9>Gw%rTL`a-87MzWWxnKOahME% z`^o#EByJ;=>x^(cswcXf&BfL)bFpEt*qXLtr{xi*r7_1|R3$OSu?ltIhEWpl(q~N2 z^++aWEbaaYlSDDdUN=MxugK@)-uZgynK^XTkUjvDx^Kjj2^}e2sTWEjFHuH;2bpM$ z5n8iD#FP>y25Iag^AzUU0fqW!`X-6yhe9T%Z2-ehoqVA(@5}KYhEFbkp>bQtVZZY8 z1Ww2Xz}$6jMs63Vdq{DB9ikuh<%XhUPK6%ZSzPlQ=3FfS%QUSkR>l3g`C3ponZ#YcGJ) z3-Pzn7G2_N2-80K61z+5JmYjkq0VTtTY31#8Ya6~ODKuwF?^o%|Bu;lG!r%&$1q!K z5Lyk|jPp0l;B?svZ=*6{aC!lDJBjN}n232rn4gAfw#$w4%yb$8c~2s_4IO(hhi>nd z@Rj#GrqM^lSlucV5}5hc@R+|3k7EdB;@)!d!#yuE}M#oP} z!++=l_T%si%)_G!wfPTkN%)dqT)@-MTpiuZl!u4^4*mv;$5frZ2ct(Mz#vsb=--<{Dv81V16Yza4)PAZaK7M#x8zfEVtMBjbEE=o*g_S1KhTp1yGSJ0#!xpIQCX&j}L(+tgHjHKigPpR@XB>ML~ zB4VC6?t`zr6WpJXPHoFrT-q`MOIjwwalHZ)Cy6iYYebACVOk`Svfs#uxiRxC_C3G5!#{%P4Sty=Wth8 zJ^Ae*e{IKOzL@U8IOoY&Gie3ReQ*O4ISPR%<6xMx6Wf);gx}_}h#5(k<%U1mH0#sM z&;)w)avW|KFjt~7|D~nm%}m&uD?)1us344Ar1kx1*GbD7kFi>{1KOr;&>y^<_Hc7B zFav0_HWo>}_h2Yh5b=}EzmXIUggLzV3;Q!Vma#ssP@i9?!#F(Wf`3es5RGUKUPXx^u#4dHd>4u+a@6W_EDI<+(&7dqSEVzn0zsj zFavzPu`{xcF*?}__0dEPuA;_FHTL5%jz1CbTMquW;r9YOhPRvI_X2!tKB|Jye*Qd| z4fDk2l2z!wYz)HVj-bQKz1UDH>OBXEnCXOx%AihLc9=PRfm-uoKNtOFx{Bu3O!ro# z>--lJ`s|K?aaeZ=P3uI=&82~0HJ4!S3lA*)yb`yJCt&N0gV2eJz_7`pYp=EV+jtP> zO}GY^_UZsre@UUf)y|rmRK8wSa^{6#o)wcMw#GmG4&pjq7Ho6gIf$6PgEnFHY)>S4 z&quk_S{MX5W5|RE>}wqj=5kNrw;3Q}ya?0cpBCJc%DqgIQlTEJU&&d_3{)+9@>jz9 zK>gPmexJs78t^>JtRo=&N<{wc?vR}-Q^e4={b~;=U6T&2)QK&ypkV_iYDpc}nKhZhq-`~dS zX}N$2I+-opL-Ux-IZM%9dlk}}xnkbDV2tbS4i~Qw9C&vU5fW3O)Ba6e+)0=qT@7x` zT7SlqmbJUR)-ew{hN_f}+n6M>Y5T7=uJxoJkX{xJ?EH1NdvPYNZl8gi*Q?M?iw^2- zc4Fvdcf9Q$j3<8afQk5udt6NRizLj(DWBQI3}2?4X6QVxJq%NJMAc{>&!iuvD?0;m zvaz^8PRTUc@TPNFW3LM{w9d&H$W^U?%hgGg^BoLr%muqE08hy?MT5e*h0jyO93_nW z-e-23-4f;=VLCe;v@`yDTs6@-UC52%r%rw^z+?ESlfUIiGQKYC1^idL;A6QLjLMu5 zb%`QJedogWpCGj8bOwH{#kVzyh)E!fzZ&8f z0)A&>ysaD-hIIYCOvHE+`lJ68us>GgLBSM~(~}Rx#W_$mY(v_TL^O>TTjL=Pf%AkJ z-1vcY{OZh%B~0E#dp3E&MwNl(A*QiK9_n?)eHxFc8})yf@w9jQlQ0FromM00i8CVF zhT&!7EUYTrhVY6+>~azxi`R&)VfofPYGg-pqnMJt3UzJuW$s(nbX8SIsL&dIk>+=u zJci#3{MQXg!#X7R7;Z-bqr&^KFISW`&3;ButyIMz*fN zj=374P`@(TWv5>3pmH<~5HS39P}oCnFBdkq|6#0T8Mw1#0*WhFWAT?U*j~B^e{Rl) zn`|pWiq7GczF3(uPQ;WEW@N=1R$@Gq!5+GVbXVD3I5t=nuy&$=vCyWFpjh7dh16XR zSN_);-llEd#BuQSr)*r;F=&>#7hUu{k+^Xi+89#x>MHRv<*zt(RuU#{=QDO&+W|~G zb($>gsAN@a8&#ssc&4d2-3%Ts0k0|KN1FTD|HJSHkFUvN@XT=)@+ObP^DPrmf)A;ov+byg&Q$?NjOS#l;o$Yhwcgz%8Tx<;GRI^6$>oUsG6~U* zdvIs7CpMV{ps@!zCNy>thCmxJK=3PJwspPB_SxQ*iB?c8N3k2zf2CU4(0wLT?nBQ) z^dQ;jkPdz!;2$LU+d+QnOFC~??T)hJqdyT zkEb(_r>cA3za&YMq)D?RY1YWuXWcu^nl)?IEFu|-630;H$V|qPp+TDD?6a4ok|s&B zB11|u>Ph48-g|$(zy5t*Pw&<~Yp=c5y{`MZ61_k@VIB0S^@n-286cZ0&9o{h+|d{@ z*B2BP9Lnj*jN6J^j*zpjCRPC;;~F%^`Zq|wYX6!p-ihzYJdUBIOFW;U$Fujhc>oaNkD z#&`%X)6V5Y%ht3Zx!~^j1k#40fhKNlg@cDs8glaA0qvqUz|w7tFx%S=Hf&u5A9N2x z{Lo{N)&GC*jWiktG0vKK1sittWri=qx`5U~&g9lXTt?r?go8)m#k=CgiqKZ-#G_+B z9z4u9JP-?AyY6p?{E&4}RJsJ}*SbKp0%JmU1we{U0_d-jFxJv&W+LXl?Ngf=1 zrj3^{)`$t3T2@f?$bj*iffXpf*W4v}5u?_hF|+(|1sdJ3F*X=Ws@I;w^2>L`9(IN5 zAzWH@20Go`2e(cyhE4X%;eDSSkl{WXDwjmT+N4;RF;=pnekWlzBgTJ!SwV>5P^O6Z zP=7@aPV3$orrKeP(!k&fXm=@t@=vG1Cg_FO@~a+*j&Obz5OM7^Jlu{Av8q*&Qnm`4 zGdDn&0drtE7Yo)CBVm%uFmW_3(tEQDG5-o)6|CQ6%)FlIL;p@=x%$&eX77VX%BEHM zVrOwt;Ase5g8gbeFoF*a0bk931cF)Phg>gc*|r=8;&yP-)=eO{oDB<7KY23XpLgbr}|Lqv)P>Kf%fv1iUg%#2q;(`r?s5Ii>{ZV04D8bE|@RG zSM}B@=%?_3PJgu+Kl>9FB5$SOP^r_ z^S^9ZI64?|cFlr)8@7UG<}x^wY6k!Mra{fuK$woVxx%jVkAz7AFxk2g zHk6Nt_IS-|)72N;u9}IM(-I~dF`ZWZDp+MbmC;+{Lw&Z{DGPfCGwh;;<`K`ZW9u${ z&d_4wd%GIZR9o;JoT>H#LeX4v*M~50)0hpJ);nO`#rg1Vz&Kd+`Xp#%_`xwVsbhtg zFc%QxdGKGs#LDSR<3_xVdb_>AD0UvR;Y)~2G&2c(1U0Eyc(Yy$-#0x3!OX<{=L@ju zm<1)>!{Du&3c) zDWsKJwN!}Sc0!-@fU1+Ab36tLl3C~*+!dzzb%OOdy2dM6E^n`W)vzy|i*Rv8aO1rj7wTk)7-7P+J=Fn}bvLVxD zWB=N7f^(A9+oz(dm4GoAiIomC&r&p2i6%fpSEs@u?U``bWH&8o45wdiVs@+Ebo#9M z0JOd|5@*_bX*6#T^KisE<>At~Ox+%=+~x(>>Lj_xynHl3%*-5=8@@9)qj)~S>;JPc_Ih=`dZjphqtMvmXFtkjv! zphFLxwlInxaBha`c)&>}!ZsTOjP9UNQJj?b9_@8kVEl2vY7h(o7i}#DyOXnF0#icg zbo@vSAJx+xw=Pp1vmnUS+9zTvq_5{s#O(B0tGo+xrqs@do>nX-`#+ef8oEcw<44ulR@tXhCmGtj{>lRk{6M9XaOmMP4z zDL&Ndv^iN*5-ra-SuEGhNCf?{6|nMyHYC1BeUrgL&`{F{{VCX)pM4Y*S5S!`eGnEj z{p3d&FQjQtjOggq7x}j7YZF)NS+H$@^@j7+1ioSxDfz3hCyXg*y87jGZcUsT`8|`$^D-j9zzLg_x1AjTgw!USG(Z6}RE8#s?9zNE*!~#6&F7l6^Yl$DDttz+y@p zxo#gl5}(j0H`sL;+kI2_Mzgb4_`_Qt4Y)NV zfrOvTB~7cFNfE~OHan=Z!f0HjuP2KbDsz*?qT#uBo`NP=+LL{smlD}@Ez)$+N8CdX z!ha$2eF_=?cLd{JJw*q9g^4$C?I*IY=6k^9?TPHd`q}JHCoi^Ina0|8dkkK4+KHIo z(r7FZGv&Z>S)b7-m?04gx~%4UqJ4W{*sMitFP|?U!%nct5tCTu=%-NlR7b@0ld9@V5d+8CGy9DSnF%Wt zbYNI6$ta8^{cp}A7p}WNrtJsytKsnG;3KqNaf1(DX6)7)GcdgI zS$?OgH{mvp0hugF{%8AZct53wi0LI=6Rkr`ltzDM;Jf?G;z0^(o8Zd7KM+lpWrq{P z=MLgSdu|m68Ifo|nW=yplW_3F2J)6`E^u_vEOt>lGsrMKOJd56V8$5}Hq-^!dGGSz z3+*jprb@TC+Y!^R*D=}D*OaleP|zwved_5ypWkdSPIY|0J=Dy&52fdh!1JUO&_0aL ze6P`hW%CPhG>)&=vKPC=fR5R0cDUjXxSqr)cruiIH+&-O*>O#rX_1nm%Ly^}2hUb+ z@jk~Gee|Z?!|V9fJ6-9kBW3cV z9od1abBS87n<8d}q#*W3jOX{O${in0FnLAZ^u%p#GH7fEUU4T^rMKKojIFkPnE=ac zFvELz65383gE!XizyK8v-sk(XRk7cR^Yy>b;_HJ2;w-q@S)2XRlufc| z47O{}TJpp2sC!t%jFvFR5%b^KJlWTEH<+e$Z(1;?m25T*BF2_#a+{SQ@U!_nn#^R2 zy3VF-Jhh?wXpv(pm zi238wk#TltvjZl#;9UKKGXqzQcoG2HP3 zvOUVv%z-uv+UnxS*Njo;NzNse;%@+0OneD}Sl1LTi-mG`(b{w1kKP++n!G`y$0gcY z(!Owe)f_n5bsQ*ujsW-ZsrcX23q$8!7cs*m%wxoqg{qsYZ^~gBhAQZhj*d?-G@e?x+?{x+y8|?}ecQHX555PFMyHozrR8fL0oC7p3r1Twr6UIXIyG@##6W zbYVe~h*=Qzi~Ug zdEXvRe+-1kzh2P3rbbA`hz!GYHFLMHLV3Pi5a%a__L|Z4=)8>aiNWT>v(^; zsZTG}6k1L+`i~WhDQ`AE6EVE~X()@D2-_in9QdF?s^oh7wy60qc9u7cpBf73qftZ9 zld6hOwh`r{eWcO+Ma+@3mIA*Csm!=A1uY6)Ma+Ek<1GuvZ@hVW? ze2iI{te|@BzREYm#H!Rgm2$n0@np8ze?$mz_&-b@mkCE|x^8?G!2C5^c# z=qn0`6Sq@g4qg_I)Cnb*J9iW@K@vt6F&)0GE3gWSVal=;lnHi|Pj%?a>)oEL(pmPB zWL7nk?30;d1xomB-rP6=Ba?MuZ08*EGo~XP{}oJhI4>}_Ist2BC&5BJ2aH1xkt++N za<`U*>4zAvc|WggOABUR-NXrPWWeo9?#a(H^iZwo+!i9Qwh@=kj49F-AWzf4Ij1kA zT&^JXu3g}P+@Gj>Mncbl`7rBk4tN|!_1A=zton#ctnkp*NUMMmV&)hJ7Z}~x&-8qx zppP#W@q@fO@LCtfsy5v2i_Lu9aWbcfMM!a`%}WNyb`#*j{$8*vES$9-G?HE2KL>h` zz6T5M=RgQr8`!VG48yWXBBn`dk{yc}gM((u>b{Q5heieUvv0?npZ&`@<+b7UhVO)8 z$Cjf0gi{N)2koO>A#FnJI;DT~}5bxkge zrn}T6YmS(@pf$=R+qW_O+hCPrVU9eu?4T--hBG!TXe&vBPy!bZJ2@6G zZ;KNR&-+X{$Ukb1kQd;`c_|*^JF@42FsI=2>pBwn7E6ElXOq+w8f$|&RdLjmzl$m1Xb|~Xaio5%gBNe`I z_EHHR|QBCWw$dhHv-P*z2F#vvF=$;6~^va9f@W8$%9>7zfFq$p$ftU?o?h zIfk(xgN3flLtO34gQ^OhencojW-r5o;kY32#zPp*@{M6&IWHS5ww!{98?As91CaeL zfvn~xjMq`Yg#jm^1n*1Dy^o8Su9BsZ9b)zw6OL~)i@Dqt<)gp!F5ktX3iAhi)ZfGKCkfCp?kTjp83*-#_>k+e;9+{Ii1{L! znYbe6>}exTz21UZ^+Z9Of-=;t0HCPi`?@j{H-pOIWb^ekpwrGj$Ne~HEE zBGvqhjJ*8XWvD^V8f(um6jz|h8J6vShK8eUE=E(}LmL%)273rXAr;$65?&TUr1B^v z1|EScp;uwk&TtWPTEYY(#=G!`vf<1KhR;+`*@7Ob>UXcq43B@53sElW-Oqx0|8TL; zRa0C6fmn4C5@UoZV3Bkk1{t3No8cy8_cw;@a4{nT%fm^bYdoxeBk9xhq~9hIG0Jwj zTvDnbvvrSx&Y#?w@9}B8>Tw1Tr>|GQa?AxVagG3O<2PWL_Y}G~MT^d`g68&JckKLH znhd7L2GMn$S!&@jm2Rrmq!%K?A(0y)j%I*_NkWXqW|l+a1*Q=c)Ym$X?`4zCD|WRZ zf=bo$Og?S}kBAtPeosN2jfTJ_*kZLP7sfNWP;ns{mMlx5pZZan5miWs-H)bMmL7qR z1I~$`waXGF6EWvj+H%`c@5)qN6?F0i3zc^NM$Ws>Y$6Dig`_3Zd_UNwdI9mZccI{T zFzCO!Dy{+-X$Ba5#;yCItF*!U19k24k^Xv^PoI!XFwlA^V*Dgb9%80G*ul*o5-eL+ z;7!Z*PV$qt7V}1{yhV)AO0s$9cF|W|drm$~h~6Xi5tORVK*4wP9zGuqD-IOUC#M^! z`=&P(CgxD)<4qV@FBQ6aNcJBbV&?v`=Hg}D%%9tOQ;iGjh-Os)e|TL4G4;P9#=5EL zn1fMH7L=RC!$?mHl#N^yC-k_$c=)Ij0TW+`Qls}p)YkkmojAjp4(sv?T&{_6C%VEhdN8Si{qjNw9Zv6%j@wIQTDhNCjDJEDZ0GEFWOnhaa@6 zMOBldk|%6wh2y1?J}q1t&2z*Y94zNbGfCz4$?0RW~#oZj`J_?I1{0A8$Y}h2Aw=c^!`o21-31W{d-Hq#6LX- z2f{94IBf>>>e&hG{soZ{$FQKXQ3Dzmppk=Ix?c5_Tt+@2rnb8a7q!Qo+q&c+9k#KE z@3xfVs~rM~kQE`^d$PAK5xcNSP^qU0`5WJfn7~VM;Hb{SiR(FVvaSovwecsf(qhR? zZB5X8)s|(~vf^*^TEhH5%&fl(F0OAP=W*VXzU$jbrF?XPZw(J2*^n)khQ{`NMS>p^ zSoE$d)Ty+@DG)e03jP~diV-4cLw!mIq8=(pT~|}~?~52VAg?`JaY8O)oFt68r@Gqb z_R(C@l>+X)z9%&~7|EyZ;rLxHt4P|b4BQ9Yhcaw(IXq?o{Pr0F6`O~O7^m7J(CPal zm^&sPDw31feyxOke(p9r@U&vbS9fIXW?PGxf6~&~2{C_x1$rW;^hP4L_P|%pw0=L8P3=`MJ!1vWmCYjRrua?AYa(IG!MkNb z;FrVjcYl)f(6j^KrDZKBjLYCsP(7S+Jp+!tZ;o9G(b-W0b*@L!i5-6!-`X z<}6vnwpYsn?Rg7f>VgHZuBQ&0mM#g${`Vm;L5%y8iCn|H``r1={Zub}AGEux2UZD2 z#OdTQF%&f|J`!sFoPy`E=yQ*4KGEB*L+MO^2ye&&;|^C~_1+KQi^+Zue$N4I4|`a1 zs6Sg9p%5S1f6_;K0%G{GezL*2(cIRk{d8KpcW@^SJL>mrl>eNXh(?W%(6v7fZ1m29 z=MCJlXJ3R}BT?cr&ky$R4ub}*H25954h*6znGunL*q{9evU^4kViT-RikO>{O&dYX z0gu(pzRx4Ls2BTb&f&?b6(Lm9!#vz>ozqBx-{cvDl`ikFXX}B%@4!^@qve_@b644bZ=;dc!LDc z?4JS7*bm}r{T1|{Ns)Wu8lqmn3NgQZ4PcKoM;Yg zlYk%MeLUKGoB{n$c`#ts6L`Kl6y}$ogZVqsVd$$?$Wg|D=5rUwSP~6cTK8e3cZN9A z)<~E&hza8SmDRBh=J^9X>GpM<`Ri&?i#Nt>TNNi13$S zjUVoXhc7}dzQTFKD_~FEDsZ0e58oapLFUmKZCSw+AY zx9slw;(&CvAoo&kD1{TjL_OyAcHIxUSrqo(69YNed6^qNKmjGlyX zM@(Fpi@A5_K$)@4K{~r*U&w5eM{2rh@YYLkA_u${@76>`SELGrD#w7)Z$Nu+7?fy- z)9U(SdMrmD?>)7MZEy)_eXD|)sY-h5=Lr#WLc;hWrc}QtGlCSzPNyEk|7|?%4G5L3 z?dYy@au0_ew1nm99gzQgi6%ZVLgxD zzVQv66rmC^&)SMJEfg`$T1y#63zclh?Sr(h-az@6_Yo>h)k&41vnGQU(4C3~FBx=T`kZyMunrIb0ct1C){v-D5w77_D98ciBv?io5TdUukh9O>*uFZYI7k4k~j>d&Q)m4TV?W-6L77JVh*SK88=ZUNLXD-m9%n88`}$lux-bir;=R2bK@s1SdORffM>?U{>EI)sMB+(n(svTtdv9 z>c!0J&=*Skmj~$sr!n&NQ!@E|TVgRp@FH=3(+^wY@HIurh~Ud%vnw6gwIiU+#+%eU zH6*9zJX9Ir>CHKH1q2Vh1}&4$!Tz?%DyP})K^V?xxs{2Nj00U($ZOq7|q)C%)lM?T>E(kY39J;@_Qqm@x7nDl0Ut3hg@jT z5|2@N?<&Ez?_Kz=JO*DD8NgfLc;aB!5j|~#iAH!4v~+ieAqUH$?~_Zg{DwbC%agnx zY9&ksVn*?snN3?FIR7>W>6-oK@`Nwx{7l6gd5ZOSa@@NcSpN$|iIt>G84wu{+lP*X zm1By@5W_C8wDu6WfTB#_ls!=Pr4}M1ufoeeUZg7eGAlf^atZSaG5a0%GQCHf;|6AV zQX`X6X5E4#yx!}9q-1nAXzAJy^n3WDVC)qXbSeXzsWDLDB8Tlx?cnm3!|XJ69D9Ft zIXJvIfZLM>$POrlN8Kl~e{Q;pm~U;w*Yho6Ox3n9?~YyLh@~f;e%nYDczqy$Zhsr{ z)OQiog)W5WKfJ(t4w}(pDciFFFIg(Rp{{;2^!}QOB0dku;2XdYZFQsXy@#ixZh=8U{KUkXUA)3+G{42-L zTR2$0OoiwjQJ};<-IiJ5BzMhCD6F)FWqF@K=bQ>+JDq?7>${1g+3_dHLM>bQ8!@$4 z7c;ADE4lT(4p6J~MB3(Nll+)bCJ}O@O6Bnod3qnlyw-w65ndUsJ_06qxuT6F3F9y= zScBFdbF(RQSa%poQ$NDMvJ7aPe+t^?8;h7C38Q&XUG3G0qq3uwmpPgHetK^7QaV%r zD;cqF3lUDzfupm)_qQ{;i`0Yq>PKig6N+(28Bl&A0&Lqx!!0%huBWzRCnjA0y?OWW z!?6b*%YVz0zJa0LXc#NxVR6B_#WxK_= zcR|Z><8d$;IAf}uQ7rs4n8fP5uRyk~v2QAN?&0h*I1x~(^ls`l{&%X?~Q0yXx*9&e*Sb%H3`v7uD9?G|iPes;ARO3t%?!eQ+XaYz8wc8fYV5|W8t}f90^jG%gG-BU zgX?);a4z(R!mP(4##h3OMoh=#rCiHH4Ov6rK6-KZOc*0CAZa6y67z;!P@?2-E1Jf?mxE$+MpzHh0Pw+}WULcV8d4EB0@Vgv{}j`7j2KzBwUr1eKlM_vLv z%*=z9gW;GRIUG*9tR=no-v!VA;^9M-KTNKEDq=oK7z@Odom*wzHq25s#Bnb@=H5iq zkA755h+aZ$s?Lc~m1*{e!EHesR`Wcb0Pwf5Wv~gu;ut9IB*C?=w$NkSExFGuUsa_1 z5Yf{+Nfdj1pyc-r5o6sd{xr4rQf z9%ocFdPDDMfWKuSSj;bh#!1Q0|6)E|jy(puhmNDli~dxWFrKzieBx95MnkiszlixD zVU{E2+NfBiZv6(Cve1pL*{e^PvE$^6ewBzA!OSFHb{JenwPo*3ZUF7Jp%@x~3SzZX zu&5}8X3sR(`z?*S>D1AzJv{y18cct6>xUMH(sppzPjNIG5c4pnJD1UOn{50}H~M?k z8Gd))0p#472}J*Vu4rRW?BWjoJAZ(G;!F6s(GPTQJrMIf$9BC3y_a2vTcL$C;F)IO zyz9;M?W1$F_r_lE!D_fTn!nO$Y!Nf7`&7;_(L<*D&y_|l^inl#V)&VJ+7TfLO=u-q zG<*eE)V~si%1iHV10noGs0)}IUxY_zF#|X9B28SZQ8?t%cj`Pilcr<%bM(ROB4&;> z8fU~f{4wLk-tH)~igl$y3)aak=8fi=Zi|WOb&NyAc7;Jdhl@ead4*X}z1vLG3kY?A z_kS)yuZU#W`{*$Bi>;);eDBbKeVu5|wnGrnJwn8sl`x)&Q6Hes!bJ86qCo1@*(&>KxLN z?F@Q@=0hx$5kU#5UlfDs%*F8GG=@2L{4Re%toR;r6Zs+I+me8eArQ5EuZVdp{WcMZ zvGW|sJ&Rng{5-*hs%+)_$5E?!qrzA6Cd`g>T6`A<&G#dfRoMA3c_8S7TqHuqilSW< zbe#GCw3lHd#dsO{X=K2!b!k=k-I+wPK7_z)e+lza!XzT*;h%+^Vt>A}%U5T5wc}#` zwIT4n^J3)s(J7*|H>E{EPW_z(`F}cq4k;j8qhCPA%Wx>Ltc3Ajd6?ka8#d0|O4i!@ zkP>|z=y2pP*hfhPVqNK>WgsSU;2th}lm<8OmNV^lYyof3K8f$SXu8~#IR=3z9zfyV zBr``EDNml3lpM#NM}qbWvAdRi{mp*546f5w@9?|DPDYWzih*J}fLHrAhon4MVT zd9YOG3N2=H#geMv)TeR$0Hj*BVM`WXg?u{=Hl$(~M7hof&5Pk={ev)=ns8CX9FZ{h z5aX?Xj%&GckDH5_rgqomHy7RIxjE-mMfzb-n+o z@D1$uCCix?6kYl;c*A}(2s0t9{7#I~Hj3K}(T zuzdVZ$XZYgbMs?G%ybD;gP51LW4M8uH@WnWF7*D2`QY2o8LYjB@D@eEpgW>kyp8G^ zZ~|Ljq+e(cNHNu2zwlEX| zAof`_I63=3x3BB@rz&&S^^zHTx~&R=1~!YBZqnEDJ7Q8^1T)1J135QuH(G|jL8ePR z={eekPm2r$Tjgu`iQ9{rg=gSXNRp_$x7qy}<}Kd^U0w!3JCrWI_dkz)I$z1gLL*kS z#)z$QJO-l-E{m9>-^9_Vd8w=ES0*!g6+M*KjP}w_wHysksv;v^=kula0?+`kPCTty zc;FN$4X0~u+u9boz_F=?NZnGs}>QX zjTon&A7z1Vhx0p6-ACIO2GXREiO~D)b>31V0P>!^5i#*{O#5YzL!NCeEVugwb#MT_ z&N&M@(=(x>ml~_~{s63J&%uF5_u%!UQBWH#mAe;6qtQc*ap6TX56@#}_Ga!>Pk$JH z?35-U9!Gg|^g?;Q_C0zI9+Ps|o3b!MEEjfORbvG$M^t$V+{FzpF?bI}WCc8m&4qF4 zH^FU+8f^G}Su72KG@1d3@%_iW)c)U zz$>Ae)8IKS7usxX%Q{{1g^?3qk;wMpM6(z(rDiRJ&*x8pmK`2*t&LS$xzl8Lic-^* zFvf^kJoa9J_MnL}V+#)&S=*aLYb44SbneQV9tnoVzs-=QnF7mI=*V*$ebi8S-)hp1 zEzA@ zc+eWhMUe5Q4H^0DoJznbm?jWns|BwiYy9??CZC2G;TVKs+}%3}TiH@L^_cF_SHg^Pqi=_CerumLCLnWZAR)(Vz3J z7>%rG!IqL5oCY}i1q0N(;HgABc>V+(bWp~rAZa2t>49mwg@q5w+fgtJ9A~k zRu5`*ZVZ|8`8)r`VIi04IaLg-wY{4xcHsqLq01JFDMGkoNp&xHUh9uLp;}tl#uvVO z5zyWC5!~D1sUYYMwRBu9j%Kigu|`Z5Q88_*I&lwdJgBYFR@KGZJ?LluHS$xXI-oo1 zD46%a3NH4rTQ(Gekn&4BqoDA~9kS?cM|wN|1T8F2hn-ap=nMTCGS=k6+yUNn{^Fxz z&8A#>Xqyq^*ZC}?*077)Yv@6fU8eE!eg<@`@p<`d=TdUv>n1SW94+>(32mkKY)*i0 z|1FR**N==l)stMcwC62ba>43*0Nk*D3W+OYpmNFx-t%I2@xAFOt!cXu6ZAKY*|a-@ z8`J7eja~fZq@5-Zp^EefJwT8i>+ErxN!Jgm|YESMTN`*|a7s4W1;M=qe z_*$`-gfG$q;k`K{jYff(w0WEZNyP^Z-xUjf?egS!t%TWoD2(v>>z<6ao`7}x& z4kWK728O9noVW$jhiS6rqx0bQk5wc-rmu)`k-nbMh&ed(9rNhUI8|QjKAM^KluTLP zpXxpRCZF(K6AXv-2E(|6P=4?wY+d;XbZz1x{op zSZA?jBb=l^xx|1*`X2bfEQVM7J^bEyK>1z{-f7yxIm@o>E?ioT2E@R5UJ{X8No!g* zVw}HzW-8fLs>qCe)MtaPs$v+=s|`3UFMsI|dN%e@(YzBLJG_SMwlCmDMHDn8#e%RM z{P=VwKmAi%xb2((_J@~)o2?%E+&2@h4F3Szm0sd#!X(TE#Kc{C%k*xrQBD7|mqI`( z{qf|TeB708@(3;sOg0~aNbIi(JW>biqFzGjj3~$(8wYtceqb771eYB{A>e%y1Wok= zd37h&V75JE1|`76s}>@rrAb_Dc*Ja57s2eCwn(+#ZZ9?Y=Sz#AgiKB9PIQ~jg6{ih z@rK z!-f$F(Ej;j>^C?MbwBIjJJxH4hqRTyJ{c@x#!8rSVKjH#xH_+no7iU(l6mItUb+jZgQd5ES&f{vI=asoFhWStDsB~>S?C#->~$6 zp>+eX=_2qPSYxxy_1$gRe!aV}b1yB0QhhgAaHkpu-|YrIpEQBk>=#E9@>#^ZL5$+W zY0j|IEbftx3k@s0LDYtuz}oh=h+uMRQ;&`=e-1*=?>|NR_R<@ey4>Rul$R&L6uql( zcw03rrW@c=J6qU&^(nY{w*w8w4G5;0#8)Asf#?rxC**Q=v59qyO{y%v`f z&mmSs@auGHe-12^3V@|*VwJ-rE)+&Tydq-yXr;rTCubqzN;&B}`Z<{z`Vl&MtcTUx z-NB-!LBuSQM)MOffhlPPU5nl;FHGJ;o$P{Pqj4{O?(UaFXvdDYgOTD`8WQr>_-l>$ z&V+~o>3K{N^cy0B>^vKY`@WX^*L^aX+)zapAIKxq_Z8x{x2-s#L!{qE!y7MFMjn@S z4{21+@N=Re%k$-HuMH+E9(WUr22LyuS$91IDqBr#pAVp@LH`sYwh(B@|=P(k@*HZKb8y()SqZ(r!wksfZ!6}h;fvWt=mOE8{2y+P;l%S*mnL7^WR^g zg&#T;rVsr`?U>W_`_#E`s#!A6ijhV$5;1*b%ef`d+sqRj9I1bvir*Z1TRyY>BC#}N zUBCj0 zCzT%_NSH~88RPEFReAQ#AM)OTwq^$KQy0(Uy&qbTc$C6Nl&a8w>j$w|j5`{76k=a> z6fcW~T4(vyFYwf`6|z?jp>YdysmHBUn%=5TyS#LR(lDv~P$^+p#B^#C#c3=yP*Pt9 z>h6D#?^fl-8t>O6w}T+< zZKycYQY6e$#B>|Qa{+!P+?<{cG-bUnpBJi5r`Qvw5qFz{J5P1M4pGjNa-#?QFgYdm zM%Angg)xU3V4mtT9Pc>*j{jar9`3Ru&7XTh=YS*7#VbL?_(_;`hW4A6z$-L}{QhAMxt3jE<&9Dzgb54H7hk)7guBDvgI?fZ zs2y!V?3%ZdO1IuX76n5yO%X9x(r0bE@X)ZKT-%Fs_NESW*s4Q(a?CV(Yy4(aAc|mx zLYE-tadsf0I4O434XHpD`LcU?6ODi2s2~`BzD(_mIXb;CfUsm z?%*~06HwVFv1Vg=XA4`{?hEXX-p{VM90&%Jaz#wJv~=!AOu*=Nsu#EWt7err(EcNL z^N%0OsBXX?mANA}!LE4(UV$T^<-m4u_A`UXJ8Q%WlyJVWdDaZOg1$karh@hMDuEV9 zSJ3|19{5Li#2Utln9%$zj~G!DgyOk9X6+ zjmfY!wI}K|uk#jD!@<0{THHh14o?TGA(5gip{V#R6ql_B%U}nnbh(B1X(QN(BP_&B z@Pc;-J>c;6H0Xxr8p0IF`5=zwIAZi;GYjJS^i}!%bD|5o|Apg=^Wfz30aR#R6hs!L zmqNwfDD(J}VphbZZXemc#8ezxn6PQ81Wa2TsvZupl=N+#er@(8Vff3T%Q- zzjna&hHvua!wp5?bH<#Vl!<3C#Q3?}K4K9pkvV_S;%)nC*n2WpvXL`+r zmYfHE?Jos1KB0WkQ@o~YtP{%*8SDiJymdk})lPf<1DJFth-A-`nQepN<8pI2>N*Tm zzxCMeBYLsMl_w$T=vfhSx>0;+MTiN@Q8D92_ve(o+~`vUrL*)Jh_~S=8iA)Y?d@+t zfpWyq%JZ<*CR4O#G0OYL3h&KHpB~VJGKI1g{@`4C9w4&>E`7fXcC}Uz*E~$b=)M;* zcMua)ZORPD)Zj+h;^y|var)w8KH2M0BF;2*qYt7orSwKVJfDfSx=cR2S8L10hkC>C zqTNtpbOvU>xC$BL6XD#;lhC$HF5H=Vn~a|0E*=WqrO`Y_jQ?qUnbP;0GC6o3{kC%< ztsR%o4>`{B207T|huuU@SY2-nQo-n`^P&UHbz@D|{Vhg=OsmEar2oj+&!1r#US76q zV-6p~R>6&B4)Tdxf<#%u1_@J*n8b!erN@YRW$`k1+M`QPUj3^DIT8`YTjU*qwDKkq zBQ%uh=Ux`8gRAanvE_68VP#@EA2QFeaPt zf&MWLoh?p*=GS+ihLKc_wHN62YwCq>O|Frv{klN$`i^Yx?|-1ve;S45UnQN5pM=p; zV8=>A8dE-Qg3>w3gHG<*hBytI#-~gOR6RAa1QRVZo53j%zp@O{eyE^yP!JJ?NLd zvxttzfBdI^Lsib6SpIQ{2SK0q%J+fjL@qS`3oTeeW6asA!F0P>9@X_$fQI)$Nb~#) z&XzT>yH_YJtUWK*Y_>`7O+UnZ>CQ7_&5XFt4?QS*d;vE%zXKhc`a@=1^NFL}7jmoZ z$gY`|#9|5I^XKn__ePH3obeUZRZpO8-@&}1#azT}lrUov^P<;%X2zuR+)n&$ejd3; zEK9r7PNg5^CEH?1-SYuZj>1>L99YoVbQzQcr##I>oz2yC`Y@_;9m%-u4Gpi>fYDwx z_NVLx#67hmC#xj?w3*V#eo?M=ZaixPD>&Yn%HF7zYpdJ}MFCql8?Zm~3^ zdlnBGeIww*x}DH(*i?``S7+66`+nQ*1e6-hgvKAbto-hKsKR&5Wy%0nSkoe;_r?Y> zw+s5nHG6DQ;up=U-mxQrH%*qShHkjrthpk_TYj3kw_vR*cFkUTb#)?bIdzew1#Ktpn%Q8I z8U}j5)?rXk1LW1#pvEZ-c3n(@?_CbTygy3F{c{~wFD`+_`_f>VPBlymQis!aU13}L z4-g)jb%TiULd?>FIkHKW<5Xms8%?`>mo8hj7?Pv=g5U$?^!zx~9kdYzFjn2_#a8*h zAF&o47z$yseNgOY3%!ybg6>SL@90o?-7{RS+j$}B{y9y=xV;fEfrz15cAW9ib}9=E zS6X$lnfkvkLU+FB||Rb&jiWbb13^ttm;i9*c1 zbx|;O#x}X>KyCV{%Xx7X(5@FTk%;ND`Xe`TKsMLwp);MWc9LK9Wv%ctf)KM~8=DD{ z8(hF??|&eaA8d|>LG-6{qRvLStOFZ7ryqMa;V`U5TTuI;L$J5g0JwNZ4c{XRaWn;WiR_6N+Le-W!32F;j?XmEZt zghan1{yjeu!40lvKZ=uwDqzIhHmqf*uh=plD3*qrV$vYap%~6!zS^iK9P#=5mRxDQ zfYGjzpmQP}t^`WE&U9%sd5C!zb5@y^GG6KQ%8@$nUJaYO8OskPjRp1nn5l9rPpopZ z)oI6C{%(O!X9BQ|5hd6^Qz3neFI0^71+Scor1@(e(N9u`C^b#kocRO{ZCl0B?3PBu zA!b>yuFThXsq*Ow2fBm%O*F%{lHtXL#C=Es)V#k03RKx&_t0XS8vhe9T{xA9*>w$# zPRmY!=KC-Fye1hPz^l=y1D<@>iHTr0Hb=xHNthdmL7NrxL-zUwkGywLqokgE@VH#L zUB(O2I4mFHJ7HJ=mWKK?cliGpA!$iHC>=TuMK_UES74n<1YLFSKJ8(0hHAvwQ@_WD z!EW&a5#t~|v@*m@jiE}~C((S7hdrIs9xF*v3FOX+k3_JWvasXeI8K3(fOhOU$FJc3 z+Xv0G(Dm}&ad?Me!`a1eK(jqh>pN%_PMY(Bj$yOuDzj-2G!v!1_-C_(d5)ODKW(`6 zt!A?37(2Q-z=U>-TfzMpu|pJ&#s5}8o#{G=u4)k%n~I^fVsx10<>O%I)C!kd-@?Y| zBC3(wwQ#b5R-uN?ISS8~!J4&FHql}UQ-_#-+)-}L99E|BekZka&*19@6v|4zrVxXp zr=ZcA!k{0fVo-pfApY%7L<8E0=v0{WpE_GXYv9?yB%0;_kM_}RrYFw@QSGh!;9#e5 z;zRpS!hAx^#1omE@#&@J=Lhbj8;U*okkK3;^B{yYF_~i6mRChvSZ8<^YE~zK^UbcJ z1}Y-s7|d1EVAWh}z*z;fep?~^YIlKlSfEd<*#PV)njm6wr77?OF>U_4%H7{)rEHG0 zrM}8Y-hJPDe*OKfM0e?NF<_(2@d8nd4+6c%&QRF?0kPe2UljGZZqs082cN^VrpbKb zUpuPPZy}xdj#U*2rSMVGowT8ZQTM@%74n3us%X#ITiDX2&HMS+GHt50?~&Z(X9~&@ zZ$kBVJVcCN4aRO};59Up2)^nIoFZXgggUz?t^)2fGUP+$9DYOMDBk}zOCr05qXWhU zaWs9Tht>%(+H2l&>WmE+GtQQ7cbd!hOYKU#begV;z)NC5HKev_wsu%~qyS@C8Eu}JI%wQVE8tzMES+SQ1QO;5y3wrb&y8J^~{ zw%gKK`rr8AuL~&&s8=(r5-D#(sJS)vgu)kEb(_r|Ns(z9b|`DoH7oN}41| z&OYltX_BOpD5*pfWgb(>luBlj$Sfo?3Fn->P$EQ$1`VImB$Xshnx3`y{ysndd%a(4 zpS9Os>st4HT?3*+6=XCHSLuO!yYY&#bJzlZE!z(8Uz3Mk#TkI2SOHuDKd=gvBq>|$ z==cS4+ipR)cqaU@S&nWF?M62!Rluv`;6x5rYITGgjTXUl>>n%kZC4Rr=O4nOrn}Se zCgyn0hZA%Rae-$FV2bM=vkxuIb^;jvQy}gZ55Z%K4^;b02=jnEE(36Y@AG{rWea^z01y5n` zuH7)%@e}Nv+YI+_OcAWScL@%!oCJ#7zt962XJP%EWEQjX35zizn8F2e;x_;N;*3R3 zm~UwzP&|-GwnDw^5x08MOY;2>fV>0e;l?*_V&t68dUR=5SitsJV%bg(9gXjn3671G z1J|5?&}!BUSnvr7-f#slyB@O`GlJPLHC!~~`X;g08E4$ua1*BLZ6JLD$)PvNZ*-ugCA$Pp| z+anm8a25<)=HlM8Sjdxk2Z;ycAThEC299UIw_qAVWcs1p;UL*&GuB4Zag5vc+Vs$sC+Q3JhK*#gQolLb|NT7uq@;o!|{ zU@?ClvKU{2N!jv^YMnJ8EL8Kxjuj{Am{&S5dfFydvtbVGO2kL4=|Vn47+hjawF`g$ zX5Sl?Fa_u!kve0u#(-f^4IG^I8bS?Z1x`C`AU}+=X}ic_f(fQRJc`m#$P?cC>Vr#% z-^7l3ir|(khn0?yQ(EW;*52^%<`U?w&LeqVl~5)vDX@+6hZ)3rvSVig@p|xwn&k=b z&Y~37kxR=c%S6;3^nm?(_CI1r6G1S=CvWpEy|fd)IPZ%Mi8o#Tg-*JxXgZb*i3F{D zk|F&lm%J~;+>}?$N<*K=ju0@_cBW3V;cCq+XfS>cfB$uY-u7`I`8EhPs)nHFwc#vA zjr(m92*%p+lF)6krO@>DQCzt(3cKnrMd2&&(WOKc40Rd+#xNu0?=^6%C3^#pYp^ar zR&d`Z1lBL7#b$dl=pB2Tq03tY%Zv=+?BRI$t!|9X9!Xq6!FU<`dTNH^-nFrIpqHyq)8z9=iW$5Y=u>~-U0qtOOkSQ>Xo~>emjm=s2G?Y0DH>KF}Zu zSZQFEodZnpX5E--ki2*a9L{Btl954VtFZz<@uo*zt ze{Mr!oC_~chQiXv4G?}nQgAZL4qfq`#E#|>_t2z+B_-Ar^-;raREds|UfllkOaR=V9Jne0kD$aXITm$Zjy)74Z#!Inp$NGz!8@A|;poi8Et zhK#^>nCJg#HY+)dBEhWg_(#nb^o!p7Jc>_h@=;Hf06*}KLh6%eK*!0skT~TesP>bB z@rP}!VFuHM_ato&6to%&_>LqhEEj{5v^yw!J_o(AqXdPgWCY9RZ4@xSjTbl5R0$@+ zNs8ZpK~B7A^-)}0e+sR!)WikF;V4VT4a{{dh;DO&^-Q7diO@xCL94SP;LW5+_!m48 zP4oMQJO*#WJ_UbR)bbcI9fk{Pe@%y#i#eg|Ifv0880|r6{v#tbarjDKEFA~P!svro zX|op8kr}qi(iei)9bwhM(7sN#1S#`wcXwe}eVo zocbfyksZx=4zrM8wk;D=2|Ff>BSs&=*PmR$*B#Cw?TlAQa(6zdvI~dtRohJ_HnoakeWRTkG4T&e8fZNC}wr|bJE}JcYu_e2gw}I)z z>j^Cix`FNm?sWA>(SVRiv9%@>n+@8N^~WI@D>*O0e}h{u`1@RHQB@7`TU zQ%gA;gC6donGnpT^EINypXZ4j|9RlcU72{3$9b^OoC3B-nG6ro9#2#bC95|ukoK4@ zPGY1X)lZoq|7D6`f7DXJ4}L4CC*=e0asc$?OT+NuO8y?fdv>u|%&pKC1ar-*U9`o1 zfA#JXcl_{f3mVbo54{Fok)cIB*pf^RGg8^*EB^tMmOX*IqBvkMjBSqa&sc$$^;m(& ztt{Aib03^r9|;Fy4!{^MJs9^?$YR!V7#o6#Y`Gx1nwiN9-s6UknP(E8XL6p@K~8T&SH91>0#m zb`>b%Fb)J$VBRZyeqEN5J>!ZW%AST^n=xq2Cr(e(DJ^2%c?{t@%-H^%JV0{aM)m`Y zwSIrbb~xcZ7a}gqg5x!+FhzeIoJ-yU#;zSuzW6?i`N6FM9t3kp(t=l;@`bk{%>@tX z+rz756JbH~Jj7&u_bw=7RrSE$-;i>mn|*JTovT<(w@NVlxkJKXq_)w~eUE9XZwW11 zKbn7<+?%d@#PtzO@wQoO;q}*cb_x`6m>7cD@uO6@TW%Zmxxg7aWm@28W0s<% zlHq(t9c0{j;+`A>uPHsii1)rtL9j6S256yjIP|&|);*~OiI94{QA4`soAw_pS5}VI zl}(}fDu)@)oz^ZA%xc|bqA&0FQ}^?a@XVrlNaNQWK9fgaaI6yaKECvo4v(c=ZkugS+BjlbbX8Xs^-MKX5kTLuxj66_TC#*HSMU|x8f z5N$u~Kqa_2<8k}*>3J!tbgOn1YtUr1xe^Y(nE|~(`lK!=K-Mj7HsZCE*s+zY`3`UA zJcE}+gz;^mF_m-`KaV!Xn~V-Xp&Zvx7R`;Om|*O-ril2`tEuGe&NwKRru}o%=`?e9 zA=8MdV_XUS$-OAzO$caMIYO4L6sxBVoVx6aS!Agi1Xup24t8=6?FPYYnB6Hl zcU7Nf7Dei8X2j5&qsQQN1?RN2FjSz1zHKFI;&e$zVVRIw$m9u%N;5HBw>gh z+_1P*;tG`7&|sqxjbu%=AvjoyEly%EhQzC*P+<@{(%Qf!PYK)#jw9!)D5UarBm}u# z1fQdvdDd?Z^N?UPKm8OfZvau|Bo`dm+)T^p*kL>W&*C8`PPVgIRER`QOQ7FJ8eEoq zW=B(a`y3c5eTSp_JAw3T!}30NG|n*sIS?3oPlo7| zy$iPb=}PlY>){8P>a@eFOKi%ow)g?MVafxS4T>OjZ!|jvRJTNe$Xrq|THMWQHagY; z0)J&$K|)}V!1Q$zj7s7#8QjwOfncg)6~)spy%yOux?sn$LfSga4qG&+(0S^aY@pL~ zcSSfh)f{Y$HDR!GIoJ*nkGt&CusBFk5I{7YBL!K4X1`^Evo`h+A^j946y<_7Nzh_; zHq{;MNBSGVSQtzcXM7kdwpVh+%AM-s+G7T|D)X&aZf_beF+0p&K+>Q7LB|gugbVCSixjq$E*w&)GVM5w_<5dW2<-~h)4kK|=Qo{3qx>y6x7xON< z;^v+v{>AhQe1EC2xM^7`bZu>h(9j@o`;Z8${Eo9_*NhI$7&k|!RRaodBXJd`f||>{ zFu|l5_Gg^{(TG>D^VTqSXY;b19gQ5ptdDIIl~~Uf%b2?1(A>p*i{|NYzq^rUFfng$ zL)U>bptFe7su9hGxsyizx4>ilQAq9@1V!>4icDTC_-cF$?%eW$WOH)&c8c`w{>^3| z+R$AVGoE0);E-tX2L-X3ygN29Ag$F_8jv_pNHdaZ*SI#YEslhy%ef#|mdaK?WV~u- z+kE=B9EVJ&TM#1I0%uC^@|#u?S3m6tusls<*pp%wV}FmuOeGkD+{HZ0-L&Yag$Hg_ z>VP7#Ekt}OpaZvMfU4jQR4+(i#grJW%g|>=gYAztU^-Tc7pwrq>NNOZ9|zx~-td3R zjS+0Ik`=r(d<1*;RI-=>4x>phO2;E8uNmt_JPS`;nEL}PUspk)UnAYMJrj(N++htf zx(rF0EU6j_jUtyVlRH`4oXTyBVQoV)(KcOCx#Mwh^cgZE_GPnv%ldM&vkQE`(yfE0e z(FRWcO@pzwrhwtDrBJt5QlR&N6wNM-hbtDRS<0>KMaskBDi6GweIlH;tk(N&q722V}k@Okdbpr9(Fc@|* zABqwrA*{EM{d)f3Flz{A*Sr{mv~k%ynCXKx$U*yM^*GV%p6hgIXa-vb7aBz{*M(5M zs1)w^iQ!x8Yp`{WBhl0$Fq&LEg4s(LKdJ<3CkVNdVX1&Spn*qm!Kin+Qhx zYoD-YZ5(gi@FO@Q)ftz(Uym*}`_QFf8EjSrW7!%pvId@AtpLeuG#IPBhoO1r;c@IU z{=3M`>a3eh&>fQwN8}Vh_pu=a76s7hK9)4|+t_e>Xe)xLT0Motw^Z?xlaAnlnYU2j zw>(6Da%M-P+V=o_rxZhJ!M|P{eaQ|%lsd+nAICKi+;&#J%Ehl*L zJQzkoG>-b0VWOR0?$^ zjnMa?8tOtx$P@jJ^@rYIc@YcFT*t2Om0)Q3FO+?{5VT2+u9xC7{5yaXQ#NoICxY2p zIGN`+Xh5CW=!^TWZi1dgGtdgtNO37??_t`pL&+{?mlN4?bX5~KMIm(a$ytZ!X=@hI zczXK>oHU^m9liM;EsMViuQ&b&nq$A>7eSaE%?a*A;6pIWkP5Zx)*dQ_xFyU2H3&H) zgBH4mi@P_IwT#rNCz3$Ao9Qjkx}uuZ(Islu){y$9K&tlLZ_Q#c)@6hUlALwbb z9dO>CJ>WhGk;}`+Ag<|#mj7m9_k*VFOk2xsIpPWC&zry5}jOy6JV~QKbl~#Cwa; zYz*o};JYFpg00oTs3`(Xe=`n+kG+5noQs3qa~(k$?!W_sXOJGAhW@k;17<@1PwUJh z81MHPRBg^eq4_^jGP1#mzxt*kmaq$^8pX9Ju3w56X{SS|9!ZR|rb#y*38bB@3J>p{ zLu+S_0QuL6=%hv}Bo73^y1)0}OW11&UY3kT`3`3>6`V9wPB7tzN~yIyGNLn|e6gJE zIushc2sc*!;@P}@hW1*@fZLdh?1W}4!kP9smmkxhM!6IzIZJ`phC~#rTLi7=!oWSL z3lcKlk_G8JvYjf;V*YZ!4NWi$c3h`+&9oD3dFqQ_#JZr{>&9aXXFa})>u_LfbJ}mk zgHCo6_^Q_uL!c~BJg3FFUDuA529AXa4|$RgwRv+3e*;(?~Fr zGM-W{X4xVU?Tb5hlMb}I!*Rx?wS30vShrFGy4Oa-(3M+|;a$hx-}FCN11^UrLuLGC z!Fq#1*nXOn&G*KD(o|wb>nI^OrMF1XVq+m-ew+WeHLaas#yogW&7ajKT9NOIzqX!6 zb0mM#sOK!z(Y6x?r&&WFxh~CCy~P%e%?M6`(2j7hu=R(`&>{3Dtp`;o--d0*QE=vx zgdp|(Z_wGJ0Gm`>*bl*N4)cUyCMpk7`rZ8^yOX3u@m>&`uar!eI+`J-;F7V;u}UXB zxf5=YjP-if(unc1>DzG@%xC7&7G?9%%lpxwaQ-+PHW)3~nKnXD{%onB+Sr{PO#}BK zctbFhcL$~M@t^3*XkXkK6N{-W+mO{$9-r9`T5Tt#*DFr34~?-p?zT*ZywptiCW?T{ z#)BZ;uLpBZM!^yLqu}t5XwVOS!^Wt4#P@zAi?QV}{RFcp>>TCwpj&h?^awuXnv6y6 z@hE91n(wxy5PAbhw-@PR9m;EBa|#(ub!`sJAl^{oa$-WeJsCu!9>JQ@I!LbSfh9zc zd=PIBZn9jRjWoA(4iU^2mvy|Zs3g%qpAYsnEX8rbe(>SeEW|`3=MCd(IhfaTNUwo- zswP9beIZo%5et?b;h<8H1<6jIL6qGF`UN-P!C5!>H0l*P)xVaV(AwN@BNaka4$Xxk zE3eU_zeDJWML_!nr(uCYn}Z5R1RaoVH5~PEBm;pXHjl-E@>!x*T91$V@v3jJByeE zW}U}Htg981Cta7^01U=q%r)qpoe6&nKEv(P-C(PE0={mugUuP;kX)DxfmVYkb0$~I z!Q(J01T*;w5|u{P@LEQA=rkIvRMlFE+&b8 zFE2r^y#t*6VF~)T55l%#>mjc2C3w=8q5NSc%vsgMKD5~!W(L9h{r$K4_b53k%gqZn z9hw6+rt+|@W&z40hX+RGFl>w`o7!iPN2<1&5=Fo17?cWfVElg;U>cwT2?Kx76mt<$ znj8k1PfvqWbuKtB;~M|Ja5HT_!HDjSptOqRspILMI6&GB`ZbD#2FBZv++lLtky{0- zCrH%sUg86_rG>>X1u%Mo%dqUeKGc0tg0&=MXso@nXl>*|R5s=);-w~n{n=J->Etka z1XHwtM{TiHrRGfc#QJk7y7-tjD!FWcB!ATa)8@nEcxcgYp!!HF>-}I#zWGdgoLZ6- zp!cib&3*%X;rn6C@7BljTIH~y(*njEFFv?G5ss1KI>gaV3d_XH5hx{}| z{+E*Yatmr9V<8RIeFp7;Q7SqY^ppH z?x;fvcs?9g}wk9%x|Ri3}6?|-rcRBgeIW;%y)Bbd;|Dx%Zp@~Ph&-LQmQ z811?4kw~rB2-T5vU$ZeHRvPlSXv}64N%a0iOnANA&=ugPet@RkVlb(k%72IY#P#R; z#hZ;&`JtX7S+?{@n9=2IXKlIG!GakeYW|OZF`AnD%#rD6^Cg*2p%{}t|thoeU z+yBAuYquaFeHhsHq@g=&vr%EmA0)TU9a_lQhxteYx8;Z;m}B!|MS~Grsgw4uIK(-S zzW?eKt$O4XKT$T1RiL6IThRD+O-QR62L6V>5ffg|lqg=^F;Z}P>;rOomVyyYNyz2r zCFK6?FWNBZ3RB)iv6xg2lSnZ4@8yVObN}#uts|omKcv6Bk-?qc0{Nl7q~cyy1T}&0 z(JMV&*z|BTWJM}MYkmu8y-I@j-lGNOu1_IyoHQJjNKG}&bq&j(y_;KPgbgGLRkZZ}p~7o17n7ZJFeP=N9CSFl#c^EI@<&y?J# zpCg8IzZC@s4nBoB(rJRtHGzU#=9SQ*V=B-*76UnV3)#^~aHA}2*#7TAksKHQ`EB64a=x) zhMN<5QJHWt?fZyWv02nY?@iLQ6h!WEEK(uA4R#j~)UYn-sdMD}|h(YoT2+ znQg&h9AJhlOTntL3HA>^0~adup*XM{WcDlqr```}`)4)5%tm!VN^%?I-{m@sPjRcj zbAtJg(x7yTE*bRZy5s-qGhn)jJhYY6&_n-Hp)RnFjSFc%Qw+umS0sa0pO|Z3cn!ryg57y7kWk<7;Thn?8Mn`=GwcCC)b>7YcOaAJ` z_oqaOlfQ1+wvvynz}$JbT1#;eHz>f=T=sCRAH)Ma>a-<74wypb@<1;^iLmXvy?kR)l0?tCh`eveJ<1 z#cD8p-pw}tKb!fLHny9G_3WHr-bXz+nRXIvRARyYqaFU;xdJmQ^a5@|Pa&B1h9h}4 zA}gx+s5jnqc|Pp^7LLx^2eYcW)kl(!O~e%DP{2@HLx+{9?ZDafVXvVO-t{%RbV#36w<3HE#Y2D`?NQHneGV^+phBVzLBAr zsLG*Z*FlM-{kGpD5%0v$hQUO9x(B`_LL`B%!%LsNBA%eD&{FFXG<5SGRNrZbjSan6 zBJl=0np+%3n_v{@##5>XO{rrp-Z&=oJ^Ik>Ko1y>6iH4Xg_Ff3U}GQA(JtPGHyJ{< zr!cWW2seItfbFzeygcYNo_F9r3S3XT@B>MaOmj1&j(dVPZY^aoPTc*C0l{qhoI{Ox zJ&_tX0rtw=wJ)#BLUE=Zvl7;s*7R*+av6x*gA~sb%TRRD)t_vW_EFS+pB*G?& z>mjOM3)-fO!TC@PoGZSBZ_oE(F|FKaRuPQT(LBm~#y;MktKK*(JeGc&ri>r_c_@nd zs0({nIDoNv5i1Qb1u)Enjw>X+gk__k$7>dTRp^E_Kls3culwK#8Tqv1d7$)Z2@d~s zpVe$WaHBCLm}3^1RL>b%p}5K$56#jRyQa;@$2Of1U0f~&dkYq`HBgMoVY;n`4M=A+ zn<(S!$kk;t|4C1$SpIVa{CIX2T%KpbJF*UzZ#gV}?qJGJ=u6z!a~r`dzj%@Qx$>{j z@s>BX2}MSGPr3&57qy& z5%rAxiwwVJu*FGC5xI_883ZpH&w3DB+!;ixb`+th-4WnMLZ1&Ty#xD6r`|ueGL%%= z&*}oD9Of{=WO!9lQnE>+$UENnOaDSNlT<-2i*pwL_^%7;E|y?j;+aw_rf-eW)1;=U zu$s;DtpljKvjo{)kA`#MkuYFOJZ}OUU{Yl%3UL3-VkEiJUN3^Nf80Xp&#f1I8uG?n zS^+4yL>3>SR*3tJ{sNQf#Uw2$O=|$H6*pjZdLc+%odHG0tzF5`Nmayg7Y!Q5;5Os#tQRWy8(58i0=3JKgLiE+j|QPgi@bsVlr zCi6KWJJhqL+D>EgAwhLHxXhFT?`t-Kgy?C4e<2CbE1dv_FNXtS4|NzACe^W}R*b8a*_aI0!GDg&X8KV34{?%;8*EVs zge4@?^Kt$VtS#mVj_l*=Y|OaPq!7%=jne$wxOw7w9Up97G#@|t?8m5{V+AKWy5Y*tVFD#dRRJ@ayWH!U zOEB?`os_bjni#A2;CUi1EHgX=nQYM#Gtv-~g2lL9GZ-e&$xN8TS{<8ih=Q#jNpY-N z1iU>;Y(hrd2a~{0Ft;`un#gi{$${&WcIPmq1hZ(O0Ts~jM|76Fo)4B}V*B7j@VD^; z-?yBcFP|5Jfqf`JaSx4&bz`iKwMZDJbwf1F4UdD={wFZh{si_!-G?pZR*>=91j^dE z=8MI^~ zN`Yy<7`NmR98i)LY}=Oz-|gE$MZFFFWLU!3mzik$e9j^~m&4p7m`{_;MeD~d6>XpC zjf3_rp_i^UhX=QBA~zRuSf5!zywqb^*^aRSWBk(?KbwrkblCps7WnDC1)6^bHW_8W znCKoD)^&o^6f6YSZJadpzcuX+!35cAi?q~+3HOG1krsec=z9BF@ITbb&mdkyOf82m z@lDN0Yyr6|q>7tNXoC^etY+h9mj|P4OCU(qk3@=+a5S?gFx~nj)F%3Z&%P{nLc4Pl zx{F|3oYo8L2gL^S`aE&AMGVNs{zTs^7b7i6qSO*Gg=vy)H@gc1Ypw&6_1*nN1X^Qr z!Bu4+EFNP75u4s3-MVR@ts*bD-*FxKmk={8iz*hg^gnj#d_^$AYjwOSO6PfIT zP@+aUGJfAgI$hqfm{bnaM=-}1?xOnT5_xY+J#g^SX-Gmz1?hIrM@)MhbMVM$Aa~Qm z*vyt!&te#9h$*tLkmkX1#qluX=_u^vqlAMbzSAxlpXtA8nNWW%fyGpEm>&d_khGDi zN|L5FYkA1oemF1=tMn&fG68>KLTqP9`gSCKn5oBx77(>4MWowuMo zO%7v5wtI{SspKStg%v44hc-gt#8P-ukp$7JgW&OrMyyc(4FBtC!|VPE@$0H}pk6D* zVzmC(e?u^br(fWmJ{LjtYPjRe)_t_yjACT(;Ds0kiZO0x1mZWUVyGLq%sP?Fy(5}* zcPZ%VpNAkHPk5u)f)n1p!tzt@;|1@l@SD~Um_5am#mwh0$^=utT9bFxGncwz=Y|dU zRMP0bCiHYoKC5;5?kAmId-kwh5e~9Zuy^r6_Uzg9Unz)(-GR#=^I`AtTpVtF9aFL; z_{FYBygp|SED7XtasSs-s7^4utwvQVHrG))iLN-wY#*()Hw1mC31t(?Bn3j)=DrBJ z%!6T-#y(gTvV_Ixy(ociFP?zBZZXIou*6$iL-4yv4mfQ26uiH|1-@S1#Ezzn>y6SP zm_Y>_;lyWcRN*HVoXSh2Rnw#pd_99~+pdDcswz0>G90GxOyEw>LMR?L5|k&C2}=|x znF-(EnNi8i!qcYw@H@^hONC4i@^_iT=n~A%yau7s$;Z?(BNx1T z{Aqfz@+<0?>KWuPmPp;@*I?7kHl(?4KC9XEAL~J?VYeV}P9d~r4il^*hsNgIbNu7t zAaP)wiFm=rCjMM11ZL9PSd1dqR*DGbllN57my?~;ni6N6^RbAov$-lJ0dOerS|M~_ zs{n1qT6B2tbV#fGj<%`4M9fTMatcSD93@!n)(GmIL&(?SGMaEJA3b059cgU}hV|!N zSd1fwF(R0o%S=R4x9cfs183qs>PR1-6Gl(GwE=Z6zrqT{Ob&bF;0$Q=|A82xiz!Yr z^vs2#rAmUNBlRG6;UDpe$U@a>g(&pHSF}Yb3U0awuoxQ-V@5C+%-uzDnR(RG7AJh8 zak9AI>pCqzX$g{io&$NGuR_{_*Qi*$5Y$)5u)R^t>&X;c&QB*^cFH&5%6v&!)t-tT z#^j^I2|v&taxu1lM>31i;97pI2}Zc=r0B=dv(zYOCp>xDczQ^!mkwV4g0C8q1sV7% z{K%66#stXxtqN=t&w+R;@q9j#sUcQwR9x1h(-pk)BZdese=aJ|mxj@oF z(j5tP25I1MDvl&#<${$bvC1K(R)0Js1c|@P;O;gff$;b^LHuDKc=W*wj5c(`^<+-y zvg4M{V1n6g9xu9Z_5ja5)(NNn8U_o8$Dll?d*Vd$ozYUMBvq-z+Q^->T9v1jc* zuXMOcI=W(xrL!2bhjm~;+OljiNxJM3a<>+c4N^HIRe{*J#dJ#wR8BNQy46J%bBfyw zWDtykeIl=Rz@M_d=8QKkXr#@Gk0J$~Y}%@h_}UwYSfiQhta7%Yj1jt+*E2Bq0+@a6 zf_IBa!r$MgkV#Y!U;72RHwTOzS3lbr=Ie~H&nMHy5WwXm@Ve#DvY!;xC}7)tEic7(#5$Y{7dJqHrJ zwBXPNLlz_8Fck#TH2#LrC?|qyqg?S*J5_q*oMUvcmn+@tmBR{M4n#p`x`~*p2t7km z9Q&^g49<}Vzi<+=)EFhwjrS!Qb2t z8b%xh+l}F{U>WI~3Nm6bdE6eliD00iyZY{;1gc?{8+Oo4Le+t%kc9J8y1TLny5gFM zDN`A#iM|P@^UB#8C`Rb&D$NFMVgn+OSB58-SAp@|iBQ-X23j{S!mPQc;9{a5i@Cy$ zrh{PakMiWnwnb9oJ>Br8aUooQf2DX91^aidP_bUz5`>sKd=|wQOe4NE>4q|`3B;o>q4 zSY}l$UMErz*WIZgf#~g^bc%QnldvsDvr(OlN&UbRs7}g*-*-2l=`F($m2H7!4@IM0 zC<7uUlt965V&uT*Zakv7(ex0^?-EPO$S{=3yX1!Ret#0HUH>K43z8Kvfwg8@o#4BU z)Ns_b!J2(ys5Ytvhmilk?0i1#nSBin6-1)SzfV!|21z)&@dQM-27~wBvtX?~fgR0o z4l_V77Aaa((vlD=hjzm$o&ogV)*Nwvu&tPJQS2>$KrW2MtfR73DDfa3bsgU1zX0Z% zi060@opdTfdydF~wY~-fH<-dmyp^ooBhhk9zdk4KIl6 zq)*RH66K$nEY9;4f|cqcsP+_t-h_K>3YLTY4K{~el1z^alg5bb^3%oQOY=bY0+0?# zvg_%e2G*~n=o!a@Sml3a6%3KZKA$qeX9D-))sq&1SK&60|EdiV7nI>qE-|cG9Eh2n%>zys zP$U>}R#f$T3rA|@aCiK61YfM|A1#`ienb>Q zShDVs~RhC24x5%`i_A7 z#v8DZ7;NNZrr=-2$63q*?jx;FFb?6vsrhnSs96MKcP|}f8$B0Syb)522l1-;`#>(I z6lUnOk}FdYTc0-n>|xMClA;UcrZ`z+=YcfPS8nE9Q7)R&A{o_v-Yw)p3d{!D*IN3Pw-mpFGD z$+~<+OzR@k@7ep7K$&1oNL%3^hsFzA8S<4Ns*s(KHy2_h?Vx`{+MKn)=@m5^=Yk1U__OKY!Dse<0N`0<4IovED|~r9xVM3tO^4Fpr!LwzneFmH}k4 zyBO^g)xwdDHE@O0dtBCO0-pU9w7ZUM>&f3bZV&B2FlGtSRM)pfqBT3*@R)d4{`nD- zc#|koD6vBc%rnMA9#NZmt*h7@k0!Tt(0-%?&nFFsD_8aj*4Qi*=y|lmvR`drGyNlk zzI_1AORWSqM>`7`%qQ->@gtZex5Fv7gPtOpgKjwL*f8;Ay)61+@oQdg!76g+X+)Cb z&wy$+2^JXSvkEFePXgmVY(aMH#`of z3cv7mt#jGyRpU8vP;Ev!yorlq#DNm9h)4q8cSK?(i;eC3IiTC53ng9GKqIOX=AZ0` zKG|y^wWJb`Z0AbiowzmaBEjtW@}Boc$wCyo#0?*mTZpOb@nARSy@*Nq4fQAYYmxsrWk-m%fB~q($z^+)yab2?gf2ImcnL z3FhvcwNy)?)USX&cywPNCMTqD zY+10XprTY&udbN6GoXw+0K%0Y{~o{6@gtQv)iuZ==x;sSOw-In2?7hMG* z-bCZPnFw8$xzN5P5oVBkfghti;oMRKFuS@LrV10m)o>GBT%ZLvayYHCn;Xpyg6Wto zAxc&?rR?vxVrXy$1GxYcp?!;D@}zx9d>-Ql_t#I%dO|W71x2oP@nY~4SWL|8HT*`x z-xOtVzK}su7Xsj#jx!urOk_vn$4%%~f)PN*^1p93QJ$%;xT{wWjN&JvU9L_1j8SFe zTayEl8L@1uJTnCtH@KLCMQn7~y;5)VIn3W+_Te}Do52bEJ>)X-Y@9W`YS93pUm%M) z#eE1K5{%l5$GpK8##E#~F*)5f7VVohijIDEm_J}&4t1J&>?@L{B{;|pIf2331-=s0p7%lRg~F! zSKQ*;MeD`S6CXQ%jjz>N4l}f_fI)mb(a~-~;u+F5`ht`yn3c0lOY+5S=&J7oG?bHz zR5%h#dxdvR6>Ws;+o?D8kjc?R=Z+JA5X& z++kt?IJCus-$_!QNcPaa<4NDgQIhyaiuyX1YlCL+2>8BaG>ls?4n)c~(bA@7UdT%$ zQ9-Ufi&5l^&At)LNV`g5$jg;f(|;~F*If>q*ziT$?$dl`tM0q5fE`WfwFWR)Ls}Mm z$cg%YwS!7)HDHZu12UT4i*|1sK+o$t`6S(rc6%2@2U#|Wnb)(8!$^dZ#+YJNQAo~4 zDm%pmTaWL_)elFjj`U#)uTWh*-83v9-v&Sf_ zo#mwE=K`s|BW3aAi>lyUgj(YM^2Lo?kX>jB-*AC6%&dz?zOk|BXQYVzZB#f5y{QBf zIn!J?TlF9%Q|gQ_eTzjq9xmgXg#X76)hESC2IRfz3x~X&#Keqz2pHc%Nz$|4G(8bE zD#-J%FI1%6`8;ZBrvkm{{aKV@x|BaH<0#R93)nR+nDZUfBp5nxw9tRZjvBw$8MiE& zMK_ryiA4v}_-6i>Ku#r-ZCdJ;t7U_pyM9E0!NUS@Bfpo|4++Q)DMV>ux6$XSEohm> zCDid_I{ywh^R2DZSxh}Q8XbbEb-yCqH0}VEDR9P}=0)_!*i}?-#UDybG7Scv#Otq$|5q5OXl@@lUo#949 z5sb)Yq)5m=K+Rh2j9=f2qpREW`L9Qh;`_cMvDGUtK*u9rsIaYsjFd}YToVGSahITb z?pYAG@L=y+P58>ANfcZ&{Vyhs-uXF=?y-3$;+>UcM-#|7T&^LQvR4KoUB`n|#|+Yl z`8Jgv`gKusXS=+xo7~$lU(daV4uZ~ElE6sHc{FyPARldVXJB#?E~iYe*1cun91?T3q1qaW4RKDK z847nu!CvUj7%-W02>$q*!TBhC*f7Na8(j;+(aEm3|D_SG%-4Y_oika?6%MnPV2Y1z z5b6AW&%@TvIOWSAf46%ctv_ia)iLJ;38e`l*@Tl|z#@uuPRjj8f!W|`h|;u#q=W9z zx&JsEBnIinZn@#XIo5cd_B`w&mrBCy!&uB~4&y{HTA%eq%cvk;=PqYl=(PfY?rK`1 zrA%K#fq#63O^)>{lA$1oo5`NhC8uZOga*Lv)?Vi8W9 z`i1VDRu1B-vn(c_i#_lmn2<5LBGZp*yi;T}#?}YKUHT8i!Iq8Gt0lYOM(_bP3s1gm zAJ~K~ha1`Qa6{!VXclP0`2H$L4Z8_WMQZfvi7Gh$$1hr78c0Wz^6Wv~Q!GZzVFC$e z(J=$j$=h>z;!V!D?qIlBN${BeW1|+|M`;t>u-pOaImyVQc>@^Psk0@DQt`V%@Ja)8 ziEWYkgBECvea?S0djh>HAVr*fQ;lERCIW3|t_LLfrU58fM3fRK6aXlhOY5{>+h)NkZKO(EwmaD0&c-sBOC#ez%1iTlfW%T74q zh3|}!e!mXt&#dB~UbhO&?Y4tU^fk6m`mpa5IF>UJE}CzL#xaxOvXm!`d~X9&m#cut z?EuPm%|Wg&f1}fe5m3YD)WIkYQ%*2ywsyh=+duPiC?{;b#{jK=>4mbiMj+<5DW9YXvve$V>60TaT;441zjA{oP?1GYe6}}+rBgYKE{AC(82RYh>KUbylum{t zUbd;op zZZl@$e71bLJ#}O{xevxSyd!uVJ<&e}-R~JM zX5Jenn@BKb5r`J~fO(S%WX)U$zo#CB!N#Sq@xcR>eXb29X`Y5xV}Fa4pG%6~kUN7} z{|zF^1+wf4z4SYac|tH5k9G_B0b8lVL5|qUXP9{L3}YlG@j%=owF5lby%n-XHDspIO5%oA5d07G(YjGq&Q2@20CngAj*3!Xt?@8V~Pcs)R4|Rr(lv- z3?!Q{fd9GI0$Jqfz`RL)^!`C*{`IsnSYoUJCd*c`qgnrx#q<-*)N|52Yx5mc!*fRr zF3ITOkFnzSA%SAuv3nsnh%6dvrqH+CAGRH_0?o^o;M;PNT{<^P1&U-wl%Ta_&s;5B zNH-nc!`GX75%!)~2K_q&*xyENh{X&M%*v@{1|uyFQg0QV@VwQ_>F07@{K{uC^o`s5 zSkx$RrL&uB`#E-!vRXkTi7Wp*3+2Z9c)c@~sV0&e&1& zoJm))?g8;K2|tlv>TVXJVdx2hwc9{yjTbuwn9;O94P-IGzn=8rg3a(L_Z@nu@g4c( z1|a)C2VqeC|MB(a(O9+Z|GzYA)~s2YG;5M;@BNlaDNWKmp-FO4nl&LqG$BcnkTQfy zGF;OZLX=7+QIgW2Nt!kNj=lGNf1c;_Tc7o{*0b(Eo_pP|b)46^&*37X;;t5&1Q^($BDYOx|FWyU5EbE9gLh?(?m1?)asQHNN6DEye_hd{WI7YLldN1mR z!erV^!S>D^k^VPV^5gxMeYjiSCg4% z3!V9M{$(m}{ckFVL;J~cZ#}KdF5;jK>Aw-48^(YWr2N^2wnbJDKF>$P zSBmO9b({7f{nW7yfcR@F@w}|;5VL}Nr`Fp*h z@taXh-_=fhTt*LeL~0AQMO%)2K5{J#KJ7p{I|rj5Y{9+URp{Pt1@stCY)CW1woD^U zjV*(rYhQ6UsB$&qn=iL~?LfS{vlkBUI*6Frjm2o93FFhdM&a0PIAcH6iT~ThO|9K4 zO4)MxAa*mm8qdG%#8it}Fj&702WPKAPS7&g*?VEcfeF}ep055)ueidKh1aO=h=`fT zoohK96Zth*>)ltxe339ogn72VwX$mQP^SGbCtmTlzdGX6-3+(9a;A~RN{sg2jZ*6w zXtZ>P=uKoDu>_%Z-ePrkz+a_GvtvAV4{w2QEt|uA^4kE1&InN6<9b{b10}kEZjl^XtD);}jk9+sS z75n?n!LN5^tgu2iYbr)_gD?udv2u5}(ae}}PP|Lrb#`>izD&`;Y?aWCt=Q|1+S5}} zPxqD20gmDUDzLX7+HPg=`*C}2h4&DeRYPFV*xIXwh+epnreNuZ<#RhZIdEVWM386{nf;%mN1|{?Vy^ zvRAuPnfQt}>Jjaiz^rs1Ml_~<|KL81ezyVEn`XhJ%^~`y36^d=#EtFQ7CSDyAAy@UmhK{^;{0*!a^Mhq z$N)@rFT7Om#;LCU96N6!*X7<#^gY`dj~myC7%v?$n(l<*SF}}R>RU6v-#GD|E!XMvNhHIu-di{1J6^5ynU$XO5)z4GnU#s=5j_mV&^#v?#z7; zmMzZ2=H^Y%;_e3#bEJic=}(viaaxM=KNm39UelT;Gcy^^RWPe2k6=>PFM|WM&5x*_ ziO|VMk+q%*U1YQI^>7#>_D+Oz(*s<8qiNiW^FH`-E{0oVvz#mbbrXHQcH=y}I*S;? zRw8DE@Y}3yt2q2<88iBk6K`48nayl4mAx2OEQ&HjZSzOS**P%0O`fYcKBygT1wk$0 z#*|4|xWB#TTy%hDTHr>cjpw+z)AYIa3yYw#O48Wg*sl>*frBkYjEOL4>kY@34qDCZ zz2?L(G<0C>3OcfEy~CU(0Y-t_5gykKsoT?Z^w5b5b;u2-EgdZAM?liCIYBP5mHV-Kmi$yY1vi_PYZ$ zE7$vo_nVU8A*iB$ZsAf`^O#i0jmIN9tRL^Yc^N-qp$C=8MRRY1Jh-*@^ResbM!u<@ ziHPx&Ff$3`#K$Na9NfyB4Rzw*uKK2VlC_0(^YfJnT@jxRcZksx{5~#Xgg)u7RR=_o zQ3U6 zxIvTD`~|zFb0uR+pP7*8>T+=o=7$86T)}>Hzdj49?5$|ohMbvYP57HWX1tMA0&X=J z1fvN>+&uO!xM>sl6s=$4Z?jdx*b(OGk2GbZ{4is+--)lfJ5`f%v?q6KbYFH-YA15= zlffo&mZ&(^B!upqe=Nn+(DwRT?ta_}&Dwe$J~$*FKlI!YrZ*NS{Qy^;M*Ot78%4}c z3FAnZ>&=_0R<4U=E<4iFc_>KJdFnncz}kito0dlP5zhkkO^?A(%M1Cd0B{{sdjNcKjzUCAGB}P2GLc=ZM>fSF@&Jd+7j7y{X_@?>@u6&-GF}kFP-Q&>(cZ zW(9@k8$5UMQn$DLA$~VsC5#(kq8_eN$=4J!OJ@;AaZU5w!t>oEsgtNBW}se6 z7(c>T75b}6V?HqPgz>A6)|@@ga}A<`RZCknM2GE^5u}^6py00^>mf!Xhy&M7Dd8%a zU!3B747d714KzLDu`6&9{I-(ZcJtF*n*ePQGpMaN(}D;yJny_}$mV8jKIH`l_DIs~ zF8a=mZL&n&$gd-UiaNqtXBnz&Lok*$Z0kvusQfVom2ZD?BT4shJa>lkJ5YfpCr_ek ztU2lv@8k2(Q10%ZKBmIw*{Y3*2`7x(i7eHcKYFZjuoFM1`$mnOTLUa?M(RZS2VwK` zeu#dt3c;U3#b`|1%z|;+L_C_*1#^Eom=@TyGtInI4#x{|P_$VJW!+a&B$;?-!~E8Ngot{GO@NTX1CAUbp#;zzil zxI7l&x`zu#fgX!7T=!wvWuuvCh2ZtRCuT z--|SxP8g{LN6dmq8hbg3(!L{6&9z~Oey~Fa zi^QB&A=q+Ds#V`24O$st+=3p-x?ay`0?nNHr5!UgzEgi_Qno%;=~SPDuEtM%!V_va zTwX+oDvFvQQXL_EfuqmExU0sdV1f=|Ro`7m@~YxC^r1XxJF>3wk?IAGOPJ?`v7PH< z;;)~;+*|L=*W4M(zxaJi?X~0RxSC=*J1>xadN-b8`ZPh)vl1iY8~a1T0J zlKk{yaxitq{9Z}i0=W_L7IsI2#1`UWQzi}Cd&2B0k5(Eii)9AUQv_>o$QSvaQTP87 z!3uo@f)BfuZM=bqmj6c8gi~WN;LDr{+VI7mA!?UR=1U8`^&C z1j^=%7mtb3=lPv5OOB3I>5aR@Z2a!T7iG88*k?E5Ouf=sy~`J=dN>67W`W{MVW?iB zC=M)?j0k!*E$OFk@YMrvyAOuN=mSVDf6aY(G6-Wvjm5Y_mSQxEq{T-25GlZ1>7hE~ zki`5dqun#EJJ;xso2uGFk1cDQ0=+P*b{HE(YP}hFu{}xDOc6>(gx;w5^*^~!yLOV9 zeLtAKpgfvGJFH>NFtpbUI7PM-F_$DvOTw&we_gpg{S0GHH-hKX;wBpq;p;bs~&$c}wL{tJ4e&ocN7HZ*Y-Yk7ypxYsKkk(y84yLM(~T@+4iGI~Os( z&2cJFih;w8IQW=XGy1ipI_}mOM{avz_emM9rCOsfEFHhn^~CRHf`sW!m}ZH?Oqe#l zOlhi|Z|kv8J@t5o+OOLy)+{{($(^F$M~!_#H&ImKB~c|l_Y)ZhP-*XvA+DUu84lUw z>bZRto)|(mht@@tU^fg1PfuA1!Y23-6b zsu-Sj2Jt^7jQ+~YV%3m?7umY4JdZ_+-`ulF{scb6_etAc5G_)>vQ8P`S3 z9bIwIMiVA(vA=TA(3MQXmU4c6GhIIAN~Su*@;57#_F7Gfrpt$fvHF??0o49-`^$pnCb|F z<|bIPS%s(B=fr42q(PfXnBS&NRpaKEGu>Pq`3JfWRh!G#$~v`Ei;Bu+Vdq4Q;S>$N zc1;t@;GC-BvF2w28lN$S6V(zHUhqV8Jhhz8*@n}jW+MA-1}65sDPqP-7%Rf$&#O=x zjxlDgPH^Or?a6I8T&vEn@nQw>EWxBMuzv`)p5-yDL%P_v7Py`2JBB8r+vI_;r%u)$ zC!J|?PQ$(M1JKxepk&G|+*l($eFsb5%~HZF9OR~KIb|fnb$8^IrI)y(vSjsG3njC- zCAr6G;;HlT1hk#067oD%dt07H&5i`@S&@h{GmE(yq3$@tOoIN!SSt7NMQ;mlOg#Ar zkB4^?C$zm3%^JdJE~*vJPU$no-5mMPcB9$9C8yPyUwSb@Bjz;s1hG$g%}CN2pe{Ub z^9ZrXBK%7trr-F^WhD7xq{C9&*Cqqumb|0N*d-XhWT`5 zR_HnM2J7Fe)7V(`eA`r2fmWu}B-`<%SUwt@t42vQ31b9bfL~@38ry#5X5Mqhr7cSk zawQJ@+(l@TvlugW@u=jb9(HRf8dt)Yedwp$=+lZhJI;|mHMp_n&fI7fuQgv?6PyV% zTohHU=Bsl>@6~BEfm!pNlPiQMH4&942yN9<9x>p2tAx4PJstf zG@gW6FvVRdAJ~l9W#h=Va{sJ8Frr5Frp87s^b}^TreeN?Fj245byk)r2&k7%TI)S8 zA}OF9Ouu_!85SYb=nMuv9EOw~=D37&z{EHaQzJ!lm@siK!l7yT&04F6zJ?aCAKT*w;=`6&}iuHl~m%js(Pc(^n>ViZwW@XIEj%Ai_^V# z;DSEQLI-Kk_DG*+2w@skxhYo}HDs3Zj{Lgwjk$tZL#XX1Tpc)u^irsyOh1wo;BMRy z+p&dWSfSKP(7bOmxEU({Zo}5EQ}9X851n%+ko<=a;@y&AS>>5G`}QZxyK`QEj+VvwpSqi84R^E&CWn+)19)-Qe4 zemUeJNv(^1DNfOk$j5^)$*UA1M&6e2Nt9cZ(kvi5Q`8P0&wESI)$rGza|l zT!K!v#;}fUhKQ;#G}%pKU`OR;`|oHU{vuwwE5jt z#5|BNuLyJHZ?U4|hPjOKTq;XwF^i4-RLK6U>BnlDWI|Ab(_ayVvDszxk*k&Zn@%!-cUZ&OE@bxlSqe!pGCq>PgD z-)v&psWTt2UE3M6g6^PT?r0c5N^pJ16PLY1-T5Sf?wliHF5X&zI~3!?<~G5i_f^i1|eroAeVIZf0AU5gq0HJ>z1=T)&KcIdB;(H2!Pz5~fQ3 zF#;p+K${FtbsVn2s?#Ohp6G=2T}*H|dJ*}rRdb`R-{o{xWKmbkP8=wgj_QLYOq0Xf zTBoCoGe&XLOYqu}x7S=!*{)Nw1y09Uqe*J99b1Uz&y)&!i!K&70>Sn`_-+jB+%YeA z5;(aXMm~AYy;a@gVp`{u7`+o}?+g&587X1f5@sRWLtzr>$86U)@+%HcSH~vYWS_m> zA)W<{zDv<8ws?Yqlf{UCM90H=Qd6SEX7Y7E3{qI2OO7M8_`c(u_a|_pBJ&Zxzy?2h zNF^ixVDt!clg(Fb#8Kw^F-Jb)T(-LY%wx9y<-@Fln?j66m}yZjo=9F1R17O9_zONB zdtV+0J7Olf<#{7+ZvppKc*=WT0HY7Hut%qd7>%zKjR9do-}O`mH4S5`*EsU`TO3g{ z=c?GOUjeM4b%uy3yGpA-OeL!R7K?^XLIblNm6jUM35UUrIe6jah1^~F+{gUmT>Ipk z7@%#5!`%!-%&@Kph3C~_gxUF%QO2a7Wd@l#@_w!()a&h^vl}XHSiyT$hg#(YOac2; z#0bi;6}_*cbqzWFHl+cqwm{&R{pePk#kr0>$~h0Zk6ultV8XS2BF0O?7!&5_yD7@- znk41{9Xa+T>C2v;s9~3tII+n?(?pCQ4qS8hDHPv}#p7U|=XI2k5>Mna^2VD#3HNG! z(4fsF&Ql)1jrds#{~uGZDu>#!=0nw^Bvai|ib5z4NG#($yHYsibUnCmwIKTdn2wP^@vG25SOy!Q$A7Fggmy&MXd zk}l$)SrR6|bcFKO5S|(Jc0E6+Mn`oayMSGKG?X!1bw!M(ipqGW-Ip-J8CnpX6OJ6t zKjU$_wHe0kP2+sVZ{kccBTWI$@T91pCWta@xR!*4X6Be2k)xRw)QO+f;g@FW zZl$_QHJP8B=`UhrdSWy-g!$IjLpkSuJ~Q{ndj82S9nFq2wko?aU$H~7?jW@)l1y8P z^HbDllgvK3URTU zYh$wV+3#!2Nkd0|gzSO(=d&y7W3P{?h01%ONmjUf3Q86xEAwI1>nL0gk&sqEB9huu z3&R6iq2FBKJ${t(?Co2;?Xn>LX}uk?pGXRqwGw7CVfM9BD4iIdxjn;?KQnZQdRh5f zbt{XeY7+}mAs03RYcHB%*Tkl!@B`kW#DriPw0xctALxwsEnmTNKdN|(-H-XomeIUj zv_A~G1&D+8MZ)YM%$|rj%45aJ%-4mEyz1ox&T>Ly&Hll5jH_1?giYFdfDJrk=dtHR z7;*yFplrl7c#x|9BwD@G8aqSd8Oa;Z$md75y~<~}9OC0sNyv$jGEnK#DzKk0T5I$a z7npdaaHb=#HNb?+y0uTOb*Gyw>rA|8OyedS0e#y;c>8WAdWV~k80}TDi2SO}Jt*dS zLSDU;cdZZP-?s4OH=7vqxBYT4KyaX?zqe8}frM$bsKBJpix}p@0!QBJ%|h-yUAL0H^n}-DCjoqgRhC0EfVG&VS3GJ zYOny$dmHS@yo)avPbp4N`VscB< zp=UBtX8DWDtcc<4N2GCI%HMKdweI8f(;Fh@cBg~F(s_|EebU=2F3B>O;wVRc$Lcus z--Oky)1vn(?aL>{0{_{AGr5cY`tYCso*S54&y}@I6KxL|j}E5(E3acv{vU4R%ClU< z&#BxtI--{@Eywtuk3~#(X$mL^QyFWb=-XVyoIOuYvbIU8R@){p%M0GA^cRI7)Fuua z!XJr(85=%Qff0GE)V)eUAQk<$JKDi?;=>#?Dr zl4(gj4BwF*Of7vf5o~qLRPVc)sd=O2raf*PFm-?P5&K_!6ET(2;kJk{{^g8G#`6s3 zL9Qcz^}uP)YHOWp{&jto&Q^L)BkM4m{)3TXump?_OOIWP#6E&)bW0m+*U9wCF|t9p z+1>Q=(Q_!OljG{;S4b=QfgKYYn+g+pj&xKnCCqC5nX)DAHB7GvN4_bk?%jw~sa>5P zGJX{Sh`)ChhWYN$EcQG1M>9$ry7%r-nY|>d3)98pJe{J)8KJxev_TZyPR&enc1DwS$xhwwsR=9i;#!R+ZxxEFBqB&(^c=XjBF7dCBK8J4GYqG>>PDx3~uY~dOT&{FH9?djA;mE%$*_hF*=Rn?a zWdvh%GYCdK5@4twiog++i5eY1GKW#vgcylchd&j6m%wY+mLzr9X$H$*d zInAu7a^&AUDBzf9w^bXW)@ua8jKCWyP;?`Yq9E!jlAk2o%JZ;Vq=6CTane&$v9@qI zCT5<6$-t=y=Fg$r{VviM9m2!KjEHfUFdYbUsc5z0ka0BAudAFNG|o%5yii9yET#vm zqaO`HFhj6-oln|Af-c9_zk--%mZ;I?xQ`432X}|V6klvk_{&{7&Ny+Bjhb^A2tc!->DYF5o{KYd+2tnp+`AnA0vj8?;gzd+9s>F{$ti*sp$ zVggx*Esuh_k0CalD&QL2cEHIwEW);1;HKUQ*wmfJ-M*5(K!Fs^K*9vb++<}NVwu16 zEPDT%9=F~3AXS+Js1>zIq7GD+@fA^GqGUcb#@J`Tr8}wik|@KC4--(Hkiqqjyu=+1 z3gl|^eQ?E;`U;!-z^Beoj7Cd}#)vRpCh@YDwilQIzvR5vm&@vHswo=&$9c7oht{7= znTTFH*>ILAZ? zZ_NRkp) zv30K09;g2^7j>8JqkhX}Jn`-WkF1{9c)k@(Z?X8ev>UA4ED*QD27?DgiO~c~EA(Q* zJlS+;{NsTqnE{=g`Td=?vb*LQYCfMzR10@cL9%rk`9lg~je^IDw>lp)FPFe9Dg|SL zhGCsMhanfolj8DTtczbtN(x&rGcXjX_oci*vV>Vhn9N=I1yrs~kOS(N9b*7uqmQQ>l$ zy$WA16(I1*1B9Nrf+KhOp#ismCbbN0&K$!yxeq>{@&Hqrj>VlhaYC!>jGx;CMzft9!QYMtbmGO)X;Y=gj4AQcobbhqmg~# z{&yCBvSZQm`cYUP_QKn3p5RI{@aUw4i1CmH%|jTpClh4Dmu+Bn1yaXK-%o5Q|5UB* zep)4%JL#2$cnj1|C2C7U2WlV_!xZ7$1YwNRl=kYruyI|#mBY-m}bqK>1x(N6`q%;F074U&8n|K z_m6}TlwlQ?S?Fne3$2@!p{79^*o`x=d4xAAC)&VME1T{;2N8T@J?4+g!(D^%B1R+4 zG!0>CVmDb;-CfF-+++ro~CshGmXkoJcQ(o3};}6(H?BuKOYI*RZ!LYBavT+ z4gNf=KaLeK-V&ymFb}a%QMCWJ%-hO|j~HI7?$TnH+G@jX)}vjXXdNbeo`Tbopqa9K z)or-sm!oWX8r}}0SHVTwVfJY;49+MpS^oe^s5HC%A+p^$Ya(K1NWaY^!fdQ?RQzu7 zLiSR}iQiDuTGg~HO+EK_G3z&xL}#r^#b|VjXd*MYgt(2Ygorj(TL~8I|L`G}d);9zxB_5ZL`13T((`?- z$V!}XgblkEllfGVLUMMK7f z^}ZbzqbX=zE@BS%zYVLrd=X=3{e*7Q>9DkQz?XhyjjjX;RzaQ8|K z8rzvAgYg=p09jdjtE=HqxE@3J{NLah~3et$8PKghR*zdj%;R-9{ zybeXWMoOl1lrUWg(`2)u(l9GuHnEMIe-ikaoxHUT6WgX*=K6$mZPz{)ch63Hi;?PE zAWmpOph<}40@?UgX=dJgZmP@}W2BfL+AVeunrrnyTPeZrWm>a09_t5}xX zmL7{AMlze5mNOSG7Al3$)8+SLSk;nl=ghm}i-+)enk7|QxlN zg5A(N))~|8kn3MdDRbLJ!VDqIq@x{_wzU9TQ7jF*M#EH&;lXXNok_#u6s$ zmbP--?6qVfdktR%ddT=boc3D-B2Q zd*joJDd_ms9-V!HaWG~l0>v*^n|{XY`i~5%CPi)le*<5ijAwqRbYqwAQWRc6drfP_LjkDUg3@z zUwx6d#0v{eq)qyvgqcQ|BF8*M>Z#^TS4TM?+@S%pZ-_7J&5;kprHko?XO1ulG8=i8CEzR1iE~cMeZ&@XD>5a{N+ymIXzJXy0g&21I1)@HsVoP8U zT)GW`Z~aOn~$|KaEYu zw^0|{W|Kd0CA8^PDzpjh|Ltyy=d{HEFCpwVXL_E1m*)`FeUam@{yyCI*p82Jr?F~@ zGj{3C6EUR{#-1=!FON_>PBLPqR?2y;Z@XpbwKv#F6`RBdNs~{NsH0bm@VrvE&bUdQ zQlva;^Ge*L$J3LlT}ofveqn{7p;-{*bOnrXhAtcUT0C-0r;B;-Rr+Wj;*7n98}W84 z?LA#74Zg|-XRM^#+D{3yi!gt?Ell4s)SAie<-{)QqunC zRp<^agU8;RFeIsoCLdoTYE>%a`{?T1q8(1}+JdyD&bT&s9P z=<+6vRujFnWwX{W-N%zAWL>z7+xC$?WcyGhys!%xorYvbMUP$rrtWGkj52EAN;OeB z>*%5$-VR#*T+y<}3LLT90d7hfrVlfR+okm)=ChQ6@+ZuZr>Wz=9NEs~nLF|3fmWx~#q?&L&#XxkJKYaQ_T#ZnZ$rwifCERtoJ zfX*$XcI>y(poJ1Vy+W^F8ng{Yfly1C3cZYsD2PI1;rgXat!y zm+Cj-;nv*wGHwrTjoYnVF}>OvWj|3fy=w6s0*iuNiPXwH!cUkJKu^J@4r`&?a&a*?VXY1Z-qs@ zozOfYAH$Duh|-s;?Mfs}5@8-{Hk$Yj4q;wWm8vD%iK$Hd$=1e&%Y>2<0V71C==NBQ zMo@!GdLm(_=Bx3HBy)bL84b@E5@-_eH-Z^E z&57@l+*N7c>=9e$;K>Mg&(O~jrtH#V7<$|!f0ZoJ6jitp%#OPXdz&UW-f;(JU!8`x zajtliaUWyrMq%bx3DZl$WD(|A@nLe-jbnUirn#N4W6tU3v++mXGlCbMN3SX|n!1h^ z(o8eU!uuBQ#X)OHHV2o#yyn&>I-|`;78MKVm>zHo?c;`^i187l;Uvrr!pzk=XR;~d z62lL4;$`LT%*=MV?4OPrMthIye=vfrn=l2+Dz3tCn}m6$M?PO?A8|WBA-s z8)q`TzRUT`!;h=%5|h|ItJ|_=m#Nh1AB^_QC*oq0)afb~(>sT7zlo2cjiS#}?$YZ` zh}h4;x9dh6UULgtMO|SLAz{L#@1}+@eO~yO?D=$!`TLYs=(*!0gVfprZIM z#wAh0L_N=h)0q$A(wXOwgJQG0T<^M_Ffd}#U&{%5w2QERz8)IHxrxzeORK!m@9l`zc$sNiyb z6O-ifV&-zNoZoI0s{DPsH@kjI57srAd~jz;Qy_5Se=rV4wc`DzZeobJ~GpLb`syD|BdEf z%;G7T2plhA*ef?Nwz!rHDsjUykHr|)e-jSV^HANRPS9`YDGr*Igy~KgH-Go^?6nUV zr*(4P%;=UXo(pFx8oy+Or|lLy)*h{mNM_>$@wVDQ>r!LQL+@ajAM+0nAu|nDZZpUWG+vZ^HbZ8S7#17 zCTkm>`2WNdDASPQdmY-N-*5x`cH+n&TZ|7|k7^?gF64JbhQdk2WJ?$m!o(%JD+0bh zWaf{T^INT(t8G+wO*A7y|DPD))XCE1ePREGn|yo+8p>8fYpWc)+*EMf*OhcTmrVF= z{#~K}#R%Vx%eq>`e@nxp>O8oO`OPg|w3S|?jU;f~jhtUyVxRWT_IO`S&dF z?@su!bgvnQSRo*#L z#4MOC=W{|fsh+m$qW)W&rxI3ye=$OxjquwD7-8uYFkR2_=#bSK1OBeYy$^mk#%%|) z=nSshBBhwAOGJ#Rgz+Pc!}LDNeX|Q0ZiSpL>eENj+ul?ibv0GQSS_Ga=LtauOo~R> zJ%x=xz*Kft;!9aeJbbYjI$QiOb;@>d>M*Q(V~F-QsZE>y^dw9WVa&$&R9<V#7k2koG=lGx+pt-&t_h^%lY;9YMA7e=IX6~vs6Oawd-;TBOE#Y#R!|U zunO#ab{S}H7dkz2#3J_qoax;Q^;%L&wV@PEEMaoZ+bCnmQ6lAtoKK$- z&AhX+RO`;YBw~bUl1E*|F!u`aw-KT-Z1O=|q1Wy`kHjyHFxzV)0up_oc((!j=J+GX zsW+N+uo4HYsT57JfLW@oT$!t6UW8Lo-xw{%EqJ6leMY#55$-ny&8~_SUH?WSoNR>K zTH2-vL^iJE`p+DKZaus(wcBcJ>qX796S^a{vlNYygi#Tu&9~PI-vwz*Y`mQRdqBk~ zzRy!8m((uk=C$ zH8idNCl7r>dSTBcOsgLc6xR94OxF}zIyi1wjDPI>`Sc-!-U&7obOgWRGXq=wNj8n;Z zgD=4>{a@5svEf({6~XK+%?Wn07A(mGUrrQ&n@0EyiOj^?2;4 z+Kq?0UN|vvFpk+tSKONtri?K0!-5qqt74fGS1AK!ev>U49;~ih7O50I&uPJxlzY~Q z7Y`x*AS|7!?cSkh%M|?T7Y2u_mt6BoW2~EV1X1R$XlA+}c_T+)@~frNcOw-iJts^C zcR*3l_zV+A=d|t3S~6aZz15%Pca+m=$gi040>uyM$WGTNqdsIG+By?aiEr_u-DMI5 z3`3)|O0Lr<7R%Zm#=d5|aYOe28eAHQF>9rbV6Ifl@t!azCfO?n8iX@3gsCn&!}ut7 zsB6o8WmZe5W@B(ALZ7Ip8l@Zsd?9qU^YG~W77B}Gn4UdK%45mg&YwLob(1%q_LU>( zx;r{w?F&V%G@;!j%y+`XHCw27Gb@yd%8~PK>(Uvclm==y>&GU#wdttOrA4MQ=|Yn! zfX<>qR9w)&;qn`?;IbQY0%zUtaLufSL3@=KmgsNAk$xWNR?!{VYos-;qcmvRfh0QT z#3_Q#9%q_o$$8T#YuRztWtE%qs!XW16H-HFvy`w3DHHQ)CGXXk*5i#>qFCLSp2j<7 za#wT=V6Wwk=;)nj|K1H%+q&V^GD#LRQiGU@^!KTOpsT)5c>?3dWpd>`hNGlpA8bRs&?CVc%Xjv| zML#=n3S5#t&rXEl?H^_IXcNSopzp>aI+(54a8T8|*J4Hyo{Fp+6-cIIgkZw$ca@&+ zmaCxKw+033Bs`7}1=%-ox5xH{U6C7g=y|~4l^6al?uMPCrDV!-X-(@*m?z;AG6ozu z%GlCT-SVS~onxG)N}1@&2*xz=_H;`-K(-V=O5rg0I;?_~sMoxPq9Bnf@Io-sD}y^c zYY;~7*oR%uys-DOH*PfP2X2?NNxMlHL&E%BbtY~0qN9v{H2pU01SY)+EpRhAMi4o* zD}0P;^k^*9r5uJ943tlh+t`|MAYu5oJEepUA&H!tuT~656Y$Xgwn7ye9|g(A7liiXP)KF&TRDM^prJ zMa&Ks{HAB4b7|O9`x43P;*nW$9?=u-b9u9Ycb)w(vbP`J4+@20B6X|mb`>$tC5#ne zaJ%dHZL5Qr$KG;Y&+Vxy-cyGeF?0blZRaKE$Q~hZLkcW3uEQo?9G>22Jk^)V)GubkhZ>!a$P zqhQZqmGc*KpQ<#v>CEaDSHRk#&VFtS_%4cdUKr@id3aT_UXlbEGM-fiQn}ug*x= zeVl2!iJpmiKT#>#-DC``hBHDfheuf%>dcZ+UwU7B^a}M#f!WZPsCgQLAD^R16Z$we zZfs8!COM*}vojj5@x`^vnVi!{>ATq^MdM1CCs&VW6s3ePQ#R1jc}$O4(aE0)nfy#9 zs9h(=(^^KA4m!K;i#~;d`H5N13;dZHgPv4Lv?F>CH+X>oQg+&)sbUlMbv^)Pi&V}b zRoV!GC5$IwBJRa!6!ts8td-08SN0v44R0ElY&dSon2-r~V23i&@4hG{?UPQ)HuFz-8}QB-6KZYM3|I$$c~; z#>g@6_C^%A1)$Bno803m(#0cEx~+u}X8X4>idAb*GB$)+I(DO~zD6S($X3b(-zckB zr7+YaL3r_q>YPm$Zx`{ks2bDKqS5E^WlT>!zzx}C24Av8nA?)_G=Bn-Uwnz1@NkDXp$#QW0%10Fj8bT3hch*+&!NIH4_tQN zjf)AvnA;rTF6;oAtt&W4Wa_7_yMAH*}wUJPdH7*ZUc{eaHV z31a_EpyyS3aZiHg-g8uajzS)-3g_=9a^K^u(EY9_zD;sP=l&;Yy^G`4{F0I><`O28 zFe>J~;)3TH=JH}WUlEk8iW;k7{I7IoiqFMB@wNnl&5q8DVmQ60o{!UsB1R~+YJWHn z7Va6G%*P6CsN+lT&mJtCABKkUN^Tn|$_gv=A_-GKm{oUwDZcGF%Y2$6=Z#xwrB_W4 zW=duqV}zR9sQo3hm7Rxnw_@0-GI6eXqUcHzUmuCH&9CF~(hJ<~Hw$3+$^%^=?uD=a zDX2H8xD~!q2CB1!xks26*;>jD&0?55%5sz%c2kXTEoVZTL@}WW=iuU9A{y2T7{SWr z@Yw{saCwf<;z*p-Tt|aRFS zY7X=cdSaZ78`jUIK|6bq0|^2MgH|X-^NKKMuV^Vp7sfK(hs*icq9{diTx+Ik!(k@0 z$N$F6B>PxQ3}Spt7Kr-voCU#fG5S!xS#kRT?xW2~$Uyc7Y9) zYZk;YKl;jf-FvN7qX*2F-JWdAxOS2-hDGsWH2-1*#~1-qj6x(_RdC;x%hBh#AAa=p z!rYpZxTDDDru%z~(U?l9p(V?`WuQjd};53VTv@3M-Pe%t>SCi&eR(M-60 z+K@;&%S9&pL=VwP*0ky_D-P@Q8?MFJbfuGv4N_qV32yrnmt; z;Wc_8bDQ_a_+tMS;!G1(0b!Dmnk(@g{uci)(f<@hJtVROY^Nr1FKSo#@XRE2?zqjhQ)ZpV!J0cq=aF?Xr3$WBu(g3(swhAFt;wg zQS5mV&n&5TR!jX))%-f zP3I%@nirCWc)_PHr5_qy<@P?5QmVO9G{%H^;8v~Ze)l{xk1B{i#l|sCgHJG-74sEY zn`6X{Kv+7Xrc%!URSjw6q%pAig}6fR>{kG*#3W90bP_zNbE4#(FZ|yhhiQzOd%RM@ z{8JBYMwokD3l%T#Coo=wSr^DNk3uIgHjz<^`mz|&X({S+0%;E26Zaco=@cG|1?#X8 z!MS*^f0}!?6|ijKfkUr6F=%QCv=3>x&HW@yjZ{8rNtpEp$%?cl*2vRG}n! zxY7qUze6yyV?NimQd*%$OVKzGrq8Wa3WJl0OgC*g@40H8^0R-4(qQLjrCG~3@nj=l zIwjo~EndH_l`x(5MC13fY^0K?jK`IUX!vYDUIzJLB1biyRe9Wl{?gmpI|;LyFjuG9 zDDH+PFxIpR>^c=~a!_+fRXS~`O0RJoJgOejYoQd4VkZ?_*d&Q(Xd#-%V{@?Z)ln`Y zlEuO*Uu?-gfa!xnv3l`s?oM|JlOtjF2!ocoK=JnKdFE$JIe)O#Y?GMhN>#JVwMya0 zAz%cjCE;)@mpi_;dT0|{|h4wns6f!qOrNAMo~}z=dykr&Q*KE@5+8`>wgTx z)?VivI!IF>NQx#<_-(GOQ4}Sc*dFo29P1$Tx|YWU?Ue?tl@!f6!sxDB zuIT9&%k=F<(Tp`$&bgqqFiX2YFuEH4Tvr^8wvfWHF!z3(LUJ`9=EKWkXll?D z^QSb5W>GL|d^VY^a01`R6@yBmC!~jyE-;J8+ye0hJlCEnO`9q0I>FfMALIIGpF*Nu z#Gu={^Jn@TFdRHZ`U|7&%`kP5=RvMCdLo$fF&934Pr|$&X$^XXbmWQhgExKwklDEi z57@)Drw&tE1;G?NKgqeRJcR~zC$Yf850a&)r;1ABJE7^A88mgBNw@#5G>X~hb`f&@ zlJMfSBG?h(2Np`+u;@hqd@#F)wO%t1{ewMMs3Vw->*KjP(JAz$1BnHkO!$_SIegC6 z4M^^6D26JHp4OU5(~G<r_UdtxorRJ7%56J;VK{S!p;f9)F+!~XE8aw4dt(vAWq89OZFex7?F-&X z0)9m@xHPyu%B1-~FsGj8ay^Tqkn?vNp{uKsWLUvc(WAW3e_$G0FbvIdP^FCs&w-SK z5qO5J9(0-H3w{0~mgeFECeJhQHqt|yVp=m3PzY31s3oOp-mYmriX13$T4@KNrnC7Abc!tG^o$_ zgCiCm&??6ZQk@gAmLJ26VAALk%n%Z)7yXDrA?Iv_D7$TFxoNEERUfeo6TgEbhDiV= z$50cHW0uukh64{1v1teL#MdnVZgcK%_sL-he#zm*Z;3gO-!o3@x~%G4#~K0z@s*z-39(p}SK6G+$2k=ZzPsS>F#T3SKZ#It;YKS!GH;rnET(6MS(!H|(1iNpIT- z#>3BvH;!(QzWaQcr_QFateV{6B*-xF6-*lcHuW-0bMth#_pl=#ZEFJN^}f(n+nGe3 zZZITqAZUHsB~#i-Ce31kS+r{tr&Q{KP7!JLZQUq+o~I^Wx$F~1zc#YwIb~^yb*B7o@w}stpcE~WHOq#U>rZ*~xjd4>}2_0C8RqU~wSzx9j(HQzpn+A~w6g)o;Es(@+qzQH)p(7#&86-V>Y=GLJC7%j zJX*Od-K||p=6sQpbdRA?FtzJN$cl8u27sWU+8uV1`e^%C0Win@J+76oJA&gZFK~ol zN;(MKO`|{*^4vyP6gdRV2_`OJRhdj0xzgkqdRn6=X(~-+$OZV+%LNx_=|RL-S90g( z0okfYNo#}mc*ZJ*>CG@<1as+_J13oc1nIoB5qj*g5Eqm+NGxhnW#=0?hE@>MOKr59BiO+wPFIz6zDA8->AO4noOrN+>I>H+9yxfjmnguwdX3VfjtyC&Mp z)~1GF6#QOu77xOZO{I+xePAKdvv?@#eEqmAb1PTc-ccl}5_w6M8lqVaD$T3jMG!yO z92*nN#wX4&N_#JS?Q#reuc^XW`b-*IrnH9y6LaSwcVS&5vbbg=WOjLt+CK_M_0OKj zF!a)kntV@)R;7uCvD8kT1NXBAz>`7SVC<6r*}90aC1fW9W?sl_t&nCTwvq#_LOrq4%Br zaLURF?&}4U|6IrGwzJRLPuJN;wHi`6DKLBl}J3zSR2{>{!8y_-d=bM%6v!--dQK2}Y1uuOUgN}rf z?mX{%X1D38DE_eDPnL(K;o$VO37}h21}~H@1I5TLy~vG+@#B|pPWKu{s&ioYmJ_hq zVjYxS_k-NO%<=NbH8Kw!%P{Q-rhIoeuYV*F>Brj$+q%06TKlrZ6)t5`nzo~NYjkZI zMdg3P%zYdMFC$(+?~L{B=1i(B?o{Tqh*w5HPZeHI0F<7?sO_Yhp0I0qtZ1E7o88n#sW!^<%N zc-2I9z1o^#`Vx#uzxQ$>xFdf}`>?<~Eag&!zLqiVg)0$$aG|^l&jL37v zZAsfKwgh0Vx6K< zVE=S4T$)ST?Qz1v+pr~6Bh z97A)R)Y<%r+5Wl|O#WJpr|%mBua3IF?CJa9l5IFdZ{qNEjwMr;GHIq0OzvSP?tZ5< z6k}^6TyEu)$YWVkQkWflrCIVAc~$e1HE$*jw)h^}}sJXK)Y1h7Pqg152%|__`U`ckcZ7X!9z6JUd!(IKm(sK2xLE(%Cwlbdq zJvRHpjAoXk&>|3~M1go_D(Yn+_mhPte z=1-;3L>DyyW%W8Zn|l}!vz-O^xBzH*eI2a49{}HyU2uKTDw#Be3}ZnspI@BdlY-8n zS2iRZv`l;_RCR<({B^#t5or8ZRD6bwL4IAZ5K9PKMQ=wlhUm#tsyb$Fm%-k z$EM3!X|FlM*b~gSZyx-O-sxxs!Dz<1h`DaBkwQ^!rsvMzn5HHm#{_h*1h1vb@a1{q zVRJWc$R4l_rnL-(<>^Uy%LnGuzA?;hg2~TAe1>oisjapVg5xyAr5~G#6*en!|AsN_ zk|4_tQl**Nl!NOD6Wp5D1FPxb= z0oMoOb-wpSb2fYwQH@8`+>if-d2qiJDxF1m+*CbyGT05u&+mii_K~pV z8;`f`W0)$2IY=<~$0u<2?wvymmf8p>6Stu-yEsGrBo97icQi!URRi6g^y^9YO;gOK zpmJC#nSlc;#zEU>E`Xx;fy#<-u)Cgy(?+wi=VOKmA((IJ*Ew62bTn@TIeQ)-D^1=~ zBq^Gs$v0KnzhOjIt017wI_ywv3U%!JWD?9w6A`byEJL<$u3P(~U1y?^W87|;(x?gi z*V=5)ssg*ttMIb}2>RUhfWKTEpttf#$l4l(8-HG`v|*S$g1L9F7jND?6U`+Jn#SRM z;xS8J@HthkhEy7A0(HaxU1{44%VF>kz~9g5L9@r?(yM`(fL%D8X_8wyk`34> zB$x%Ai@AklP{0VXJqwjn#On(?Nj!Tg|3hgs9F!}Ky3Y1pZo#5ALvcyk7?>XG3ITb} zpwTlNTvB7JR$t4D{Dl8^La16mm3LZ&w!8!$fEZgij)Q?4Js`!y5n8F7Bt2D< zadH|n=(S9mjs&Cfqm*;mm5FW-3R2qLQ&hi76>+Km+tSW{y#=d-_3;xl988lv zV8+7(aJn)Sjzpcsn(55a!q}J{4T7<8KhJeIn2EYsk&en+Mx!mthefq|ZGK@Q{$ksc zo}}gbhDy^srVMPakHm-jj)75!J>bV-XV^~qL`IEC!FO6P%xQ)hNHE@iUF0_Y$UrNJ z>&(&}Dsddxo-2)2l7;GYZD=eItzQAooBod3daoSz#E9`}(Kwh9=>_|EM~J<343@4+ z!1mE>ZQ3%-NP>arXB^DWK&H#d4SQi{>6x4j+{8=0WEkqxD296IKc(5=UkS%mr{l&< zeXyJ14PL?fz;3}Y*grl3tNJs8Zq6`<1hcVC3qDFQ12rtL5fZ7?_>vy^;c4M`e-y(MGR#DR(JgArrwqwJmuK1tuk!8r zve0Y%!Or7i~>ABRUcYfc!M`7uX?*S6zr>_uz7!G&~*%B zPB4mgZFzgQ3^du$Mp*Z}JBn;*hLF>te_*25|J|oeGpdBeHikHP}bhpC(X6 zoXyAAQ}KyQdT?wPiPQda1Vb`@x9yOVxSJnSnj6E|5KLrpXTI0$4Afx=F#)t(l9T?4 zdlb3iAJY73X};U4;p*WT`0OeJXtUl2KD65h=h8x8jM6durY*zFVVG?M(_v08zClukLpzeCex+q2l{zYY5PVDe?%xE8-^W(Wgr_(0ylJ@BS`@s_{$r@%+TeJ!I1SFHDau)gXxHTg=iA@eJchFr!tpdG$3UI0u|I>RpIqp;U80?$6clorI47DzBTF$4MeLo?6@RU1KRMwV!*c#P=4 z2-RO0`N4x`ZmCa`W8NoLLC^U!@b!WEkbTq-7P&ZqF-fN2&nL0z6^2>OFeeDc$2- zup{4*G&&20wE@R*%xi|3#H2|f81u0M`SsV+QJ4bp0%SnlT2pm?YP*pC7gM8B1J6`u zVBJCbaH5?b_&s(6rJKPJsd@}=FJYKF3?m_!_8tTHLwV`w@ONurSfr^auyY`;VF4LI{vlqUbhz+^_|{G^wI~?MHizQbFBoPV!(1Ym_51tre#Pl%!4GR; z;)ZjmX2TM`{aH1hVj8FXK70PTHU$f-$$Cx3p~uHTx2L`!U@~3KGZ=FGNI4A|xIs_S z8VplJFw1vp@wzY45fG)lFpWU@Zbu9i8aHPBf6}=65@}8v;n-p0;5_dO3s#YSHUmOH z)A2YCvSVLQdp6>=iYl$42OmJz<{-f|s%W5tY6nC`?KEZ5$dyKqxJ{*@!EHbi*`ALv zjtWuVS8X+9Cm{tz{OqF*|yCfoB-gRR(T*W9d*`Ez9rXhZPtkmE%3MN)f9 zFtv4{=oLvq!OLJ><|`JBR)=u`&d{>gL70{u2XFOVp&)FF%mgYJM)4?dHj^u}0^X7F zl+A5~)uWd~9mC#v~D~XiW@y zhe`JK7bm5!-(xAQ9h92@?U_QQX^L6VrxNylnS_0x>%gQEZ*cGL4!QlqK)0tNNDi~C z`ebGTS_E@Y$ABAVmw*NiB!|Kst+TJYG?$tVej-~NnbJs!B2C-T3rUJ`K2ryVolgO$ zUkB^gTHr?YX;6lb!n=x%aCv$VEb>x-jifOU-JT1WG};6+xQ{k3bV)$jBS`nry8hYo zjqjtNE_za$=%N^!xuqDoZzzVE09~8um+ByHrxR{dI}4^A3Iw~3+rc9!2-wE$S`It%Hh&z1>F17P>8E^hGic-pdmW}?rOGx zCr6m;e8{AkOE3yHA({OyrJytOY=nm&D#c^(tU^T=OGR=FO%T(4L)WG$X87r1DE*u% zh7Elo#%>?%s`7-uwh6FdcPD7RhGlL`7-lKKIL?1#(9S;vNeCuwVzMOf;3f2KqS-HL z4*0WvyNa+W*y1$ z=$ne3nUN}0ry6O-ZA-~W+nzFMU#B%H4aLxW8pY6y ze2RIry%s8lkH91Ei(wQA2e)WiLH9{vV7lfZPE)m$SsKr_=T3qdy;F^EVUUKF5EBTK z8cQFI&PVRAZpx&Qr-mqoChz4K`eNm-Rvq|{F~$WqMew7eH>@QCyHiOk-JLGwxcXj+2yRbZ@AC6vb z0DVl{;7#!k$S{nAtEJU=b}M!pHJ%x?FTos_sPHp4XCNmXa_|_lT5NaZB-)sG^=}yZ z3QsPL920u58jPNP6So+t3yVJ<0Nc{N(06SNtiAFAJI`PS?Z>1EBAB^76F5z^Oyt

    0QfRl_%jZ1Ij=qhV*96EwHk2U^83(0A%us?0e;{6cbsW4_ zc7@?9cEX7%r(jd3$5xuMNhFxB;S$bWl8N@euol8^Op#9VE)xZAxFu6s$Hf1} z1Sr&k_Rto1_(lY3y6&)O#a0-8Iui0{-o_W_uoFQyhDj%wD;t&gmW`Q6sm5B^QRXLY z|5z0zdMk=)c92S=tNV9p=&K0Y^WJDCDJEas2A^7G3`vhjL$eTDc)TMFLTWDJ{u=DY zqnKfG2*!EMX#QJa7P@`OT3BA`EnTjpk94Os6UWc~ccoFx;`mcg)$TEj4(*FwTTcR? z*50tj!UobuoP_sz7qGS}3pp;asqzH`)7)t)|KwU0+LdlC^ggkb&w15Jq}4Z8_Kx7s zwYg5FlgXuVz4H*fOeY=Vog$%C27D|qfa_Vv_YJ{SjsHTgq?355lm~F&b-bA9{GA%3+kao$fA?0sQ-$&zohxopyimo zm+!-!n1|w<*TvAs&kZg&ZicJZBVmvIEsRT<7l>q-Hw2T|whLeIm`AH!tcC0EJtQMr z`Wa@Xhl%KGqCeM$`ZS86;}A_r-9Y<#MJ)6;hQMGC7#C^_jwRu6pyPEMID(ao6tNS* zSAyxYZ5UsrBte5*t%a&C!=?JqgGD*byYqiqT0{%xI^~$-j~hU}Tn*Q3nh0$ddqP{w z4Pd7n4%uHX;OL*PSJfCsC5R*;RmFU-S3GJ>Fm-*LBq2G+cm;(cJe5YiHkYpdb~bX% zg_VzBuWeg=aJn&=)_TCHog1OiH5|qjU%>lbv+LDvOlj>2CVbX-{=yUq^7FA4!VK4N z?(4P4@FgpWTxtJiX`DthOw4V7DbnURt*tTm_<2B3FFUw;Ega6yx`NLeu!|LMX3#wd zCN1B9AMr(k0*Iv*>g+%huWl112H{^AY65>sLotzQ4`5TP2Jz`7MsQEn4K&;~!Gq#R z*xT(oJ{Halx+gQ}{sd#yxgT%3N{XHwCtlz{SMd&$3d09UhyRB8bKg)*a@jq2{G=5w zI)q{PL2?RE+6)!fqhRL1Qrvb4vos0A=nzcu^$vVRkQ9X_S_@eUekk$IG||YGnKF$0 z>q#;60khoFDCXSq2eAL*ZSj_m0AX)P5qaNDu%hEBnEbE^JGEw*g$$!lFmp58@fmBR zXjdk2ogpQn+SDq;;^Bv67@Fv!Yx8ePD?RvtT-iMp4;lb4EXNgg53vWe22vO^=Nit9 zVVGpLHpT>#{i7Wp>MundE?Nsknr@u?h>P3}jWaTg{6z3?O1sqWA+*X<#?Kb(Lj-ms zld(2|VSN;A?r{~LJj*b(3^S8p=9G8hONymv=uK;3jq7M$NjsF!RI`?0XvZ`XTqQRi``>MW9EC6#w&5yPt7e$j3}Z$xUY)y;POws> zRB0{5uCo)_xQ^moqxJrQp#c=d&{%+C%sfU zmgUoivVF6XU|xS}!RI7M(eherp$F-5y|Vi`!^{8$8HTGNFN?{ckV-=@R+?g-wyA}J z4yyQBv>wE4b%UbMyW#EQNZ1y93(w$KEbtR!MKBe5FS(}^rRZjzwUF>a5$V63#fMee z%kFRF7c(q!h>fw1;aW|ry#KWJ|4P*#c3Z|4DC)Zn}{PTX_5j4f@_pO7%z3;?%eq*86ZBK|EzZ=FYoq}nOuknbXOqxqS zyyz$we}eJ$yu#J(<dn zH+sStatZn6djvSV`-Ug%VM_bT*5(YsxV$>g6=!oOngmcYJ1r4iA0NceCymW$`hhBq zR(ChW(9;@~#u3#*x0cE{{GBd*Z|w<6x=v7?83{G9&v9u>rZjbi;Rxn^mkXSvG7IU) zk&vUM2_LDmMWUa_-bpvb&_q|?vt$~^Pt5$9TA1*#6*k{L7G9G+P#t2O;A?dlyd3ZZ z_gTR(GZ^LqRhn`EmpDEPZ9i!(e7YPWQK)Vs*|ys8Z_>yU#Bz+kX*A#-b+E3XCH|p1 z7KW$#z<%=;!+FdH;(aW4xq z(Nqs>Veq(3l8WWlB8#tM5iRPID@`s9&8kzSQH)LBd(f(+1NQaQgFdglz(d^$N+*WH z$Mp^PO(Qb_W%gOCBbb50Z7xnN3te)u7RE@gXPpW2FpRDJONODAMor+~FuU8{hoY=D zcv4rAyf^cP*$GZCba(_jOKHIT&sTVVu@k{Fg4s9iA-906P5KUNq0>!eiN*LrL-XVM z|F1Mh2iKECWH+qXQy-$vd&9stj>M;tp(qA**kK6UH)%|19|)$^lh52fzbv$Bv$bGV zZY~*PGei{lNb!GS=bMKJeh4BRHv@ z1cgs^xZf2f%^PNEssvMP+J>JvjzjkAt%Xzfwn+vrF%#8pza(mE0yGaz_l>MLX&14u zbI~xP|3g@!)dTN2ErxxSK47ft2p7+Wf!dh6c-+yt6R(|KqEq#abp-NVIj#Lx$3j&OwKC&D1Owg#)mGt2{q z(Ign}_g#6J}k5r3~#vc?%Hvp!F5Of zhWS&PC-u?bXY~l|0(;?*XX7Ex))%Zw_rW+xILuJLhwDi3B|Q|LW*9^;M{0WWPpL9Onqn_lHC2 zk1E{7m#xiwhM7z-mnQb%&D14m_FRIgb>Mp(s1jMs`)vXg^QY3NG>_XqflJoi@XPN; zWO}(D*yfN7;qeGK`|=T9yNzM0zsS~R4#BK=(3gK@C_$}eSqonc21@3Sju1~B@`%^Y zjFR;icys==?0d7f{YBYLAq}8joQi=tqna7LUDgkNoF58T$RBzI*+N*ULkkZ~Sq<7lo;&?cJ z<}^;%XX%HxOqz`Z6Hs8!CzjkrGep+HosY2+U27BRTyc_wHZzf9=tufbjPpkLW|{Gf{wSdd(&I?1Z1c8Da+0bk?63hY^_!zUTWnP8etZN^)y zE=7%<$oJ;O1M!$=^Q9ImBV|gX-4dwMXsAx-c*Iw-s8e-EEM$3CLUivg`0H^5-UeRa zcx*42(eVd;zu<}(UzrK0FpM|BOd0fmYdCrpb!tI;n)5|z#f^4+yR8oqeHB6Hc*rsS zTYj5>?u1x4v-UnXHSEMYXO4vp{XHOwl#HqkiGyYBva!WOcNr#)DeVZspjB5mn?+a9 zhu2oZmezqNCm>Qf(kmX-sm6kFI>XS@8oj@vA8BgP6r;BL4ph3&#i1V&B)WJ)r_dcx zc0L-sl&Ub8GB4o3Fku9KBjcxXuWg=BBiZ%82=EPN}mT^{pk*FMPBCZ1qy8~gL=wwF*J81g2woew!er4tSW*}b-|yt(T^S5B;hjvHe1a){-i+7h zE~2}IR>Je_zr=&L-!|OcMgz%POi*e5#C)F=3)A}5g4tMOtX47xCYK+8yV}msBRmcQ zv~OT8oNdo33{y-nE<=jAL17osuB%pp!B%6`*-|1gw|y#mf<-%7$T4(nnksG3nmeGp zV-_yaHH73Nq^{H45oX?rfem#&~90$)fI^u{#^k5>`HM`d?NtRi;=TO%MUtOT#m zXKV9{VO|joynVoFJ->in)>;Xbp&Am00zdSr`^H}w{<~`U-s)mvmi=dQb zpsc$&l0LW5(9*vUmmXr$wBFDkgU1<1Nn^<{HB&g^;G&^WSpb&KJh10;!Pn8dJ(t<8TaO_RF^T^$zTk82E}y}t{L@8<|TEMvgV?;4&mgkc6S zj5@)bXuQp79KV3hHMb_+d4?I*uWc<^+o&gdx~M&!8T7i5YVZxaS^d*?@(ps*E(*@M8ElEE-Z;j4Gar~PPAj8PL z0Bt=<*QP0^_Xtv-cBmI_)ENmbBxc?y*$T_c!$3Ja3s>A_k-bOC*6 zZ!OpmmwMZXs)!LA$|GrO7etZvXbs#YZaO_GN@4c8!8fA6?+Zu&t1-c?@(D z1-$g<(8UK4&)g1X)CGg)HKXV3*hLJUy7lYM!z>ynx>e7k}5b5 zYJlgf>q5+5WY=HZ4Da`xARV$(@tfJ~d$W^aj0gq^3jBnuJd~?O)+X*EkB5EaHNx8= z`heL=`upp-6Bvd@Hq@u76<2|cBgQdyBccBW7r3}@3-mWQ32(I}c*F>XNn|E4onSm$ z|KRp~%0*vVSqld~YKxBTIUuRE){Iv$N5J$5z5%q|V#tzvGMh9hON$11PFAS}(9T?jpQU zP6S$(Kry=8DxvKiODtZd1Ac-ROr5b0rY;SIp4&^X{}-mTs5i3DnmxfNwrb0l`AX3K z8Y>}f`FBItfj1;IU!=b<)Y9mKG8)+wbV!7C)pgK!RxCUdRf5)m`FQ>z9Wu34UhS^Op^R9K|gDW^>e$7fqx0)~Qw%q}x`CdmmRYB@C@T3Oe$ame z47hw8#+=&))5aWxL0)ZOY%!~T&}5i{1fvwRkoWODk3!B9%*;{QE6X?IjT4Gw($E%q zhNN#NZD!Kr#NRQODvO~Z<|MxIu{{)hqg_V4!80@rk_WxS-7;9z*^wD^2*F$*Hkvm& zm4h^RE5R=}6FrR&kvJ%HlG>NX$vXAPF>+}JCNrhYaJfm!dJf`%$33Cg%pZ;hxkKvL zBVcjjJ%03w-Qw20m90$_!6Zza@z zh{Pi0cfqP}J;$$IaA%ZU$knD|a81i#%ZVjc)L* zgdIHW*!IjMn6B-c^R{(o(69(AA?NxB07FIg<}}nJc}xgzF{w(dJo#6 zSWx0`LeDvI*yc!om|qtH%{sY2%xF>$=k)?FS7lznnql$?M*ZklZbru>wE4J|FyPU7 z)ajLr)ab(vo{oE`mPXfxN~2PBLDqVbVyMyvOu7Q~M_qB~t$r|X)p4--v>!~#IO`E} zltEBuXU{<91qumfLHic`=bLfJ{Vd-g&wrP_~^C0drBwY8z;`|=)I4A@8%MJ-yehZtDRtijTg*Geu+1Y zWFGn=!@MJyQk^&4;Ng*IQvxx8r)|(Z=|rUez=JO!@1tqoLAf*(BbP?ILoAGpxC}40 z@5Q-BJ)kTg7-lQGz@p~9puR~F`jba8RGMC&W!v*R!L*xvmm6#sfjr3eTzaTf67=H( zYUjF7LNTh6|HeEvxB{Ako$(_Vb!gZS4C>^;pF3%%JMxGEy#C5CUQC*np=95*E#>Cf zg(Ig7Dm3=sxM||3Rl{FHR#9Na5ohdR5Z9pqm8vS}U#XJ~P0A9L# zal<-wIDS6}u8`JjcZd5yzt*4e-b3t8I+tNI2uAB!Ay=&%focUS!O?gCT5V<~QPA3* zNtO0r7|pveP&+rD%qy_PxvSM7_k9qw-f{p8!~9^$76q6zhIxS?rnG?s|FIbPz5Y#sk04GlTu(sVo>11n6gzz4hy?|!5X21>!8)YlPmH4nmyphkRf zC5t*U8D=EG@M|(T?|I?qJ^9|0R?S4QF~>x&W{ne3X}J1wSr20BZ2X&F`n5eNX5*PF z5Nx{)kN8WAbW%DDN6YrZe5F7buhxj?OlJl?hhYo}Mq-}9nS2aG9f>sh2hNK=OB+O5 zroJ)^4LNA5V~U~DP-pXG0-5cxD~3!bFMz41t#FA_4_Fa=7&H_QfXU7yuyxf3Y`ue> z)_z7d6A9+T^%(ARNf`PpwGuq;Pm*X{ZzndAu0wCENtXoTq2(QwDTX#Pp<_e`hQ-4E zb)?75Yd@?!peNiK9t9ph9O2v9KtRm~LuT1T*}iGXe3}Wtl!kTWpBg2i9L`E;vE^d+ z!LG`wHVJ|it;pJ#21DN?>ZAh+`>Z)KgI-NA7Np4H%GOxaD#l89q1#!SkP#!^ z)$Fp&L(2{N-!O|bZ-HC97w&txE!349h7xjmuHG678RhDuY`mhbuD z6j~oizMdJEQOlL%vyo?i#3}#YH~)q?SAG+6>z#1Fsp_EG{x}Sq;s|Yz1j3Enc5nu- zkgZKW=F_$jjQZl|obKj0v^vU4Shmtf{8I0z)M%q7qDpHj&BnIBO@Jybx-<_uDRjUA zdc9#)Ru~z*w-dbYAB52#hr;Nep}G~rI1oDz=U_~do!m|=Ak_aW=c1nJ6Icu ztcf($PIi1BBUQ0uXC2wv6m+eS`829DdRmiX*6ogkiVlU)yW1qJ)UPKv6`X*vhjxJ3 zzyP?lK^>|WvT~ls3=>E&(%0qOj2&UfotVJlnFAzUmg^zAvc-I{VuCE!NnIyx*(%3a zxsovzB;BpKss!$a+u&P)U0_tRV6ar!1r^7FVbEL^2pYr6t_>LG1i^GL`M?$S3qzp< z)AB*8Q8n$IJOyaE)XrH$WYZvtZqp!!Hvd1o1RuTY} zgB78u13M99GE6MNym9Hm53dVHw@Ely+_RhbG?y#2uz4n18=4xj8j>t)Mo-5c(5r8p zeMi=e-Y_i(((+gGPuDBM?wNkDcy=!^UvmRQ4O3zDM;5BTV_EeSf?4{0zu`)&2;@&b z(j(4h;@YJh@W8T6F_ngWw7%nHS;27R<+(WW>n;njl<*(TFIiygVSvKX35BmYRtr7`P!7wFfs zzwtv*`@RjoeXIkyCc!Y;ZW>HAPJr1K5Amw!wlXiUktwZ;VAMu-;2%GXL!Kn+G#k7o zd&3zmaZtC@5_-O&c>#L%q-!I`P=lrcRO-1W@L|bO9OEz^429zm94&^Y%T9sk!V0{~ zW{wOqk=@_a6HKpEcfNh?X>>o_N;uruOB$>=UOXr73R)e(Fxn%MWR}(xLu2UsTD34h zV>Y&|(gU>zAuy+QGHecwhi_6vn3~LvQPaN3yub^BdH8(^@3JKcEk&6{}^wb*SXJbhq_uca!9ZQ8B+B@M;Uk95bS`S2v29{;5Wu2vKabi#)u~*wukzA`(fB<8_>Lw3u&`@Lc!!iGHGToY1$A> z_)AN}guz_}HSTdo88 zy#ru@bT;&LP6eG$6*!YyEW=bVOY2H7PCDKBw}&Jsd=1$*ph>ta#6?PvQ4~Wh zttsY+NiA#?$C0*AuVKTFFZlHISzzBe0tQmi2^@O z$VQDsnrHV{WZSLG6gz(WA)-oKy_97+9y8KK)cAxdFc7>BoGTrTq&g!jWMP`qo2> zc^C0%J$-oa{s@#-lRj$elc8ZS(+T9&`=FS>keV{huZLHxEJZ1XaarDrNg?1k1^-WeA;>z*vDBSEL&M`iT`o>QbN35xtuw{3A>AQxunVlSTml0OazSBWYlv>i;_H8Q0=WtepY^Lf}z-i4DQ zCo4;#k1k|iHlHC;E*Sm`L-T2JX=u%DQc5lCw2gz%(z_t~9*qZD7=h}HBcN1b0F$LL zV7ey@YhE;yVNw~!j$jsU3FLqHW}{;>Erscq`b!;We&ow9j2Fj4ye!d0rJ)$Phvw>Q z!I|8lJzsYRj(0hUcLW>3n3adYf3O}D8plFX#trq$~J{Z8A-n$G=OvvkhD$Tcq?3;$$P!#BekM=eIr64~z?};I6 zcrxfIl;Hj6EM)uU1jFPI%;c;k{HQtsE!MXbwxwS~eYUPdVNz{r)3vE9|NFk7nCi4@ zSXt|hh1a^UXoEN0Fr5gNPAM?*dkqe9V`;k;3{yZbF4>s3zmbD{Of3aN^OfSRX{mgB zQ$;CV8)^bHhNeoRK8>0H^#T;*hRR{XU<*8?KpXT|d4h45S#Wt*8hncTh-Z1RR$yZo zrj%gJEZXs3T9eP(UzWm*;m5=YBNZf@ud7Q#jxo&i`3ytntu@7*D=3E9o{MmJYCpJ@ z;0~RP7J!<=IXLD16^}P&k1rCL3EUx=rKwlA6uTTWcE6>dqqGt==V^vXVhO@H(T z!v=pSDV+%)d{f9c_-3$p8pDianDzvtAN8CYVk|+O9$O0a+nw1UPDF2Tk<<$NgJGRpdo6#aNMHb+mUk z#n6*9J+M=ywYSZORXWbNhnhNgnD|1AA7;>MaVo63&<5reGHGg<(sT%>TmV51sgQK5C9IXO z$Yvvp1@sB#%5e|wct9q4Rca}y?Vl=Hm$^yO-;+mA$irnSjsNRpcDF{Pp=H%x zUL-LpzK1$0CjL?y4b?k_UY1pK$uVW|1(3SMmrV1~1lzlZ;J}K7(0S)+FxcAxrX6Fk zKre=wNib=#Ja&y&_m&q zsLQg#F*&9>s{k55c;dNVdw`FFKiD)khZZCkdgr|=86dzg$?T?ZCBY;(rE*VipF>-B zTMF^UJ&?wMV|;q-a2Y1#GBW|$*^?-Z)~8X7Rbd>cn-)M!o;MCu?+Lw5AA*bKD`0MM z0wirzh0_-qW-`NA5zJ`&7;d%cIn=n^QrJx%Ay}#9@>cssiJPts#n99ct%0KH2dcEF zIak4Ah!^$<>_LXw9)#7imcwKBL>Tj^9VmBWm<{Ygatpx}Y!BxWs?yMkDVD;_oR<8P zgme7z`^|qTjau5jVHT8Kh1zHzd@@l377X!+&Ha~vscRxQbZ85cHZe>ilV&f$q@r{# zer6g{9c3wewjVC}Fq}LksqQF#Ltfv>wE^u-%t^2(B|}+zIBI4ry%mDiyWXBp>N_i4q-k6^Xs`dDIjW;&2P9R$Z2rTFI4m zMDr?KSm%cubjS?J&WFM5-6HVo7ze?)74-VbFhkhAr$50|9DmLg<)xyY?Jb3ev9Xfa zD?Hco(P`9i#6P8>rB*ZpMc2lY4BJY-a0oZ_?F}UrfspHL4)ZJHNaMD45M|3kju?hH zMleMizH&p>q#~?jDHQ1+AhYm%MRS&J{+l#%r8UKfTNQ$phd;Jhs0l$k0%6IEMKF`x zWA~rd8sc;qCWK+43C3=N0`E`y3oQO_AuONN$j`msAj&ie7d2H{_6D{#_Kv@$F?n4G zug4w6KI=81>*7H0m}(9&8;LVo-wNh;XPBQy+%p7|6QIB=7N?-HFBU@K$raqj@wvQK zL!Mz%j9i*G+kRu-9l8c>_Xpy2J2c_pv_MFGWe!^36X2R+D_GmeFdx|2lOq^UmFE1i zq7-!Zn}slupT|GD|C#?f_bdNzn1S}>xxz;>#hh%cD3Y-eNvEZb4$VDWhcp_t*iKv*027CDKlnDYq~b4mR^Gt z+r#)^KySF)I|v*i%%IKeI0)L%5_Fm|%xv~qyG}5@kCMJZZYgN7s-@srXu{jI5gR%> zE|WBsrYXkiDYLZmhlw=&Vcelq3#OGFftgxnFk}%q`s%cRswk#3bB3uP7$C0F{oH=u5-e=BiC`2z+7V|CPBRH0e7uIxME5=A-8o{tj z>AaCR^aPJu=(X?wQ$I-`Qn$pwIl&zKf_VlEF7J%5$kB~QAYDCMFh-?DjkBCnh_2&J zVZP>LfmiR&Lgnc3BI%*O=1qGw5=`Ldi=a_`kO^qf0~i|vBVNpb1tyuGnJ5b<_E9yT zshVdPGb3GDJ$SS=8Wud71AEjnK}${+9(|!|eCP?3R2*(MwX6ph;$4UgEf({M(F0L_ z#$GmAwa0H5qDB(ah|!2cpGd2P6vs#=@4GG(S7MB|J?vbV2}MV{;t~al`EjHwhcQ<` zo;w{}h=vIl^T&_h65Kr~&zXf3{ZEHhGp&VZ8KKO(m3ko67!67m4$v3Jy2_KX;HyJJ zXCgfvRKXZiTRHA1#@M69d>0e5Qc>V!VMY2eaTI9pX=EYD-0~|57~ZOdei>0rdaW+# zZi$An`Sy^6UuIVNAPeh9({t!G6r+nV=eNpoZxig`;h#u#(9ssm>_u@K$Bhbd(mBao;& zBeZ?|?{A^AJtpEcot}=pYvHm-7^B)x2NtkV5TND=orPI&##Ii6O{NJ{20iN>iZKbF z-m|OhaOlLIwx{<%WIa^h^1;ZlND>9EJk5ik3BP+9$vR(du7M+>z055oZ5U@71q+5c z0h5o7TH6(D!{|fLy(tD^%%uzeut_$BXq_?M-|TWhZqtfcYa=hDW&Yo%XE*g){78Ke zGyHWgNV15+?e(3&;!+lTc!U?}AgU&iV#Z_4Lz^acNS{I^kE6ib;;g7%?vDPBES_6udc$m@VXrwI7I*a=?Zml*sP%R#g>#VApXEykSL+Q6#5D?l5R z7W37;x(h?hWjV9zsGmk7QGk^55Kn85>0nv|PQCXs@3v{d@d=SIA;t-mO|oH7lpLJy zMllDd3pim+&dEBq=}G~5hZkwTCHGnDEwz@-J+gjcNEG;+n!b89&_QW0^RQ4G9!`&h zu6LY(!%rj_oRxzmQz*uc-o;&nF}D*gvU>{(kje)y-jJ;jt~$I_Q0EjY#*n?||A!fO z@&f40*}+^v+Mqio626%`Lt9D~oK2Poqf4~KL=`pK3XDPc4e?Iy1qioX=U20vQGVns z_ITm0-!ScsX7HFg^sKKq9rWMLq@C0R-;4-+`s56j6SHCd8F@I0dqtD)Hyx>(jTrNw zmx#?@fH8Nyc&#*6Xnj*y>N0Gb7?b(wR}TH>dLxZ7CEa&1s(ddPDi;pbH(j9no^0?z z3gE9xjkb?s{4i$G=`wZ*R^xEZi#HSC8kRkmN?r7d6NeBDvy8t(2cQY0J zd%@~;;h?zG1&)o$hL111z`HxtXaguF1Y-_=E@y+S3($%>FFxOR4c98u#@e9xkncScgDn_!ezQTpj_RKgqiNXz_;ZLfwDT>h!1IJ*W+3-&U*H|s!K_b7ON&;j%uGht`% zF0kK&VydapsxZbj|0O#n5%*8SF5qx4n0r-YDOeTn@ITdDtE~agYoUxHqXWI$B0B$sx1!EGcKCycb<)f-vFMh*9WiH+Rq@eDE>i@(%om&h4s_bLf zFdb+WMnME#q?OV#z+#UqEK;W_hcU(6!k9@;9k}@* z1y8wGvsVc6wej=2|HaeD>N&^?FKa;&%Zm7D_N=k#0Xd2lb*G_9**WVBSVDWt8F}bojFdKhc+t*+Zg8u37=^t58 z646whp`NCJG4lo}ay^gcq2^OKLU$Wla#uOp(#`DdUyas2*bF*_=M58sUyaoPZg~vu z&4tyROM@rfyMWdPiZP`a1B@{qrO0t>@=%5dPtQ(o1jYk%1@Y@>o+feVzZuOO=V@JX zqM5mQyH zMVzO#$2^Jr6*@QH&VYRpHSqCP6!UJn7CiZi_cvCK5cM(*`nbzNh!pj-5fo#AF>gN0 zaqfNdP*au{|KP!Wq13VjcC4|(&#@t%_BS;VM{%C^U_W#JOD~u*I|kJLb%d((X)vir zSLo84s>!4dZH+OByX3iWJ{QeS^5XBV-6U+OKhLGB&iZZj{2OLq>IJxYCYqVEsTas^ zh=F5vPQV{Z12rW%5H6z_Z;F|WF`*uETz#Khq;uGd&$d?)mTPqv9q2sgH=~h7`p*ch zEK>tdP4_dm^tE6MZVS5li4$lB;5&s=<=|ZltsVSfv{@L#FX_r1$;(0WBC)4s&$V3P zdyqRa(CDWca;i?$v>zLCG&Ef20@S>ZW>#1C25r+Acni*8fg1wOd*2Ccd(d;}0y;LX z7^68|hMOv%gK|Q=_`K)pLaE|TC&JWd%3=449^U_HH1e_7BD5N|O^#-!h4jK5e4`=d zz|lo6{5>Wg2({Gq13 z(Fi8N^#YvV8^APt(FD)k(cq=w3dY0IL94Gk$Oq8%#+hQgF~;ouOSXDvHkz>0iyu-d zFLdisEtvRtr+9k)4MRdF!7RgPofn(JneljRUiw9Y`fgWfz%lKzq8xw`#h6jdR*ZqL zr|k2rY^1!yi|@2kQMhYdN1^qLnZIF3=pp#BtIMN#h5UgTw&{oR|5S9JH#o+ z-!LRX6E#&wszJ7EICB!G>Wk~5q1RytI5H#)W~nH^*HKhW5XBtAn8EX(vToP~Mqms( z;fgT+MlxHmxg*`M<1d907a$*2Bt|3E53#qaAyTlLNm--;*=f-*Pt^rxPfUl?kK|#* zJ(@#XQ%o|(Y*)U|?%SG;>bK#AU>Pf{NZQ0!JT(=oAzun5n2VR%#Wak$wYM5vg~5yr zrw(fKqQT|yT$sS7!=OnD5ORnnx3(0Mi!rGWZ?k4q*+}2Vi#Jb~5zc#hP3ZegpCgMj z!Bm&h=}FW`PSuH;xE0l4ekquVf2JP=Ya!iksLk zczQl1E^ti5&bm@0jPL6Io6$(H`4gjdu^P0x?qxdPR)_l)_`Rq$7x<1(ZpUhM0>1!? z8B8&!Fvi2Qg*6dS%wFZ5qKcg50;wgbmPE~hS-*@X!H`c8L`|?i{zlL%nDIB)gUU}4 zu)We5TA!rD=Yd^7mZw?gYl^ACm=8yuuyIRrkT+KI@j?vy_Qpz~?~#Jv)R6Btug_4U z`8!k0#xvD0mkDJmZ8dS_9nNf67f_JS0J+Cqz~?x{{6jH~7^80VjQzSf2Yudxjiz~r z3-i+#+^wG{o}LmHAdhgjS2Nlh-vw2>0C`9EF_Xq=ffha*l5v^^5B^ODwLQ3Ya0tb0 zq?o%HGjZY@_IY3qIN+nze(@$Q{$;ixJ*xFLH4=<+ z_g|R$SJhyTFD>OZX@V#`8d^*pphJ%we6-pX*6pG$P(?9sG3Ma*&#d;M9K^5k!jIHt za#d@1L6v=XafBvn{CN6pt*HaP(}BN6kxzKU1vYD4fL#~Dm;;<1T)Q6uf@OFcC6fv7 zOFBWP8&r)7#eBmUxfdNc^Eo-lYKa#=bVo<7;%la0tR5rAkcuwy>06?vJ*Fx90<3=; z!*r6-g-dzS5H0TjDg83wypjww{#XdoY1^DG@z`i}GTeuaIcWX@FMidAS%NO>qJ_yH zkodz2QS<*{I^DhiK~o}`ej9bbM?M~aH0Pg2+r0PhYHIIY0Qa6z%!v?-F|GW z!)icAK9Kp=rVTFy(NGiO0D;f(ad*88bUQ;acGLyTFh=LQELU|l2Pus9;uX6Fa`EY5 zmKCdQeq#PVqn)3M&jm(=G5)nWFb=2c>>+#DE|&ocuALxtDa8z-7y-t-@RQ@r%5%^- zp%?$fwi`F)_ywWLXVagU|4)r=Oby7{hcg$t>cGstF|hr#J@nVk0K-=uVbXcJteMcU z8H+Lg&lI?B7jw|F;a+^n;SndIE-e2RV~Cun_57wHKUGYw-R9D8st-{qhLGknT1DN1<#7|Z5Qe)=2cZ}Vn` z$pujK4rZ*j=s>u444kNRfVrE~;Z>XrOxR0rMeLz2;D9l0j}$l^>0ESkpcg+mu^x5u z-eaZzB2+-i5|qEy!=b`_aRChJ2}!CSBt;fd!>+;_@18JnX*2GTvIBIUtb>JZA_#bQ zgV~VbAdYEr6te(hPF07p^-QPt5iw`X@ zEpJWJW&DRki6oeo=>_6SNOH$Rg1Pb?moM(GhL+D~nY^&)jM7&>5PaAM6{A_uS@ekc z;72cC{7|zVW9&rVSw)v7RA%GFFPJ>0tXx06Y~KVynSlp>(YK}^PE9NjS9B3f#5!64 zLog?YiQq9C#9VOI0A}Yt$VhgEUfNmUna~rIchfSs2&%@HU}6=x({`898$3NT?UY3$ z6uOsN|I^8esF7gEBis@-q|Sz5ihU}T{_qxGYF)G=WS5BtFO&t07N^5uq$iHc}Ue!kE%T;MVe|ko7n({^~~mGB3xSqT-Ud zh^TozutDr;qzsNUIVBjPhPXh0&3V{wagwp=V+2;#;c#iuELip+9SSbLU{)3psRN$BUoPe+t^$=p+jI=Z+XNG^zporqQt>U3(=)JA@bG=Pyrz@$hKI)lU^< zdhdm4gIwY5y)2MFEd}*ubW?bdVni5I*eQYix}p>b&aTu_q{22ZQrhH<&7w1GkDkFz1F)%xQ`_i!oEWm9QENi(aE$2|Z2-ntP01vCI8~Vj-_AT`>fPB3j;2Hctbf$6C5Nn%8YczW4*Z(Yh6>A^IZ)f@M#FhI?ROxjZ84_AqA`z zO$R0SZ!o5Az$^AbPB9W*@Z?eXF%-}A6ji-BDJ0XAj18%TY_Eo3NIE!E?KI3kmdu<9 z(1KTM_QKOz7hobYz#!ubvvmrcH$l{BA2DWI-+I;pckBK4oF}goErm2rnQ~kAIsQ~b z%14`0ei@Bm$W@ZarjyXOC6Sppt{2!l2gC7hZeXC81y@5pGxrA2^3m=TBb|T`@4ai; z9u|ctq12O~vu(Vn-Y!%$(mqp+AvabChNzLu8wqAo-%98ag&z(cuMG=cguse_oxtQ? zI&=wo%b)=?|#E8bj*`a zKR!j&-7$N+8vR3z`4Jub5i%4~y4k|Fy!)u1Viqv6}~wIr$?8_3IFn{@G=WGn$d89z0dJ;@bf#vvcvS=+8c_Q zh%tv^ve=Ot5hx9-@m*YMb;?Nwe`E;~kq!I*r{>DGG;p-7gompmnI%KDVb_~b`0hL# zPNihPD2L9F@`5H%v2^vc!`AI?QF2c>ku<5MV9Zn6WFt{EV2*%8*c(qQ99Q*{@NQHyP2%iIniP3&nSwu}&6 zZ=B6-Tv5*bH#Gz^1W(T{yJDJo(v<^(9Ys-A7Vq<2X{+ zNe=HNo@NmG%b^Ko-1aJ1`)?xi@uVJ(X=Og14Mi*&&IySp7<{~S@ zWsZqOo(Z1(*{!3j9-Zn@mR~efTtVC(LoUXU)ssX4f=Ldngrn8|%$ABiP{iy5wX~_w z=}|h!o5?^ePd)7#RTGLaN{>FV-}B?p>{w6y4!f6CTitw-_1@nx#ApOVipV9H)-xwz zKjT)^l#T>wxM{^&ryF_tl`C(7qe3mQ*+D&a4yRLm*x*l%zNt4$`o@PV@|4mW2aZfA=$k+*z{8ot^7wM3>*38 zuSRQ+x%1#06s!(nI#&0AvJrbB==&r{_QLB?`3GjiF`5gcP@`2~OmyfMcIv^S$R@~> zH@G+%B|B^tNiEm6Bzw>HV?(ZEw|9ZTI#o~|?8}TT=?e>S$}#xr1kj#{%SZR&?mQ(F z^N?byF(%F8Is3UN9xdDB$$Jh%4{gW61p*f|;|2I&?~(v#?;~O6JXx zzEJln1RnR93f9aG%T`Uo30exNuoVdEa~)Y#+a0im)OiD z2`JaclYi@Df`%DeBDVoa;tl)X)JQN1b!Q=d!D`0Eye}-R2!>P z(H=8&YZZtbH!^CI`@!4kA&?$09W4AaAw2aH<93hE8$}wSzhF#{@JFnjbRt@~*^@t> z$8m~#yg9|amxXe5^j3sqdj5$CamRh2dhTTUSs6jSatNrNnGAN-*rAo$m}fs+pf|;I zPQ=gec7MtmrzE2A^`88*Xa}x3X{S(seX)3K$Q_UW53}Vn?gLe`g$cr~SRy-wfQ#=W z@NCAL#e_B{_{ZZXhbcx8V|-j6vd`-hQHPBkHY0vw< z7&BwkHTJ$y67ur)NPP+%DT z^EMIbFF@3g6DV>c|Mk4v;vK;=`%C0t7>PrnJXQiYtK5x$4aB#}Al^ z%a_61BR+5hD&g$&f%wHG+T=8iV%#uhHve95RFsLnO!wr?JY<=FTbGn|N;@e|2gz=Y zv@sxeJpNQu>Q#!<^1+O}t~_jZ^M#ZiE1}-86fX$+a1+tw_8i45!I;f?u7dg*Ij9hM z^3wkE%dU#%lqoK}F5Y;wS0lkZ97v6(EW<L{EOO(ztRrvr$%3N)NU>EiK1I9 zQ#Eb~oO>Guj&mo&*VtsZ7SsXC$I!$35NfmtjB&rZkTZzPM5b7c>6#3yJ#O+=qJxHF z3^^Sn4lQW{)E-k3b`I{E;@d=>^x;8=U|4(J8S-$8J(H1gFm5d!o0SxE1Y0!zS8lfvO=JuWQ?9hc7$k@`8-+lOfS@Zbw!V12SB^ZgC_AckQ=_$DjLHj5ZmmZa>Wwj+&q^!jA|A!x`Y8Bcn2hyjVC(T1W2icx^r1ey!{7@KDpBNK3z-7_)^U9j@x_Z&E8W!G$ntYuup=K|zY1PL~OGa5Vi zECe46W@enwfPCW+=n%RPZr~5gtyghH*Bm-MbLne7?=fa*(|)$-Sr+;z@Z^)`DkJSC zCsB*a4)H=jzDAK26O!I`?Z?JyP%SLjd6en#*c9@{go9qyLf{0&U{|09>It+i_9C+ zrcM3e6ZHV8#6?xZUCa6~nW^@Q^%Qx1gB*^pQFhj0wrt;{x-t(BNU7d?)X{ zWicCiqLI#0jy4SB?YU`Pj;TgnY^?{NV$?zAP`^N#}C3P)%fodsK7$wB8M^vvcH zRileB%HM}`N@KIp3R6%1)anZ&{%j1Aij)?gLlZTmFNXv}zDd8Xq?n8IE<rsIJG@*3Hek7=-E+9Vc#$6Oir#@0LLNMf1J!wKMl)p%3g1ZcW7WZ)I z{bnv$F3Ev^f|X#oBi-V5q-qexNQZale2?X#4vIJ()DK5)EmMW@BR3#}cN9ZDeM{7k zDpd(av#1(!!xNZIOZ!7(WjMq+xPoU!HVny7$M@W6N&GviW<17}Hg)FY*XE%Iojmzv zePl)7y#}CF_Sru%d_ z%ZR5*Fr>XWFm*5t_KSq$ zF|*-AU@BCrcY!IDbRkHim=zfFZI>ChW?ViBy5_-OfB#JwlGsD|I(ZKgI8rs_6CN=d z!H~Y{1Vg@ij-OTwm%gPjN7YT>ORq?fhdJPgpV@I` zJovq@JD^<+N&f73W=gIx=#P$o z9TR5byUTl??xjnTM6dWeyZlh z_bTX#%dRhe>JKdj;hO=&hX&RZCYgIaQi9OckdiArtM(8xcVV+VuScS0@A@>qQ-ImS@^1x$*9QmhUf?3 zaR0_!I65)|PS5QDqtoa@u!2T`TNpEXZFjE2x?D7{$b(N_V_v?|p@-1G_l1a@KxtXm ziMLTtj$amI4qc;|E8jE0p{5lEt^~+$+70K2pMWSs3)t3-x4Mg4n3;2Dh&P2{bVu+I zV+K^74tfmPUB)>6u0AU42 z(C73{7%_u~P9;)M^LiB|8Sh}ynihyLqp6x#81o{dt7v%FBxH5VgAX)&U+#G<+p0C@ zgvfhlE{yI%G2094fA%0IMk8vK`@(hf{`_(?WP9M zv1!AYQn%+^T1^`2izD>xJJST~w6}}ys(unmFl3QVE&YYb9Y!&Sifdu|YdLtMJ`9fS zI{>QRY+=`e1hC!ml5sdjk5nI0qjgHgp0+uZlb)V|D$aWF6CLWAHRGkq^{?GzBOX&V zWRWInNMCi*!GCkxO>vz~`r_ljr`=@^Sprm^I0X8WoWR3B8C-(cHr}Hyi%Uj=9$=5dJ@1JNc*NWk$FwyA)1fV6 zAJd#A2f9~$p`(%?oVZsGvko(mReVT1HtH0kfiaJT>jaOv6eKM7;QMR2qhh_~C~iU* zs}`(+U|OcmCM>}X>8`CS1>?e7Odk_PSXR6TtVXSa_{wAOEKwVx zKG2QF0XjAY81sF>f|7qerlFa+9{k)*^5u~3SEgT=#}SO3;Ieq$5R60(!H`AzCBwnS z{kND!s|JExXauD8bpfUPbZEMu1$Tzh)l;2f24Kuf14S>XU_{a7Sd@w*!00^~gcGB(7a6VFz`%6J)w?mPu{9*>7H2IjDN zeH0WI;u{b$v&EQA6l0AsJN6ZGZQWCm5suJ1R(C94GStp$z_?Jc3k*%J6B~`V0Ey7= zJ#)p=^U1<22wT?#-m`i`<6B#J+9?@k#|?w`Q z2M&1fVN;Kl`^W6I$}KMy5ls`Fop@aK<3RUe5!lnXcOGLuMc0VCd2vASh&4{ z0p=^dFMahi6S31)jQMe-ItycFGFP}J$UryzJ@_e$HLWyMtgQ5>?PQI7+*(P*LjAzfGfttNABTrxomWQ zEzZ+ocQD7cNtG=;Ho{68J2HuBq;`;NBEf zu#BMz)Id6Kyf9{Q*Dl-yym}sV^x*UQIy1gAyOebb?2AnP$%iFzm*Glw!Ovx_y_$b< z|CDIgBg~cADiCP02PzmZFzcNOtGf1u)J8gQo>PoB##|m`#&%1|MDJ`o__}Rn$mPyK zk>g=itD))z;9Ykanwkq>fe&3h+hcZV7r?HUCzvUY+F;0rfbr(J@b+{H@N0U3TrS;4 zHB-!1jCrysgw3-~M>nlJcnzJj@)gCg$ZcllpBU+fztl`l&lSfsGBza}%AnEmKJ%c& z2r8Vzp!?8S@OVNjJXzWm4*Jl-u_}u3$C&qu+FYYwDrz$G;Qf1bEKl7ZA!;q^Cu*;T zc_+euL31!tZAS#XtJ&cFE5*G^(`?KUH`5u5={E#&}3}L8!H4u zLMJiWt!u}jt@9~n%R7CTZ5;@)d5fUKk!096P8}b1(T#^0#hk*Jm$gM~Lr5CR(D&fu zYrZFEtX3;Uf;5@){Xs zFomcmp|Hbe793PO3O+vFAuFF|HkMRPBgS|u8*rQJQc;bC2VWGLQRWxUbAw*){0-CI zXcA1%;Bwfw{WkM_;$Sde5(d`yZ9%Oj7Tn^yKu%{5v8P$cgpkMU?_x}^qS4%k32Ddy zJopjm(wxCzWl_m+lix5TbpB~H-*X%kt-8bnai$RO69)P#XTr)SN5Lbj8w^yXuV8iP zEXF*+81o6kIHy}_XvtI()4o_8z3+qGI$jhl@hcFA&e6(+;s`ClOdCqaW`%7jgjb(u z3i=sB(y?GD9p?znCzC*~Ndp4p>1U#O6!R8iT78r_wE^kqsDlST`l^amom>gJWjkH0 zhD2yGHbf0cIf$o8Fsb-!RDS15rhA+LTdr|=H7*{!ed8>vCEC%#1DCx-b~y#&_2%_xiXl%R5zKfgswVyUF_<{%0;3zC0v=Yu zFlo3u%+*Z;xwV?Guz+HYQ%si>X{jwmxKmOg!7EG)V9OL8L<>h8`iZd{TPR*V z|HLd4mO#tOYG&E9KJa*C2qX`2fu7frVg4#y7Wai3Emu}NHp&>oPHbksd8eaID?RvS zmIKRfUUd`s#;9^c4aw7p8j=f0Fe^SciRaCd?i@J2Y+~+jFo6Q|aLD0i1KW@QgH#kj z7c8#%$W&gWIo~j-=Ok@LS($m)&(};1nHVf5VVeU4oGqE%owoINoxDv9L6O z88;#z-f$K$o(ZtYrUx|r=sx-bV~8=S&br*w^Jz$TJ@&NB{-UT7HB?tMOt|1qfjH&R znp`MO)t$PY!CyddQ_XW!P1>7M;2zy!+RFMvPFxr`ewYob4dbCLPze+#)4k_sIyPn) zGvsI=?(>l}6tl{MU)4E8=<<3f>RZ(fNif7{WJf^M5RBmB52O8C3e)diW84=RL$7(E z;tl&%-y~4*RfGY@>89`?HJSip)~Bd)Z(`Dr#bUf8@a~8zKJx6WakEhnUYtn+CBcxV zk=tYTJS>H^XYm`jKHBi!YcH%+a)X7_lOZfk3mk0dLa>u!#$t@)_YT~c9cie@)q^*j zErm397>Qa-4*gUky^gApU*2iPRVe%Rt3T=sTv!K znT9bPX321g*=b0}&V$c+7u>UuVw{N}pg)-N}c_6_=e`O(lc0F@Qu|KTK z2!l5+_RuPO6h^*Rf{wFkgnm!Q#sOn;IW?|dN*anA>%oT)y(!8TwQ*{*>%|yBV;vAR z1VhvijNy_d_=XSZ)AzDa`1~GzVbK(JCx$`D;Mt&;6%UJb)gjN3Vzy8<3&_~;eK?;L zX=tCh2Y;x~X;I$+O~Oifd?<;>Cg={uESdH@hO9RxXDeXYhNsMghM}Yg5a zP0uQH{l+Zr?ZJlMFa|RzX7t%#n4~Ep@VVQ>4A1Ec_h;dA=vsSNx<3KFYV-gvUpj9t zQ;aXhC^-+~MkzV@9eB=XO0!Lu22&^Yc6P5t)tA<95aJ{}XfV z#R(WO?*{Xt>mV3X9R`9UPM~)2FusZ01N#5y%h9KcICMr4Ojir8b5j~R((2AzTN?^X zzbK&tPr{J*m_k@^yAIl`**+v6zAb11qUNJ12Nw?3GslMw0R4$!U@&+NL@$kllf8R@ zY9ck-28xNp7)LXV2}nbG?zr=Jca(G5nyk>R<3KTnxWJznt&wLwFo zZ3rJa;1BuzU17wRSg?Q89fFcGB@H*8d`J3o&PA37ucpxX7#sD7ZRiWi3wWx3o~?j8NAqko4K)V5F{SL zUkZ26fdvtVVdGeway+GK=2MIaV@#DNaA7PSn>u&ieDOJ9#lRt~l+Fb~dyL8bD`GVS z)4elQ)4RS5Oe$_M#oq_Qwu6yi6*wDoSK}vLj8s5Pnr1dzDCR82_|6;4;WH@o0%Jb< z4n}nyj`YkuHxR})r{Kom= zkV!B@b8!c2tVV*7ZnzfB=oD~=iET21d-V~}Qac;o--!doT}oh-O))l9%}0zGJ;jonw;~lS{l}fZb#s@X z%faE?syE-oMiZahw!1&w*;&i`8xD4esRRwyO2 zk(FS)o9NgW^q>wcQPXV1!8O%e%>2UMumX2f-caKLZlmMD*Rm&!_n?ckJ6#C$F(y2( zH#g*C3Yvy7^RK)TjpEVK&)?In)j`cFKpz1$OSFQ%BCbZpEqrs07eZcCDi#$iu;wYQVN zZIyuans`hYfjx}4KzmF~^e-0>y)OaP$m@)2lL?F{-Up3yoxrwpECe3y31}3})0`-V z!I4se_ew=maj@yLP99zF6D-)MVTmMaf*3kBFRq>jqUOa)>d@ZO zrO@2-3bQXlAMj0F*!#i_KAw$->BBYPi895gQ;Z$Pv`Y8ncH5<*F17A_K=l-%HGe~} zHPAzhk?URuCRRl-x#S8c-#!gb_W#1HJzWB;Hr`}54KRdxJ3`^8&s-RJKOWwHRD&Dg zG>1M;UBCrnnjMt5uEVekoO0)brU!C$J*5R>$9esRQS+gg6`{W{uVh$Qf94uf_SO)% zx^OtQ$r*Nkj|bSS3e9uq7xn^*@xYkxeUv%f$`o{^#GOB&{+U}fglEg+eZ^xlRF$fc zVA>naegg~LmS1Q7S!x7Ecz-i%vNIG$#ltaP1xoi)H7e9-t1zZ-n=g;IW-9OdXjV%I!{}mu(lXwnan6;*3)87xPS>D8q*D?m}llx$ZqBG3Zi-nuG zhsuNp)SZX0mV20C*t*)vfho|claA!_8ZD5k}VViI2- z2dBm+=K5d*SeqXSimLOVW^f!>c2vX1;?xC_DP|YOoKw-{)Yhh;4oBR1mrNCb#-95E zn*k2LVdSR%CnoM;2?#T;GwSb*@ZlDIw)!a!Hd04n?^{*)K7@{q5j9#U#waiB#qC_5 zf?h_t^IvvZTDHzj5bo;L|2NFgS-)dOzs&}(O{K6Z>pBxM(g+U3g+n98d|P=GTGpt6 ze=OZed&`USv;!Cuby|m0pO=E_Lfv@-*OOe>m|DTD&9Y*Q#0CCT6%u~|Sdi5TPbPM7Q0kc`xWu&1qR;#y;GvH^=u3CY+< z-?}88H-E#(e=h~EZx0y3J7ZWpCLA1%=E6(-YU$UJDv*1PM(E2FlZ`RjZ~AbmDaq)V zzdK)Te_izDV*qFUJzwxQOy;M2ATB`ER4r%W>g~JC+8f4j4riU?u$u9$Mj0 z(&XZx)*3%unL{!2sG16laa?W86@E!Z{dc+ZOj!;akeDurU(_I|R;ET1ti*qNQ5TS4 zrpe$chij!!FWbzxZ7_g==Fu?D*a=kD#KKU6p0Mg9U8J9M6RWAl7{luWxO|fov}>n3 zA2GPu@^0CFp;SY92{D?<{YyYFh6cZ5h|#v4XW`NAJIu8`#_$P0ellCi5tdZNg2Gh% zM8!+$X~!t00b|At8OEt#H6lNEez!+oR{vsef#QkLVxwJ2qZp#*+s4yC)HKS|v3Xg? zf_&*C#`n81n4(BH*5V2ilCYWxRY*>zYI;yiGsb*fZ_a&xmW)hxxbu~zV>qc*hex_` zcf>BxmhlVIwE7pudteSM?8JfQkq6AP`u<=S5Q%TM;x=v5VnKd}Dp&|<0%b%otr(NF zYy`I_F&S<5ap%28BHXBPhQKVMn=lhE01^x_T6;AFGccqCm+t(-sD||iSDX&6XmNo& z<5>85S{33OsT!B=;<0&+F|)dwbN+V8Xx>(LzV6l?OZ|-E(pMI%gjaCLBp9dl)CJmO zCL88}=otRIdip*iEH{Q^ok;lN?E*WM<6!r7RfsL8W0TrLjQN5wcNd#+?zYM3>Lzzy z@Nb&1i$fy2YVjJe8m)p~Mr)5DYSaz$?ed`PhUd7@MlDKerGgY%& zQH<%FCM|VOeh?Sg6B}*4JKyEn;L`lFV^}lO(BF(kT;R{K3Cb*m;Q9BNjw|{@QCkEg z7dV5eQ5;AgP=$wQshZUkqlhv4U=U}~JsF+#cIPWDd@c1_@l+5nt>!;4f2vVfmOK`E53y~lJb?GG1rN5B`{ z$-=ee5Ew_PgP#IblSnaxFs56=U~cB{WK_1moma75DK!2*Nw}(mvKT{LU~~fYG%_{> zBT-W&Qwody?lEs>^n<#M5m36{1zx$w;cF!P5C{BY=z7?TJlT#;Tf8tH;Jg=yV{ zZZAvOT@U;JR6{V5c_UFnj24t#3XbV_n649zVBFbon3V1c2k=MZ(gJnRT1`DIkg6Gt zF)1mA+{%whsOube{)4|Zs(AZ`HMiG6O?bYLc_UHtdi?KdB3>VdjhpW?!-p6`=hko- zlRY1NGGjq0R|5)@X@p)uF*X>pvAQ?cn45(9+q&~=Hy@$_Uq#$2T`g3IL+0NwWNe6< zy4VvS8*rORvoVCy$Kmj(bsp&E#X@v9O_2W4*escP+8m6jx6jW4KyUhgeGlX+3;Sk|E5Bx)7p>mQYtk^^sX%mWZ!!avnqgx`&pcI^Z#acO3>&h`Vv9pRwS<_03oIOu*- z1I)B3#(-j$U`*tfUR?eCL{v1&oj-D9lR$BbDVsl7B>dahMD+dTX(yvkK=jw!OvHOb z*wHT>+?3s*1|L7vDrmyh85CnfF>5hq*uR?Gu%<+`k-=GKj~(n6WhJ3QT*OZ`OVa;t zH1F^dxTAB25e+p2cYB<2=(s@{Rx?IQ1J?i8d*)Kic8obTUyC~^lY|O|_-IJUmX+#e zAXJ>{_!A@Xw8BZh8|~KG64;X3%qX8UgoMm+koKAfyB@>>haFnyM>n`p)YAemX3`)n zZZ96283K1c_*$D#>h=JEe*Mb-z_fP(vJe~_R{~>?-e%tKF$A66;ZU@09z4YMAX&No!8awg7i;KXZ6+e#F+L`pgo2-v~9-{(AR8YVxRSc z*vaA0+Qkj#E{p^H=lH?&Dmri0DTxDk2u@8@vQIIK+8Wp z?N7|hz9%4c_0 z>dvRIzHi_Dh9SY`PmJlg6QFN-lX=w52y}2I+pC7B(CLy-x zap-*CdKp~Lmx)gY$wCnKE(fmdDTWKpHqcn03<)dtz_$*SuzzbP1b0z^a}NE*AB$}% z<|4+Jc)4@di7YydJ?(|YBCD$H6^!{11@wAxF?i3Yg@{$fKrp95%fV2;NW9*h3eE+a zgV|v2^^FO>^olvMzz@FJ9)>Yp_QMmVH$3~%4el15p4TzvmMP0tmE+e+P272#`+b?! zlP_6Wj~yZ;7(1>8G8-r+(}ZG9rCkStY0$`p;J^;>BI!QU-(nlYJxhYZx3OTAXaZ&v zX)CaMbl$XJ%+L*)?4SiF(Q0M9VK*NlTAZjgX#Dl8zV2dy0hs^%HS%pP0Crbiz~EvoLk?9ChH zMSk+-ukNfBNiac7F@CQ4GDy@AOa#8y-hX5<=;DWi*K?B~KsOFvDf)tk-Zo$_C_~PfP$kcpY=bWoDG$VRQ~VDu`GHvw9rG^s4yYp7+qFyli8kvhVKUEzO(VXmsuHaTB;r6sMc;V&N2 zArC;=k>yQ*!*Jh?$@L;I?N^6z1tYL}91k4}eSukY5_-DjK~6*Re)B+rk;j;nfhNMq z-kEr&7mjtZmr1Xfu}nzbV_s=Nc@j*W?f+m_&wavQ3a=f^gs(U{xS5;-6|L!DX>}A_ zRlQ+*jxngbKE_KkPh!w27_;!vMB$lDX~a%!0tsJg$)HLXGQD`CkXxJo#>^=FA8EL2 z)Yc`}AxG^qx=3+d;v=E)STKw?2nRjfr{m!;UminBFcUCl@8;6tqOmE2|2Q0kEPhK= z#>}OAs#fsQWG|}amBvY9`uYFFRFz(ZX)C^<|IW@r>FP4kB6WpN-sN(+>oB$!}{ z(zG!qT&1UY&$47fX0!_{|0RjpKRcS9w)PZn0ymD;^68@vI`_b)Lku?gH^DRbA#ka^ z`R12lL3{=3+Zzamy#)|A%?VD8+YgEr8DOU&$x?kFx!)LK%-{+r9;CyEZk8!of8LN?3pkd@`NEKd0g#+-*`h)A>Ja#T9 z&e@C|-eX`CDyfj1D3ON17)=FA*catYxJ+?jYlYW{TN`c2xlE>r!ziD)$EPT|E`I>U zi%Y?_6Ay0;z=cfsHR=(*X}31Z!Lvn{aK9}UoThrh1QmZMNVkKs*OJ6BSIKu{g)yn5 zrEu2tl|-8^_H3q)psSYt!$>79n8RVXC?N4LCcr&NF1()!r(V{fndSyC?qD#SZ9WCh z@N?0mRr_J+a7h8PuLR?aF@>?h;+CJ=i4krt?4?e1I(_dWvd8x9znH&DE?UjKQmvo^3*W&sOJPFEl6qNNW1BX``rI~T%3N*^SLt4oT;mXZ$Xlp$L<1zw4U1~MF8MTqe2qgyXgE8etDB&i}!{z<+%zVzStkkNA81Md{7rFn#1*t5{$6~lZ`Ro!zKwQRs;~=l3mzEqB&$l z(DY&@A#M3=1`l-FK|t}Tsd zek=t+AN=9F_g)Ychr;4g1j_3qnAZ|ZV=(5po2Jm|O%TE0SZ9nCMZXL-BsCLNNKP8= zndpCG$lK#~9r)Anb7u zAx`abVZX#{ihOmH$X@q4f^#{zM=uV;<=JqqI_D1l#e7gLfc?s@rv_Z3%29vK17O(u}- z5J&NaUAiz>(hRe3&FlycS4b)R2 z&1<3v6pETq>y`zOa?A(B7q^2c5d-c8rtoL4gSeS^tCKGVlLlIB7VqbJO_(So!4m~Ku7Wx z!uK9;c=>S)Xl{)GJnMnRkFwwani4Ugy zRoY)^{u{GQMuexuHKT2(7r|HXfee!^F!e+X{!%?-mRhZ}5M`%(yI(=8cUIwA-Je3Cos%`?w=8@s11ZFN=a#1$q$SD8U3s zq#1)TDIJ9Hj6njC`^A}M1mU8uNka%~vWw)x{-4j2%TndmhLdLLO$jDmP6VM_Um)4X zOTjwZ8*Gy|!@{0OSdgs;GU;o1OY4+Kqk%DUrdGleM-mC+PtNS+kwJn7O=kr!9t`?F zr1}5DAWIgCQ5`xzb19UM@y0u}GZ-XA!Q^8`5VT2R0x}Ye4#w=>O$rUkB;rGlGaInc zkLWjQ7NqN^2)S4%w>FiYlH!a1EzPk=A$*wr5NW6^gurMocsarasHA96Pcnwchmy?u zGReb=DaM?CFh@9iWHQnD&6$;1Y9drouqL9cbVdI+j8Be4X+AwT)oSD;W6p}g*q9%KTT89fQX`Bh1&uifCp3^{thiW`RGQ$=ErRW1MXE?*I z)+h)IG=d-Hl7k>wg0aJx%L#<=VPrBf178aL>XSv(nm2Q#PH6I&Uh+O)vBF8ioi~3i zjg#h#1r4W{H=)gk7lYPnUwG8J6%_EJ@#ZiCpzxd`uK41m1mlP?Gc~M)GozDyNb|oj`Sv;BZzF;lyC;Z#YXhl4KHweU0?XoXWxlO3^nm2NIU&Jp z!lQtJ6r9MhltuR(K||CWYZ z8xC_tUj)0e9-#r<)=(z!g^Bx}p#%pb>+pHg>?!#?UrG%6D8>}I&lg6IPa%r%{l-(C zCA@+s337VXd8KhK$6pNRK>b}C4l}W;7-F&;(eJZXu=$HOJXq=qHy7Z`;S5s_9 zG9{P*jB$8jE<8RVg^Gqn80nxE)an+m)8-(2g6bbOKlfcwOLOjr8lCehY1jr z?vp%7atZ$bjp6n*E@qQcQ3O>sooHy%d~gi&gZ|@NVXSQ=9LX~Q&l@XvOG}Ypk}$?Q z7lgaNB@@9|X-}lt;z0+`2(xPI_^p$3)j4Tyyu~f{U;mHNI1J-j1nn1|qxzE;u-hd7 zj!18V*n_wx_Y_{6iZwjuKby@tj47T*2(_z|i3<~5*gaM61?TIZ3zu))$8Vh+=5I>; zU!`%!8i(n}9jsKYw4l^k0QZ&#z=c11VWWN|3_l@&%yp8B$4H4ZIT&NK7lc;#l8HU| z!k%fSD)N%m6|C>v&7Yp!Q^em~b2g83FSj~K!i;g^y?!?6iGhMA(HQ=6k|L$BjG`D5;5qvGkZ<^UeIpy zNcd|o&h6kl8~hseH&>mL=D#sl0`fsQ?={kl25>hy2?a-X!r5!#aGNAyTJlm}nh6q2 zHO9OOC4`;xlZc5Qo!NvB@xqX|VM6)SiM%_=DUGX&;M~FNQ>FiUot1PBEYr+`-o!U( zrVa)9o+p9!-3L{MpJh=OQd;$F=Gap2-S5G ziR1OoZ0`M|qR!qD;oiqS66f|mO5=R!|HcG~bAa&9gLwZ=#Ed{-9TWufO!mS_`B1>Q zfUwh5f~l2A(}gkj&>Z2;oCG4H(wWt-s1i-m@h+-9?D?-WoTVk5{2vT=@!+Jn=$Hq# znjPqOCILy}Q}DolH=OJbf!-tfx#+cNV#=`8*c*60zGn=->i`X6gRwz|A!JNN%{Fe!EfiBL{{wmG$ zYdZV6?IrvCTN!&Xxs4FbwjAGP!HQEnhvzZPnh8{DKCQmO%bdXcfid#^@HfkuxXFGKn-(G3GaO zPEZ@K!<;&Az}l~6(a`nhkjgv<5r^ruDTAmV!H_-hGKAeM1rF2n6yYgUTIoJSJHpjXsB&R3P~EeHyba)qvgiTaT2{9}Q*u zhLNu8YN0Z>6f_LuV0A05E5uu8(@@+kX&jy;6A=&7rW?~;FAkCppM4=#+yK9n{Yk?= zljvO)-(Zd0SsrtIBCj-ajJcv+CwT8NkvSV_z+QDSBdbrIfLI58G6*;Mxv?CVT>nT1 zW#=Lu(@xgH4Cm`m>WG8D;Uuj$GL*cc5DN2qKEg^DfAaE)ne@fsa#R{_Dat8LQ6h~c z#%yru5WHwsX2$v%u%io7$ik3o5I#VGbp0g3csgDN*Zu6jm~77i*o}L5Udfw7cgpyZ zx>$kBSISV;n*+$mWmD`M!Tq~{E;R5aaTEn^T^UM+{B$D6HJZ@pyzww<90%nv zgCv->7!wgCPxLB0qu)>ltiH-hqAy;asy*-hFUGU*7KCM0LaAaIa7qgpQ3k!w@4};q zWpwXOJCeEM0O>))DZ5J!WY8~Tx?qO}mF*J3V*=HAX*OYukNj{vh9ZYvC~v@aHUto9 z73!3zv6yW7S_^&eOTlL}4nTg!rzpM@a+um#<)D1F9$r6POVV0t;cos4)Zx_& zNXMDx^bEU+l#Jyf9uqCW?8F#)rz-KDaHD-I^;zptCS*YRENYuhFE0&e&_0&W`07fJ{HDh5X;5Ib*w8QzJ`>^ThZO9l=1Njwq!40Fk#2;vM`3$Mp>CX1QDnL0`mysK$x6zF+ z6rpX{MqV0M{M}$o5XSt|rcZ45%_L%K^jPhKAxKm`ks5t+3hFAWhDtZwDhDg5_izQ@ z8P>d|3e;Lkpl`EA47#XF=38aZH9q6vMx#V&$MJWAF)DN_)M-X4ZPH`CqHdDHU!$l3p(@IbuL8sK_&<++0&#Edg6qr*XkAhX4hu^`TJH(a z@@MHYd$dS_rYu_@hmW^rV4_Bc zgY7&TQr7CTiOVlB5iZ(HLBKxp5f#A1_^Yt~&mzdNSy?n^X-749j0j_fl&TUh@5-V9 zYjs(||0$EXrVS3ZohP}3%OI2qo2C^)uPSZ`{0-M}bYA3}10PJugP@oKIxeRM1@2x$ z_bk6HWZFKU`5A4*_<(lNGLKUffqCPb5$=03(K2`>m94bVcfKh9zqGY>j?y)&#kE{A5wp9Tk=Q+!Xz_Q=A6%z5`vn($wY#0(#p8#|_Vbb@4(<=ByLdqPGDpQR<>KY*teP=Fg+1Xl2t0?om8O zq{d^uW6a~TCc<@cm8AZRS*)3FFiF{;6kC3jLdu6DK)NUn4|Y5ao(k`vc#c0r;r<(L zuix^%!2ZF@D7DZfRN|fG@C(gG^OP1)&M}K9xEhRpks-jXP5x*eBW;D1mV2>Kd(d*S z>6Q)~cB~KmSa@EnJ$MjuEl7kJZ}Ga!J&7N_I>9O}8G5S{c@wa_e;gkMR+P2l3@UPC zCeoNx%!ZHEr@rr5O0^un$qt=6h{tG+3bByQ7Aj!O>5e^uzHFo7lZSNJ9SY5;-!EJI z8Ob7x&~p%UsswUfH(tYKCak10^$F{3ah)~Z!tWx0_i7wE9zO`Ql%<%p-03_?lca1RdLzTM1mhU8L+ z`*LtSy132eiMuk;pEW4oKRNJPFp1g}dxVLe(g-^Z&8WlP6f;nyM{!E?AITrmlQ8DJ zqJWt3wwX3I(qYAihQXMbapK#SyGRXLCh7{j4bm~qpnN$WmVZ z4)Z#$^OzMl0);UMW2U|iCE`QoGDFp7u^*+&h~Tb5;)t_1BhTP!p-(SBTw9EqR4c&K zvk`Bh`H&rtTk5N&BiBE1DAUT4xp?OcrD9tM?*=!}ijyPJl0jb}H1H~qF~v0=7-Nkw zzn<+NY^DjAmZVwi@jt1|0_^cy{qkjcu^Sk)vJqZb^`qXgxPZB|9>VJI-*g{>zV3Up z+&BaUY1WFaXQfb?vrC|5!9>x>YHOr=y%WNgo#QdaxPTdBY%%6wunDo?kT#>Kugh*r z31EI(jHMcv1v5=IMSLfV@`Rbt{t7EB^BzQ%iui%GxleHYZMiDSS`b4v>P1j#eqxv~ z`Xo8~^*55qz7M9!5j@5LcNxK$^%&E)s7uh3CC_-2>awdJ`!R`nYbez{F-)bD7%VC`egU?dUCkKLCUW>8$?4tkRE&HkWD3pu(tUC zkLkpnlQ3or#_Te>D5$wuPW$iBV>gEmp{M!!P#wcum_F>(Y78ugrmca{jXi#@=e_Ip zTM#wTWVgmV%JE4M%vdakVpi`Goy0TQ4=K%+NHc)P?8TV1BVq)T zmTaKodi25KeI?UnSq?srZiDBCv(O*e$M;V&-*^|!SN;OekPPtdDxmEi z$)P~84a@zqkBmefD%Nyt;sQ1{aX#!E{7+^$Q?=(B&O5Cdz+LRT5@}O`0 z-Lvvd1-L1H2irk;keggXZ?EzvdsF?G9{(I24c`3=xwx<#8d zUqi!>U!{AeSuJTctcr6uv#xD3WvVidsl?-_G|VsXkHwXr z+hMnL0`Cqk-Pi#dIQM4#iB)WgstO9XS0tqO847;buSJVu1?+;bl_H%6p6qR|eSZN8Q!!*az27oO;6Q~YEvC60x{^%d+Z!r7v_qMF;(C#P<8~gym1AQ}KE_l}ohH0?#}yqvXUJZY?PSJV zFQ=COk!AYSahD`IhIgPi40lM6!ULVUQeH#X%B%1#Q;6WeMer?nE&NsFN3X`w!p48T zqtnVWL*3_o6Fjr@^`E19*M#`0#)ZIKDUWlSib_0!hV z-)=9ZjwDD?ZZiiEp=Or61Lcfc8evQe#;g-+i}vq}MT&2Y*fhBxB9F<-*e8v3bZc@N zB)#zhLnUm;cjse$D{4!I=75=1is5O-6Te9@D?3EvMuvG^qCxPeeWfZypnjw@!@d#h9Y8 zqeN|i-e}M;W7b%9CUU5=66dX%O>%Q_TbE@(-HA-l&FKP%kqKZk$jegeDW6(4$r(_Um(f zbkS{$wJUtK-Kdy15afIYg0E;&bMdXaa@|DKmn_35 zy%!X{f1#V(Su+ztII< zQ_sTUX+6y1X|I^8O0UTB40&d}eI{dSlF6(&^^C5l`pFyg0xS*2sA0@AFDXIqste@1 z^+xQ`+91>uA1(G8@K)Gmhg-1-UxFu|4#QzGEO6ToRWTSAb-|sbxNYuoQq*bjhmp$C zBh%K5X6DM#%s2aBGVz%VGayNw#~j3KgE3kd^XOd!E+`*G<~SO$yU%Vz`iYU^C|!9` zlc5+k1-=Anvusdq?1CoZDFj7`Ky6hQ-z7fq&sb!yb&1K^GJrV2yr;LQcr#j6^N{86 zJM@T-cLHv+xhKKsV$ALEZ-P1lDUrbzBUV1A4y}6^EWST{vOxN%2yC}L1KT*f~dOE;-pVPP@j6K3LqPzsZ>}Dm%?k-=tuA;DVXFG-Xo!d1Hn# z^-4NK$nZ6^#||U*uzNCEvMxfLIys(beJupH!%k7S zNPjC#AiMi6v-wtCG>4fk@oW}j%mX~)AY|KcrggUw`@&uZtPdR#Q={C3t}^g`FCV^vk-K)G_>@cZ?rBq~4MwMVjL|n9a|&a$db5d}<2EoO4;ix= z-S3!%7j>!K&eNF6S=Hc^Ktnn1m1;Xt$S0A9U8x4O7lmNfI2fYE2Wi)WD70SVB(X|Qy7t`% z=inXiJVTl}cHSG=GHa+bZ7Is?-9A*asFhyjtwc2`Iq}jYNigRzW{vDrB7bleE!bwl zE(`WxUKbQm>InlGE)E@4NkiSHSm=#w#66-JD7{d_cj|M%?F@6?4QG~=I*l|uO?6_koRKSzfh$|?I zdE*9swUs!!(E?&8Yh3no0qU$@!tRr|p~qt}x|kwIEj;AMcwN6lzVlO}7Eif`H191Y z?IMkM%o40L>~cK87(w6wV#}FjNb`X)OFUY^?AG^#wJkd zQiB`eDKPcUQ)opjbT&D|`u;^!aP4XObxsdyGRA>ATNe)lOQcav?Gzy=P2C3`(~2>D z!vY0r*>31&k}2QsDEBnNaLbL%VY$=zo@mKE*h`x1F0q5&ZN1 z39PpArP?Nmh-2h!Qm4g_YQ=uFi(D<~|FD|mFdpxD%sY(n$~QLO>gj`e=NYrwt1=iS zd@~$g6M;1B6QJIIIw;5IgTV>t$_MtE)j$8 zhET@wa+K@jvw~et8i>Pu>EtnAF(&FjobbR3A7s{L#Kso3Fb%W;TN%3;bv;Xl0~4(H zq&_a(ec4?Td{(CbVp{lo0nJNV)E~Vl>hl3@bfLnJ9#e6WQjS-q!e>pSO`^8(m|tx? zM#_4i)V-=s;n5yT#!*B2Hd3~mXCg2E z0nGA2E2xO#;gpj>8|`_?m&b&>;4vx~b1mV5@Jo&fy1L(xRU9je-i99$i}%Q(zJ(%a zJ&HRh<9E+3eXqdLCmr(F(h#N4#(Oq(-xR0?-Fj4I$z){kVkl!YVH&kHNS2C;ucgC= z9^f(Z5@{x2jB%ii(AZE8L3-h@e^a5$c3yENwB|k0!bH@sZ8QOifr^$MRrr~P-eN} z7m~xQY~?Wo#`tBgA==c}iKdJ(U}x!Q;9idrV(IxAB$xfLY1(@}!QaaH6?ndR32N3= z{KE>D51kP`hP-J!n;p9*jCkxmi20Q)%NiSYk*{PYFd>&!cue6d9%F?up=UyfGktEf z+;1F#S|~=eTBJC^BUa#gOYK0AN>5RzOPD&9V0EswcT+<+VZU_*Am*Qq~syfoZI z%&@>v*t&KVs+K01n}_n4Gnw&hmDxCEms1Ow{5h6YcW_}i%-+}h>FJCy@8e4e86ykE zC|jQ$y3T>T8@E*~Wi!H@3qn@D#AA;9!feWHok z_2|0!D)!94b2Qjh5x>VQU|$A|7*plvCHRJ?a8I=O; zU#Ie*doUG844c!ZLFVj*^!xAO5G_99v#J;>A^4T3r8?RPmdPgA6h`Sdfx|WmW8a16x8L5z#&KsK7IJ})Mi0sAP;x* zPSN&?@@W4)9qQvMoSZBggnnqQpBVE#O4cS0VzDap1lln4!18 zsa6H{jf|z4aZzZslRq_a&R}ZI^&@C;XEZ&dSBZLd>J*Pj!CNQBWMj+?{TG5Nix6hN zy#bqc?lv=?HKuxc%^3^n20o;!RBH>P9+p6zZ$5Yy)`R?*8u-;}2G;i;((-}Fk=~yZ z)X(XP)Q{dUGRy5uj&Z@kl^WB!Cwx&(gLY2W3RqTUK&kLldR?AWQ z$~N+t<;^^X!I-a(ih`8%g$((}fL*y_lxSmEJT*CXG-H_50Da4F8;SI2e!eG%3FyM3 z!~&kfar|yjqxqG-^ic;XC(NN%Z2JuPHYd=L`SJ99)nD)+#gxZ{NHFCXv)j->;P^n5 z@mp=kHcP)o&$eEsEUvZFoHU*th5TbN_prh#ElT|nY%1&EpI2Y@$}mfJJ|&x6elgr{ z=WPNdXNA%>!@n{%!)4j8U#rQBSZVmYsl%9p&k2I&*+q2D8AEnqjxCzyTtsR0o}g`v z8=!K2F&L(>IPA~{YS#*QOvaUWV3Cmvhjq*7Z{O?5vhgEW?&mvTJbI>|Og|6~U>^uS zF&t)i3y*2W7^&1pf<4P+>9v)H?2^X@X#TsKl%w`)+G77BkarVe#o-CEX05zIbJ7g@ z_y+3KaRg*mBwgDSOqRT^V76|OW7?x)N$1ci+Pc}DIWuAok9i`&v}26dNfja$T_&_% z7_!uWMA5^f3)I()J+yQK9(%Nf#)EC1ZlSZi4-gbXT;o|yBHDAaai zE_e+m8#70cL!v9_rF+fj+oz|{oHX;WL1U%$V9fdD3yF(H@#LGAhU@|BeAIC85_NgO zDp8$cJ+$JD#kQvm_Z4^oJ|@>;)VW%)>1lze9-MN0VmDp+X^!CZRdvSY(E(Dn+80_K zRY2P}nurP!5FBPZb_X%04`X^PJ%~?s15nHxL)PX<3i_pao~n-?&tD3Q+pj>^ELR{y{ay4N0`RWO3g^-~hPy&A!0?tU*E9{)+mn*iQy z@Qpxb;XtW7W)8&li-t(yfgzjgauyYugi?vyZAtlAC7?Dw9yBg8;P&S+MBVfP&)tRm zu&v%w+!)w)61y$T9!AK@(*cGeg4(wqCg*-(Hg-tUH%-!bY4+o-6Jv&93^K4J@`@c% z)nFX9yS)Kf2eZ3DlG{%UvamZwn{ zJ~whDNW0{N&*WxE8L0+_-;P|AcJOQqF@(o6KbcuXF42l3jNVoc10g+fI^Bm!&#w5uAMtyaP6 zpCQqW{4hAzZiRP%%aDEH1!ylF2Zn)BP~7%{zp$$Z8&l_MBB+(a!qK_wSLrP~0;u2V zn$)-&hPKa*Z-wkiL-eBAfDPIH z2uU;N#I||k5jV}p_Mcpgz;mU`U%><`jK%#0IOmqbTy~yJ9nhIV-CJjdItEQ=w1dV{ z1zDphGmRE{YEA@?iN-rLmc|idWU@nr-=w~fN4yN!uVXHu^i_r8YZsEpY)>IyiyMXe zriKk@<6BJBifC|9e#OsT9TlZOX*f5*({;MunK+li%=Ebo+%O+p14dVx!;94xnKBE5>HQh z@dAb^_wWH??vS3bBL=FZw2`(jlx<(W^?XJ>1!L&q;(5T~#7Cmj?Rs7v|;7WR0gK}!p?*uUkUBDl?_`sq>d za2g0bM>SZBRsKlkUI^>=Vko;$x(CU|__MRu_o2T5t%iLX-70k=H%@zZ=J__Ttql#oy7xu&!n_6;8lyDpbA7bD|gd-f-$ zz=mej{iRI%c z4&y0t2hU+l-d7Q^^~o{j3#-rCe2+&z-4}?x?xq!Ux3%J3bx>HS$%jXQ6WU9sYjPWGI53MYm9O=~$9kv68$t(Ume- zzYX$Mg^B;xXqWep(^Md{!$aBCkXlK!|P7L9d|q{b|41>aTcQF3o3o$D<}ZJnROW7a?6G1VB;E^s8YW&|^v zS`FB~QE%8q@e0)0;6$cZqY-Wx-2kt3+OYHp&b8f;3vmjKuqmq+I;W0?pa(5m0rG(8Z8yg zB>6lAn|;?n|MgPdpfjqjLpL6-!L`7577$-|gEO<`!ctuK{$sTGMPN4K@6>}=rkoAddVh$GjP|B8S@B1PPcAr8Y zFKs4L-H274c!23Rlt7t3UBtBJG=sxg98-&nDgC{Ys%ixfuTn1&NV)C z&%7*Z`*=ehQyG5)xRK(vWgj5t_jL)T=nKC?2ZhQpn$xAxME7Yd_ml22K;0i+)BD=g z*?n!JSPoOuz+?I`M)Q1D@t^kx=+8J`;HZHa8UG=hQojF#=9K374R=f^D#k(k9zM^8 zlcs6a7m&wg^u|wyFsEZe2ppnCZzJcw$KQ6iGArgHAL3FRzmv<`@2MFh&_;mR%fd?!Ip#IqiTk`<>j1 zeoaoM>i&61JFITv?>DwLg}g5igqtvMmd0J9Y;Z#@mlap(`cKyc{bPa%JHtVY=@KjA z;Dk1M;3qZaWyEO2VXU6=7)+#i0I9%;TvWYQWyM?AhO3X8tZ7Il@-)vLpKObXsQvCE;4F@G*8o9TEENNuqR zyZH1+;@gh^${;+Fp0Te2qE^O&CywAM&uW6!hya){6vxx>w9-3$`SAGAA$D3j0;kPo zM4H`Jdg%~5*eGMmF31d{1FK?r%u$IuXwFHq=TEWs^et%Ra})NHtR-vIeuzpP`I_c3 zA%hCMcuV76qdwyr^*c-Q`0-TS#Y61q#f-Z15LEv0B2Qf3NWWKq2`le*)1}{o=;@?C zk4caOh%GUuWW+9E%x!<9IKz}Z;Io7&y0ebjMt0NOpywE;HQ+X_2-H#=LF{Y_2UleA zvx%~&6u=JmPpC6^7Im4dAlr2p(UpH2PUmSf1jAVc&{y6FA)8d8bi%|Ol9m%$8+$e(k}O`d5oq+X=^b?r+=hq{+A>ay3Ld=b4q859i_ldHi-0`8HdAj zQy>Xn&bjxS`hVncRZ%=Y-_vdJ4cL2Ek@8N6q;z%Gpd-%f=$t zt3N#j3*6)8c-~BE=Au|iX2VY8Fe#0G*5^kZ_fVu3uF0Z}e(dEjEdD&PrR~I+U6iM2 zyk|zezWIz=i(}Ce#7pe#&d>BJ?4CDAOQbMyY>R zp_gwW$C%?|4P(48rrz|ZD6VW7YD_a>oq}c2VACXVN7F>KX>tw}dt~w$E@opW zNahQedpAA<4x?~vCS{jwN$u}ggld-!Wi0ZhQTmIOsF+!;G+DKa$IQY90mcMj%(LmX zqBnkO=&ha!s~>&=xpdzU_eu4WHq(pvByz4hkGy9KWaCQWEq(ZwaO)YgPQD6jwvC}) z9a5xrRv4g+t*VT1{5RNfVF-0WrJGK9xRS@XJ>)Sl7;|UmV9|>jn!J{2%-*>78`k+U z;>7W0s5qny`Wl|{^KXi;;TjM5`(U-{7ASvx2Ig3i?%lt^BPSI;sP>af7f)e&&YQ9} ziKgrbUnS;qlRRR=ozXkVv6hN42b2~G--h)QMM}o(8>N0oTu?5SwzS}@iLzBbV8!7E zXO~-G>cTe2XsrO#kI$fe#7)S3x0%h|xQUH$r^(2DQy6buQ`Qpy)}u*GnqwBpVWvoq zwJeMYY#S$7H};RnEz5{iI;;vu&zFktE>=P|yDGsV{0ko!;MQi89j+y~i_7FHn)wzJ zzYB-4zYC+-wQs+ZTFHg9*N;7H*B3{mvMLFwKMVj4qx_gZ2yS4ErbdGRdh=+{tw!vD z#{EQ3-3@W$(S2mltx|A(@)24OoCb@eCy+F&3mUrdi@VJeVCF_aNX8@dImVpr>n>o{ z<@m66F>37EKcCUWN8YTj!$0_8(;4Mq489SFIB8xJg!WM-X7~~#Hm80TXiLY7&7OCX z+}oPxGyJe}DS)pmc2sG_cTgetpnEteW-koiGZ?ZzKVa4?tAP1FRW{nDoY9JZiw3n0 zVt@RY&r5Tuk;mM@m^|qPMBW-;+7*o0yd|EZtZgx3RP%@AGVeJPs2}MJtqUZ%>KaRM zg^_z1=m*b*o%;*X%139ISuS_rLey&Fta~(LZX1Hk%A?4K>aTdrVTp5lA7dsRT}|A1 zvV$pkYse;!j3mpxd5EtsG9#0|mhy9>tUs7S@dKPNmVTdK8%Kp==xJ02RT4}S#*Dq;LBuW#U_y0_SncnpN%eU~;<~kq zY1bV%U!dU*EZ?RKOiUqk%iIMnWhBVu1`G*kL;K@tKYr~j<^KoB0p9n^gFk(-c{$X02(%5b)j#jq8C5t#Sh0DA@Pvt`K zdImJKAHo)wYhZS;78#BoN6YUVhf3T1se!F8pe|h+)gReNFL#rsYW{@tnCaM{u?ciz zOy*WKLX(bSl5CAwr%CsioUe~jdDwU++vG7H?l#Mk=AR>g)>_G)6a%4#Nk;JUW`ki103eG2by}ro&A^rFtmS>1M>fo0`eo zwR{evn}#wz@0uW}`5L@PSBHa{ER_Cp1E(l7L0u0Eey^2ai61_Y=S8E=l5lFt)}d6{ zxj1C9CY!D~tw5bxAIf8F>UfOwqJdHYe-s3(d%c)5XN}l&lW68brWsYxGlNmPh(p{q zIS?^p9xnRB84z=EaAhN&T0XuSlnxS5t*pwpPYy+%`u>zm!w_m~e-c`^?;RbUE<;^c zl&p>YJszWgG2TnI{eNV=d0b837yn<;C`~9zAx)AZQ|g|*w`9tcDVaj%%u|vnl_W_6 zNh*X8Dn+U8+2=M0Nk~XSGH1@5>AUv6-_QH|_&t7qoWGy#)46-Ewby#RR^iD^U%KRe zU+H36GM(EJL_Svk7X36I<4EwYo2R}CtF^g{tJ-JcH1Q#BdU6jttXzuUZRtP_U3Q{1 z>lc#sF@Nz89EGCN4e5n9pRifUbiSIi*Ez-*FjhshP?7IUm$m9ASxpa+ZQQ??99@aT zB=Q(1Jw6NS$XJ|rzky>)CO*Qhn;Nm@_C5Hrr4cQ89)#YSxRCL!9^k+v|sX^`OUaYnz32{4;nnti_rv z%rJ34fVXW*AzCLx>?Whw@y&Y zDXqt}2AY#jh*&@QwKyyPpX`otvZytnJw4~tRWK`VM@O#65eIy>6Bwo&{BGc-jR4HO z70$A&^3%fDJAI}5FA9;}vNYm!WVyh8Hz6kraL^zHUa;{o_B)h~$F8X5p*pL0j4?PT zjxo+CnwoCK}jDf2^e?0#hjo(4^^c|GrAhlUxv6v0MSvM+7NgnM-9 zwQ{^a$WK^*+EWa>b{ju=x|?b}Ef7COpLS!I&9HSs0JRb@9h^tW8jZqH`!;>0XKD(u zD$9>pRZ%_;(W=8@=zc7~j*j>7j4uv&x&9eG5tG$#diunpHQLssZ{>MmOzd*;b&~`6 ztJa9#<;RO}m+a;*Z73YlfC&Oj{k=Z2sYmvq+^5dchnJ?JW2OPR|z%Kh*7;@Hzucym(NvHrNR>H^Q!8eV`!&L5C2!Y<8vpyr!B z!p}>?NoCkj)bFE{I8qixj`{q<%|m^}U%sn3=E5z$nrOiIElzM7?S2S79^x!@KHWrB zR2?MK*>jNnu0-5=1Loo2fYLfV8>wT4Vbie}fZ3UUjv*;4+e69>wxOYFA!34U4EgI| zLN0r!hz<_xIc6s8(D2d{0i*Hsk*ig|{m9~5AL;Z$fBNN-kz$njc)prrEBtsy;J51m zUh4zr{jkHl8l?v}?uQRrlJFxtiEd&58geaP{0=(8t{b|L5jzUSmh&4qro574(g359 zX;5$>EdmK}tKQv;3d_}IDSRLX_OlTWVNbB3Mk^qwpBv zhvHsC|C6pVBUnD+Ax^u!n>)j@3u2ZLw7P3b$c`Z-soo34Yqz4SVuui)=+5M*!CTSv z%qot_xWqAefGJ*;=-OGcKRP(2w{$LcCHiP`TH!HQ1v!ToV9yx}-p<2<+X|};uEJv( z0ZXI2^>oS727ThDJrKQat4nuYXiv;H8Iis@AH+rXhH}isGLBIIX3*ZPZV6|<3ob96 zqz_+nkxl+Z#YQs&R1G_G(y%&gxhaRMzS->6w7Hjf;xP?eFVpm1)Ny6)|ql>>v6-|C^k=lVu z9GCqb1m@>Kc=3qq2rPrHaSXeGnv&orP1!V8n(d!1%oi=`9er!b5S}aRjA`qU`vr!n zzsxZ;fayJw$ofxsd2y||lQer|6|&w>6*}%`1SXH0_WA#11VN!sdE0fP{2})2pNBtz za`ls!jufz_LUz-&8~s>0PO@EMgD&4Tq-xaxGKRT-g<~E8rt76pS-Uff#B>!WDWIYZ z*+0oqyv>Rd{2fbh;egM$4sJWr^6RliE_B=(7xUqcp83bHS~Rqf z7HUh$Rh7uQeLZ^rA{8@CVg<*%0?dl82V`?5Jr{f5ca+8?JrLTBIi`40(OpOy0af&a zud(03L)>CwwaY`S_nP9yuJdWKq^xtMHT`_TQJQ(VKPpwhuKjxrg*xd;m>;wjMriN>5&#&Q}ws#QX-#=1YfVt;LCS zznh~pG%1Gu9k*LiXq7H79f9YM8t%^HY+H`&^kEPRH1+vUQDBuMXIwI91=<`kjlP>! ziw~{tifS$y)6kn=g}74-(dRW^IA*ajfYKNZHU<|@$x7R9rk)Ot(w(42*@y`X6r%1z zvE}7uoU^+E-yA*&7s6OdwZ)ftclU%QkSzwQ<0aY2!ko{e#6GXg$kSRi9OUHcnta_s zNWXRrhw4rt?4@NxWCJm@0bu$ZI4vvA-c7qqc9agT3ZZ*?bXI(u`$f+Bp>y^WucQWzKxGEIqW+K-)RwOLk=S$|_PQ!hF+z|RL?kcWIeveOo+s-jJ zl&diXjP?L5O#dU#|YH4YsnshPCnHG*kI1-N&4E1Wkk3$wdUogv`+00FPT zTm{-$883bvw-S~0jv&u_e8V5QO+fE@a+{NGps#^HpUY_drLeKf=o z>~u|}+COvfe&fE>RiUgA1bVf>?pt#B1#ul*-0RWv*ym*<+OYV%7~^sbg^rFTv;6c( z&*7nH@#u$Q7x#9gcyb)axWU#5FU=7!KbjS8nUkXFX0VueDxX9m|IDW>>P+%FiyQLC;q<7>_(fnQUi}p= z^j}`bhqn&FE3R2mryen=aY-nt9cV~;mL5a{Zha7~x2chwwJSNMKWsLDaR-d&o2^B4 z1yiZ#B}d8W$#bf|K7wTa1}!ec&_N^5;x9|LaI52twwXBN!$ZCc)X!RntDhQEhxL2V zkT0{zRVb#^MC?Y>4!5OuRo~&ZuA?}{4-Nvrj0Vit;LIYId-ilgi=*@-R1%vfrV|#)Ct-71U z9{p+N$gR|z>MpmHbcc817;7cQA28jws1`n}7+1J(tCRHYQVM!_>oi%b{Y~!N7S0&y z0Yx%g6TK z^|(UgIbRLZeJUEaN|T9O)aluSSH$>hhh+1SPS_PkDN70nDFK8E!`N zZV6X?KwPeI0U6hvBnMo)1pkOSoCFsqtiiv0%tPG#JDvBZu^NGn2^g7e)f9fKJVw2a zr;8U8tws7g5+8W^8D$>Olb>%mATZ2m<*^pQ{x{v!WQ{${(QL>cFUERPr|rpPT3bmL zg21nPTN>P-fsPQ`d6)wXvjSU?@Bq_`g*fof1<5SX51nc^P;_!@miHZ;h_38BEgj4F zD!*l+#WCzygK#hoFg4fIWfo*Ky7S3V>R7Iho$f>t1BR+euvq9257fxyE1GFxb-olMEPp zzawrn@7ANQMov<@pu4i0!?%&LHw{ACuRJckh_is!(Z99WW#CBO%fVu3hS?r*LcIP` zgKTYUEu1!;CO&-GmZbWw6CS-t7Y}VH=9sohOgdm{Pk6iS`4){{c5{-(o{6Bp)25J1 zf9DHovtS|&9*Hw1!p;mY&90X@_S|`bhw84gFXGeIJ#cfrC-H2M3o3DOVx89nqP=Sx zj&$-97sbBeFRhF6rDX#~)!5QCyZ#_@y5}gxk4~mTy0#_>dtDKe{LY)*3!7fe!z@$} zo2-iUx~B4%#!3;+AIos>-Jv9CU>EdbTb!7y8$#x8xr`g;jS!vf#vt|yXu~G}FRc(T zS5tl$ZrXYT6|8WSR<(1WqW>+y{$Ug{vW58%FKw|u#AK{SkiGafvM*2Kp8)e0m?gF) zmKzhu%=^pH;1i+Z+mpLVjif@F5|@kTC#~ZcUuD!;2AIb9t3`)nQ_&R@N9kBX1f7v~ zK^oC#ol@iRcrXucL!hHeCEOINy-(pa0@KdfxW0=OnV7VfY~8vIm3_|@AMcMO9X_`s z&*q&HgBFEyj7kY#O%-6okDBsLBpziS0u@lOvFNqSL2DlCM8LI9*hJ2!5t2S>dYcM+S!JLUS2>( z-WrR{X6w-{e93F0U-$m-h_QV$g}qv*|}N+$W+-G1}B{pB=et~76ze$Bfk%vfbZ z8-5OwUMCKcelOOhoe5Rd?>6 z#xCz!ZH>J&_YVy?;W0SD!D?9IasA>b>H5IIQlR@hVVs^Nt$M63dBfw?U_tL$%oiBO zQi;(4%#`6KvOZb+<wu zkJk-3rx?~2qn0ZQY~=HnZ#FFP7~Aa$mt$)Ty^r%8(s0VWH)vOI2kFn00Cc2I5X9sL z`qT6#B8Q)$fOp3+!}L|~mu3N&JNIhJM4|^&>Rrd}yn!5{6v1~+>ca_kRL&3D?@kNqF+EMys;$hVP?<^_UAx>nN zv|=9F*a7Bb+jLo3RX^$zZ6{@Qb&^-s$0)Xk+3_#UJ+BrA9p8b+wp4KqJF{j{v%8EZ zwfJJg74hiX%3x}%K=^4-k*0Y1&|CX@qNkk>(FFy|`D$8}7-zujEj%H++HnqbX|a`V z9!x;;;t0jns8-0x{1RqEgZdfFgDtZhJ9n$Zcg-reTY9SUTtrZufO3$AEVMTa6cBHc!ivtzDEv zBTm^$vi&Qih*|9=kMMLcDefNE5kx#!$8|;7SZ#DZb{A@K#naPRE2jvpFFq>1(T_qa zUBEGBdJA5xH509JeJpDBG9aBU#&e89iJ1nNQ%e@e-i|&%$IZ2s%!U|9Hodpu9QziL zMK-L@rt2y_oVgnIw>~hs5)SB!*jyX~*K?CboE7EqXHe-dD1SfHBfUoMKnJuzvzFR{ zm}V(4k+4IiaR&bGWUvy;W<;wo0EYon*nghS=qOaAZ%cGn(?7+hM)x zadWr=*OVCJ@_2Phi;tlAL%T_bHtmSv&P4RNrBO^iu1ES7C|}xB*wX;B955bPmt9x< z+eWqK+e%I*I@0s3=|p~L0A*1pOFSZuP2?_$E%nO8V?e`oyr}hXoc7d`4i@5(X($}j z(MF`r{RAX>s8RQOfAPJ`OZiK?0y{Kd0s#{jc%(?@@O1iks;xA~*o2m9MiE`N@8Yzh zk8sGwv$*a@FfMsigDW;>@>_M*YSp=D15T)FN6i{SkiN+ra#3HCoPHCHod0RiE?u7C z6blcI*`>sU0OsP2PenQ7d(z!IZQ+IWqpcUE5u2@VIYzA=9AjgW@anUVv5tNg$FN)V zx_t?_dxaI%nmHVqJa8h-cVFQWP<^*9Fr>#xDLzuyo@2_2_-dj6vvJ3_qNO)piCDCi z_KfZ*e6GzQ+wHq?Oym+MMS%Zc;Rv|xfLnD|BWS$;j$d?nw&_nV5JU9v-%yD?-R%%+ zKhunkSw^HW%Z5lNZcj$N;eP|6dIDg~>~9n$?w>Diziun}cC$orFoQdJth$^fg*s)q zcy)LgZeI0{7ri2L`{Q+!YJrhs*x;cq_&X2oyJT zE0zsS=t%P{x`@~ROb{4maVdXk=K+&_I>hx=)ji?fep~6cMJlR(mqA{3+bB%1f=;0~ zdEfzAiltinw#%2l)u+5_HDtu#~LVQS4#XlVeT+27=owfH`tvhuhfz zFSNwgR;nsBMedz<6QhJsSzLecAD$D5UE4}H-K7@SoLYlf>3d76G9!o?)JIy=HW}Bu zr@1|idnW%q>?Hm=Kv!DpmMqfo*)sOh4l0A&YQTi#9dWHdn~;%*t+e^N1N}XE8)*zG z5SZ$F?QwtJYQ>}^9W6buT4c_Dg%$IlX4%BC`s951C}Gk-Px0p`6Y|Wv4>HI-BEIiz z%vZA%a!*)IJz#<@tqM;Hv8eZGTj};XC%M`9(d2MIi%_!m1fHZln8yOF6mfop32y#z z92;G(!>rY+<>dtIWi*+PYk9(w`NzZoS7s0c*;f3ec)B=$bT`CSb3(bA7l6^Q(knU^ zn}Ys4w~?&Eqo|Gk4{Yi)6Q!L?!pF|oVAoV-;_-3BPn0ne4C&y1W1$N}&?;*2pM^Wf zvagot?`5boz6mGy7uDnUJ*JEO9A|P&Pi3h7k-fCSl|`sm8qytOBi%8vpgteIi+z^t zN3JXP;=Lnm_%6V{v@5|s5Ho9Jr3iKp-5k<^9Pg1xUVaZkA5s>GTlelE@Ab6FB)#Qg z-&ZR*rb-#Aw*Y2+{L`XM-BVHEU27?{!&EV4)J^Hwhd{LY=RW-9sR!>>XNkwspw2w; zDA`|+St%lOye-)Y$Je#RThS}iY|*jTF0$xOCt`6gUDTPsg<}Gh!ENiYtyDrEtI7Qo zv1r6-YiW{NioA82i^3vw4T^)n$;y2l*LXBddWe&IjKdbi>AX3KnbG@hvL~I#hmkvp zi_sfdlX%N6kmxv@lkq#wh&^5?F$QL2zoT%(UdXL2@V4fKb{sX?yrwxgxL9@8;`8590u3qFAOTfHqZ(mel+X<;RTS_&D za!|^r9EILN=#Y^sa6*>}&TusnZ2A~qpKpN{yzN8}`Mtm^ ziqwfo#YgesNyIT(N{jS=}VxXX^Oz_F_f*!fl9&WOep^;ZA+5qs#e4BOKbw#G_?hE>3+gSW11+ zUrK(rTG(9HnMRwbNw)pfqy_a>v~YGGfnkc27y_6XkGy1qztqdiZg!Q<4>H6>p;?NU zZXSsFK(QVu_t<<~z4akped0L|xn9O|PuADDp==*oZ@pHEKX;%o$6SYgjO``a+&+TN zL9d#|-B%nl9u8?ZJv{*vaUn{!OXZZfb5>W$W)J+*!?P4=FP9_tlOk3-{|?th74W9M zX%nAd*K-nnky*>-*ze5Lv2LZY^l|S2RNp^OXs)ZJAEs5KKY!n&a(M=3t9h@)Oajcr z)`w)XzG~Cc&0VBx?)t*_?r93w5B7+aA~IgWJsLQ}8fV_&22CvSXr#AsNNofti&XG< zUrN)zjG}v@=14v79H3nm9YS9&`$(J4-IX)UHf5aV3z+)fXJqY*WpvHjF4A%D19YZI zl;Yz~Z@!udufR!Je+O1ezK-c)rRuxo>lJ)nn1PEYC!_fbSI{HNM&Jdd+0?r4Vj8+# z7pYC$L;X4h@YRSA3qYK<2rxabr^*JdT|{?Zw~zu`;)Jyc+ZF8}T^E`m)L@B6S=L;r z6+oBWu4`EBSp^Q7P4O}7p7=qDHj-4{h^@E0#B(NxA-#o)u%77ZIUQE~p|CKDboX96Q-^7o; z=5l3m?vx~%?U2o~BPLd4(ZMeG?JZZKUD99Iyg^y`6`9U4R!Yn!z_`8KC+l`$A6*@2 zAuaoTQfgYMsWAPhC$if?W}Bn6q&>Db&EY~!CX!`dLteWpP{h(rV$)20L`xSDeW!~! zeO?drW+E0fhQGmkE=f3S}ad z1#i(SFw)$qdmQ>d<4MV^4&-@gJc@r;C2khlk`d3MIc6OEJmG(n1ekv}N(Rnc8%Iw* zHkUj<-==xTjL3wahSX^NL*ATpQ|8E%Le|d1;xtc_68yWs6#wusrg!$IqQn7vNb%K< zq)a%1^6Sov$1*fY)&%8CYgA&60cN_(k)kKAq15A-xwLv#4fQdaL%u;55$l0srHCsQ zQ*hx{FaT&g%dfka*Hz(7`#rJsC0p7ta1R4YcxpEtay~1(VFI(zrc^}+&N}>9>-h+%!~~>azc7hH4O{t zh4C%4eECsw{%313WC!|XpaeD`DRfIc+E(hZFvJ;>>IP| zjGcyk(V?MBMdN?wQp%kR=$n?D1_-I*S+?j#+shHH7iWGD}UyMWQ#OI_bO$TMlC_ncphyPtU}&S+5;GUcYYyjSgjLT1+CrU!*^vjGE85$* zkwo$S<<$; zBa?qlCVLcyh+U>QXCCEpY!*YOsl_S}=~MT4VWq6=Iceaol}M}qVDWH6xqMcS!)VmC z<5H%(B>%biC|^w{Wz_i>Fwtq-WK%kNp^5D}OH*|E;KcCVWP6G#zk#ZAkH)6!l@*V& zAIrH@pV9jJJip2BI9NKAmw=bGDU~^BYl!2!rs0)`&7^|TG2$6C7Ve_DP8Hm z6O%|pvkl5oIgQJHjlz-QMc$kg7Sa|M{yoN(UaaCVshbw=Zs|eXVk-o3*?w_g*9D|z zcnp3UFFYqug_!2;E55)Z^ChLmdzg0>WDdsdw5o? zTf2#4Vqvp^)wlviWyjTm5z+DJoK7c6J1&IA*Ys0dxGwUU9w&Rb^NI&c z*jcDvJ=B``_6;Mc1xwMk@?YR;5ln3DyOMgGFK(y~=a`D~9OD6)p$V4?X9R9TGYvaR z)hjQ`HhYCDDoU>+=GtpHZa;XZWpNc=>j|6Si-YU{bOdZb`ri{>$uBQovUtx3^tp{0 zJvqvoG=K%w`0Q%2YDgHz{LJB)v4AO-B^TbDHVMhvn@EPeeNn&jDGED_)2L4U0#7{H zOPgQ<2SLAsJn>+mI>T(WG9qho?a8ox1JU@W9VwpHlX&`cAQ%7M6X)dxbBxY8j`0DE z>a0XpNyP#!aWj^V4L^vy_U0<)$AD*g4Yi7#$whe|iJ!=;C+SA^*mcJ$|Ene^9DCJkAtLqq$w zLKRWtP$8@a_Ozvdk*-_He)KjJbh6q@wM+lt840C|ylxA4;^A5Rl_wsqxsR~1Ei@}b z6_>51c}On47vLq`3m7ITGRFxMbuDPa6fJPH(vmc0ccFD#1_%s8;C};{0Kj~{xJ7pB zyCe^{Z!c}S)e*0~ldaHO<%ohFm*YnHckDVVAG3-F>w(hSU(P=P_cCzuzYdAINr;r# z->>M_P(%9ptfMsc-!A0qpi12$rt;Oy$>o?}z)a0QD(f>KO`KQSP8zWMJ?{4=M`5&e zHezyY*KyF4yuE-=SIC&&09qWF(_wTU$EByh2sc%HPG%*gUZ0C9h=X9>b{-OgwD`cd-^%HJd(zA3UNJ<-uNv8PGEEMaaD!Fp>&pNDYL`e8|?~6jx!dn~Fzw zIF5b=$I+NlPrScIPUm_0(f;GD(YqC?w2B7t)wC!vsepN%pDVk6VgcP{ZX|8EnMKzu zh)@hO`XFT3m11|TTX=8CJghP6(ti~X=A1`+4i%)okb4&;2OOpd;+S4GJs&_Iye9%z3 z>7^!Fml;Td7PO&}j`z46yJ4O>wxF5ZHiwBXG6ldu#iM`wB=PyaD74xtnzY)gPRtCK zqaoGl;xuUOY4tUlW8&d=0~tX%V1isq+&bzWq&vnKN}aB{ON;gguhSHab>eB6nhGcH34`nU!O(Qb#$Jq|N)yh;Y8(hdA;FdISi=EgJ z?>J~o)nqBCi*GC`?`=xPJV-<9QqGBHFItm#m0^4}R+$`A2N(n0XGQa7hEnTrLn-97 zjx@28FFEWwow8B{6JON!o6K9SSaXu44WL)u#EQKm@Qo98G~?QCgrdR;KH7-{4>^du z$3GHhZGVR?#JL<}a+YJB0VZmyr~K>?Uuw0_P*T6}fKII5MJ)Dz{!im!IVA)S=x`g? z4a>wKwhwVo%L6<*GzkBBVnO|Tha&OrTrv^0A!=P?k=HME8a3uV_~0Ur>2-!<-UDVp z&1Cu7$Gzy$T0`l{?oNW)u{4sm=&2Z~r%XKj!5h-l9O?y7@n9Hct>1V#0k3m%r1yV} zL+yn=-VA~{5)H>&OyUl&ZT!%IW4EoUMJ&awE6BrjE--X!%xj!cbOC$MsmEIy-eAw(Wq7AmdpgZ;sxW2sMSA|; zUg|!7zF>FPhCa^@r+JMFC|gar^1LwyOkL0P!VO2p3Zkcx)ay$})GFvWnftpZuXwOd z$O#RX@!b`0`vh$XIwc@3Z)oJJxw+}OIP7|!?0vEpji`(gQ5$1n!V(>7bLWu!&yJmL z4AWM5-gE`b^RQsIKOVP*4Ms-NvHjoB-tr7`%XX3A*?gZT9;{5n;6r`TVELqFUAZN7{*DN6xsvk+g&x8vD^Zw zd^MD0YhI&W-BXBXw-TABM>VuuABDuQgsUQu6pw>+;E;w;opp3=$vh`LG#G{kKMfW~ z9eN?}wtY9+y6U(TvgxASu2sB@VU8*9I{N`;_at-K`Cntvo8^Yml0jzpx9%Qt;^%(#7Bp*R;#~5C2Rrt4J)i1oK2+psWI5`{65*Irdx7-ixlkHVk%8{@)7NB zJ8{fZWpIlCGiijnY_H2kl)TDND%*Ng@aY^z9Cv&c{BB&plf+fnAO7<4s#-i_>`?4E z4f;9&!y3m@J{gNwe6-2E@X^B0y^F;6hYU#TO?QMs^EmNeCr#x`Q({H{W~|Xex5!^H zXw+mwDcL)cRxF!Jh~7gX%{2qJo;n=IeNZMI5y8edZ})M2{osG#BGzi^jtiELB!x$_ zh1;#u#CIVxNp1H~d{8Y=?6c+r$NYdy8e-@PfH^cW)-A;>6^Ty_q{iAa^ub_N@}+YK zGD=Uz#~$?HvQln9s|h|(&C0}s4L@1%s0;^Mg^_Nu-sq2Ggs3uW2U&j>ydivgh>tDd z0uuf=JK$IY%nZN`$t`ldb@V7&GSWcWuy_HqOb->Rb@Pz(b*OmQTl2(&sUj{~d_Z*z z4{)Db`>b>LzONxU_hvtNrxA{ZI!q96dc+WCq($}}T_UDl-NG>|l`-@Jz)X1=T4d4h zFgkHbUmDy~Wm%t|6w1c-6-ke=ADiB3ZWC>0Jh zehLorUcoa0b`RZ6HUm>pO6~ZyY;2?n2gaPKjiuXmu8@-Wh&$d#s z(?ZlQC|OZ2&p>Pz9&1Zri3bbSS*sOu=V39lyWd%y9@dE*@8wLqUiU}-^(J)lARAK9 zs87s4KNo+b1#pa)5)%!Wdn;3m=6ZKUqr7yb8u<~_-zrz(GA{~+w1Zg@J1cps6|(|! z54^||57yVo5|8=5>Llw}GuFv%k5W>s=%X#dG(H$L z##Z9G%FjIUU}Yj!BVZFT*=ktgk@szcl=lrw`uA1|nw?E(mkeDg+D=zmF|G^UaL|Ec z0+pCEfSI_}RuSh^DXarWqc|`EWciKXf_y%YfVEovFY#clR#spZ zkY*n&ZCo4XcJHnZwRh+v^~{b$-*wy46th^4@yOz<$pg%`pmnlCk5j~wIBn^o=`WP^ zB3BVnwg&kj@KF!^@L#JHYaC;V2Wz!r2DFoVen&4vE6F8rJ8G2}D9os>r8^rckk^|J z$WJc=vzKP9%+?fuY4O@8Q+H9PHfGwAZ{<$G=Tw@ab>~66;=$~6)!??nbOo4d!bpn$ zB_3=%l~2}J^v1e|PT4YymKOR;*83BwfA^)7u!Vox@IK4 z^sktX3>Zf*1zV#oJ=3Vy#SMHlz2WqPsIvwzcmAE0*?*ZwmsM*@cbE1O9=k>;p6xJ0 zEb*AO^cEP;{r_97`t|97OBdQ8e8-0B39qoG!(6n|@T;hF@nHU&O_ho2GzQaWMY+rB1f#Pv6-}4%7S$Y|>#Dh7*{x9)pvOSMKX8%Mpi@FM1 z(2qe)Zr#X=ncCRLqpxgj+%);bcjvH)+H8(-hNKWy^9nGDw+dyR$$RPhO`4KJ8+H2C zL|@T)?>L$1CYW^bjq+BjjB~j-pZwdTvQO*t#xWy>GVx&I^5Cqes5qF4tKH6_ zps0AV>yIH(ogapBn_i2f=j)NrK1xi!GPu%lwSR(xMi?-Pqhpv3xPOLAP5QkO!(IK;DF(vF1Ry{MHW6ou8j45COylmtb z>V2uncMYl6bOY)5%SclGwVB7ztkp`bcpC&#(D(xR4U3@z20g(2x&+~@ja}%$C*kN? z;XF8VbVyuEEV62+P7@06<39*zY?i<1>;*oyfykv3bosfZ3#Lr@s+@*&HB5|jrJ$;~88G&{3Y z{x&KGCjZ(d6h>y`r18YV>g!4z zcUF#b{A;m-j>R@zb9oxY#O0B;$3*KNYGjsk7vVwTTJh@*Z88T%2qiZTiG$iIIHsc# zvjs5!TE7^S7!`y5KGl#u1cr)d9?T`96yTx=W(;grL?cydJZAfM<+tkIN9#arei5Gv z?2Db>3@7ENP)PLJCHi=eCv#io;eK9A#eV7Pi2ZM#!=2<06K;z+f6(>y!B@ydP(X+fbQCty1 zjvTJS-B0!thsKQM7-#t1045GFBNmz#^#ak}vzO}9V9Qfto{9;22V!%Ucz7)7itPm$ z_zeC6hcA9d(b|dpGKIBT=?pL=f$tK?AFn|4<5P%OF+Z9_@6;dxXJSMb!w`-MfXxOl z$$*&?ez_>W?-6u!k-D_HeIONVG9=HBamcgJK76de6=zI_vMThd+jZ#(g64y~2Z~u5 z)uh`J!FC@Rc4!llFTE;emF^<3dpeRGQ)0#9_&pr6E1hG~0h8gh8o|slC-=Gg8C3p2TnfVuX*DY7H`(-x5LPoO)G;_K+RHk+7J$VBOFVobwPlG1!<^V+MwWl< zOYRwsM8i9o(i47m#5%!M5V~9UY=fJX$O(_>7fIlWhF1 z?ON$w+s%?9|D%vG#*uofkCZkyjFjx2x1q*EjM1-0UZ@-}uyxh~W^SKIw^pvbg+rHB zq+w6~;HGJ%irU&BZa2l`*iEazKMfkkGR`$}$uAq_QnC@QSfeLPrY>I6kF@ndw?h_m zYGns$C_F2USkOq17=d9fp5mBBz}UC7lDRoV$SbW?q)Tb$*ltj+Lh*72Urn6vH~#Zv z-F7AFFS(sAt46T_=~}0~pl%%@{m$Pi`_f0Bj(kj{{Xce~rEA(z`K?G9!=xxr&$oc7 z8N6DyAw6E)HsK%L+X1F0pz{i?L30tCO=N%OBTnm9fTz8OvB=M#a`6S*I#;V4!QGzz zMk9CHNl7hBQJ>a!!Wo;d)Mn-_r26(P+B-EJGt64$>G=&X7K**H25%MGaoJz`HFB}M zY1Q^)K`q*S zEgZ^gc5rcdU0e-s>T`w9z{=Sdx7%?Nt!;OZW@~!jpsJfxrn`iCJi}=Bk{l}4t>LR_ zt;Fa6#=8GenZ}gablmG-^v>T9`G}r76?+^yBhSiWKC`&}nYmc!9gKL}3KJN&U&T7! z6#u^9fR9}rj2^~xrl+D`;HCQRP!j4yjWg#6VW+~8jj1YOtFcjH+5^VBK1+6sgwbW| zeo>2<9BMFYy5d6UM1l7X-nz_Nt(r%RI8O%(UK%&JPMT>v$_l~61PevI_jV_R)VLG$`riqy3=+TLannK>Mk;K%h*x0q$(#rI9v{98E3>`=zg zc7RFizeDz|OA;NE*h15u7D@g6dr1x*PKl9+;NK2zi5IuD;u;T@c(95G6PGKhDf0QZ zOT3{Mh5RS&CLs=LWM03S=UsRsUJnogC((#ttJ^>r+jJouysP>F$^&Mf}@Kf zI)%`|xj$)mh?;ce&Soqp^o_0io$3|zN} z)w+*4CTX`)Pw+feCEJ+^cl!ZG6y zbIdfr6czWDuW9K?7v%q>K{ciFF5}Wj+%_*>im*4$!Y!{3{C_ka%ubhSJltyg(0T6T z(PBGiq7vDJ=W4A)cOJHDmq)Q?10z1I*N7Q@K`1leqiIPdbA1K_e>8k$_b< zWV}BOJ^|Kq%ba1IS1L6gOkB>)OjcVAqC+e?q9+LE-M};H`%skm4#viBc9X7dMpCOT zlTe#9zC$kuOsaolkvMP)UH zw>iCS6Gr>pu%m1>dm-e2V=V+QTi@mutXei%*x>M!YNO@i*cHc#aeSIk_yX>0Miszt zt*bm1U_Vcm-?)PrJsaz0Kj4FSF1n9wy=pfa<<&}@*UnN{_Ou=KSl&i#(f%T1n5oLs zGYT+m`oy|D3%o0|i}^uAn(|P_mJC81A8?HaYqer?JeYvl|LRFDE@vYtSSiB(>EgJ9psgCDw9_e<|`KZ7!OO%)dz^psbR_52LD{4^tLEnvUg`bIs ziNoKU!i0com=1FkM>dt=VFT}B=iM-C1?Cj87&_@(A?|Z9N6L~9N7mrgWp!?tJP7Wi zudGj(G+P;n=?>Z)GYbxBh&m4g#&mUe*(RuqjZXeX^&hswuNFp;M;mVnI&VsO;!*8d zjGb@a#go(mxI)r%6_i-P2Wp{>hZH+)5AJ{AY0;YWhlMjfB;nv13u(lLJz{7`A%AK6 zmG{sYfLXRzTlT6y1gP`A(Oa9U(O6k1Y24Ertyay$$F8k{6^K~x@IAaTXDClR{)f?c zGEyu^)FS0CKFF4-EE81|^-10AOM+ikidY%;f@5@GhlbUh2Mn#!l#QPoi#A{VN|XB) z$*Xf_5Qm$_D5ENai_6)74K{L5VQ-9$_N4Qd##*hehj+lcFAXIx&*uq;TH?gaXW%w6 zemkDqX_IL5;vs)&bxI5c%<#qU+?+g8QTX;R)O=rqcuzx>s0PNMp!+GBhxGijZ44rHHnU2Hb=xfiOviO^qx%i@Htt}rNrsn$qFM9F@H61wcU#r#eZ`y=9 z#*@lj>(TR};o?A*c#^K7M;=?w5Pv>e%Q1z@PoNqw+w#}C4#+x;&rK1N zRM&CL6J>B)518#!s|z2!*^Ba)ex%hWy3$+q&I;R9xF>^`<}q~@Hky{jO&Ol8_rNXo z>0ErlF7JQ(+mW$bx04&km!Yxt+H_yLV4{1YE76=-EM{!m#xWtv#N!2Eu6lPWnm;rY zEen26GfTA4#EoGJ^F9@*S#}cp?b^!|52hpV*s>W0)MWDpe^ywD^{^xs*JhLXb7rCs zRYp|hln>b`m=p8i#iEO95XbC=Jq^CJkAQi-{cmBt6AYe@e@m;AhN5znWJR~CG*of~ zq;b%e;141guKEVkIn!jN#)Dy^-?t|Vq+aBvhbt;;-I<>Aav;(7JCG-PuZSC)0yyS` z64L^hf2J{m-r8HD^q);st0DpUuFX}n(+oqaSN^|>2P>>Fr#?2;jm6L`Dcn9zl?2^s z!YA)`Lv>?J>6KyM@%x?Hq;lg&@pKH~m<%{QVKuEMLifY0?QYM$T^EWbzNY%}mpH{< zQY2SL{a5i|=gt3Gt=PcY|7kpijtrKDjtr5OOur=DO71}u-i(yey+=yly6aGKu|=@@ z386Z~0cD9!e`F5qldwX!q59QX`5in@SJlR97L-M%G zFQ}eHd)(>jIYsmgYvg~noV!{v8)}x~YUsV-i3dw@GZXUgTNp=`_ZF)_#l4HPXYpB7cDP2Uy#^!3cUPjq*00gk6Q?l4P$k9z zFl&yUmHDc-qADuSX}{+;1T~K%ihnl-@`{K3)@Qisc`_~;d>6l1{s22}m9W}m5SK%i z&~p4YBEPQEs&0mK;+grS6s05gX)~qdMToz&5z63p0AQZPDP#?Q`qM$rpVG`r zXT^G>XhmVv9H@ARI47eHyKV^Q6%Vz9+q|~MG#;$gYQe4~)TkLv3yx30Z)fGvcfNkK zsQ{stMF*%^pD?}}mPSE1NC0!-xI*R`?nh^DZlnvpg7d+c2*nre?kES8k*4G(K9)ZR zru&s+@BB(k^TBJqjN-(#HdvZqg2tcxA+9U=jP;KNqG|u`iaI$bgj-7wBbVMcSsJT z2{v_qufX#C>lr3O#5fSllZKlTxvvrUtn4XnxxN7RPgjxEdh1IppWKC2V=&w^st+tm zCx^uUU-1Y&odcgtD*?hU7yj14p1@Y_ZM-ACRe?& zRqzwsQfVld&R>RlDN0zy!&Unn+_1s{YN%DQQUu*~%0H-v4tHiipD0~?G9ViG^$bKF z&YEa)Kmurw@8s1;SJB2Z;v;Z~d~e823nZB6x0=#zZx-XI4Nq|Uh9N>l;SqFm#UoZD zpra(6p`_w*_C9O1qQZkVDqr;24}0|+gtu-C0GsO9pcC)9qp6p|0N&9J_tUu#7i2-U zniV1@j9|(VIq9c7W9)VL2{vq-#A|I#LmB6q7={j)(~1WjVE%8o-1_HBs9PEf1Ix{E z$(s3~ZsusDL_P>hs@;LRr7HgUgLp?R>&-CoA|{?-^hO}*e4l50i}q7IpvI6p(JLS2 zs`V6CLxhJd`MlLPzlPLtjIPG>{s&h2Zmk}RHNRA*AVA;_Ek#1s=Nes6LJX5qo6;!CU4Y_y%9 z;%e_Uz}-8ICfH2otPhI9Lw9Hei41x9Z^mQii#O0RNd{BxRPmf3bMCO;K`e`zjf>lt za^HguarifX9Gcp~Q_N5Cds9d-uJ3U1^lwgF+lZ(5RkbEK?3#`WasvL>YDK&u*OAjf zbIn3#-0Yc2+!RSE!Z@>;#l!qY6Qs$0VH>o-ntqxv ze&|WQ`dXtjzTO`WTkr?mow-4JwKkDq4vXh$HwotNXN3uodPBhF^G~p3UX~=cetmZY@TdQ$KKY z*Ll$uvhD}{>PN8s-ayvQL)9A1DGbY>46m8ZLARcib5Jpm-;}Wkm1?=cw~rk7*{6Q8 z-$o{4J`>CcWy50g1Igf24GG}>JQ^oB%cIh&wV+5V0hX8Pv#f6_JT4B9hg5h_3~ja2 zcCCTAB*A2xY$)if9?ef&>xUNA)W8RGO?Zv!C4fE9qQ3bIMtHEiaSTzMDk$h z0%Aa`JdkDK(Job8(n*xF*BCvJMWTz+y+F+@pVuxuf+Dx-qR%<0yx|BRhH({zhX%pS zR_-d5Q;q^xdN<(U11ZvDG2>)od&IE*w9mgcv#D>Ie39uihYkMI*n_qOxzM4?47F(o zqD`ANfuRj=`H$E3pxLSe&|#|*{_b{nhFL7`q4fx6U6j1^aW7vm$^H?36geEcEeeoz z1ZJ^TD@*yvf5YYaz>m3FQ9E7cb351=EmLtuvuYiHVP_v~F=QU{>8p!Ayt%=re%;P6 zd&rp$dD4ss#&B+9@lXGSV0++0Y`%9dIHr>*+wwFVWRWVAWkW7&wW1wemPIGvy+5SR zRxV zH9`?JL?~dtL`=?dG>+vgrop=H@nP6VI zpRs9h(&qek-@}I2<=~|grLx(%#{iAoqZN-L@;^dbtvbD*!O)4fnDC&kRx_-o2s5l~ zgx7Ev_ak8_mQ|?pEVbP zIi(&h(d+1n-#6aIreDi}?Zz~j+7(~ssQl6Y8PxTPXRTKM36BRMHB5LIg(<=NO)6KNTP7vm1}89|qLd z_~RT9#8z`u+}yeo%-6@slDB_c@WinC|`ii<{tX>@@ymz6zLjeG@ufaS@)$9R!-sN%;Qy zAK}*GAch$vt|p3LnpD+@v4IC#!IZR_X2aZqIuGbdn&M2D>~^#hs%9; z=Ro7Dl|a&x!H4t5z~fP&s9wJtYU16&(KDI+)G3N+lSvrEY!V-VWP*8pMrJc2E(X`v zRbr*TBZVObq>8@s6HkKzXhT) zdrSzho$`<$=C6z%cOGMy(d2<9Pg*9y{Ds{L)clWPpO8x2oZBY!sqBXyHfXWoa$1U* z*I@=-CX%jh(lxXqypimu%V0>^5cvC(Hm>kF0T#L+LqpbRqwc-az6KVAMNvpyy%q)bdn=AByv>F>UXIYnt%^8ToMU_FwAwo` z+k8H3+hl+%=SG0@KK^J-WnVOGe-!w6O&RCvzk%|xE)3I1-q2(frac5{3yNuTFxgAeh3vW2C7g_3^5xN^IU~#<|`U+;0xWGx$=+!0=*0tbOQr!55(%R zy#)2xZVYoy#5^aM=G%jd3nuoF_>Zl`Q3kzmNFK|59?L{26RGWq04{_nXSPjQ74E*rcF(#OH+15bfn?h!qvYc1`JOMp)IN4(njU~ga>W4(&#ROqaI!55BL9JAKy=A`(&`A#rPxB1yPC%)n~{kVp+r#}L9^_l2>jRK(O z0yGYh&UieCu7{!4r&xLQzlw)rzs;anW)2|UWn*I9PEtu|2)FO%FgEW=6#*T- zxTtVeSX_PzRQx%}8;=c;Hr~4fjHV%(3_?!?xFh+YduF`vnrJ@y*q%d##_`k zg9+xtmUlLKuOmTAXF0yTX|CjI)^xPNZ!M^=I}Ovv*fQZka|-JwYQVJkbXJO}A5{oD z?vR#Wr#Wa+slfSPI?bQCxfbQkh=$4!9r+1+dIP$eKjKX@p%??1jd$q@u=G+H9&EA( zPpkU~%iKdi>9hps??DR1vEp#~6TY1dm%DavV3Fbu&ezDlFEPs?d26{FkMc@I!RX}P z4^VZmIX`#lB8G_-d!VccX8X)Qn_+iPf}TdD7?Q1AtnNBID-#1>xoB7$FdXiz&u8KF zG*Udv{5T9v5(73CPVa>hKSiRDrh~xk&=LOb-UyUDO#@A;S;9a6x`$z$MMVGzW@6$5 z>zQj#fN{5FxN-GVJRCk2sv6FKh+{FVOhgTu=*g{Sn=Y(>DGry@84tBRL(mJYV<_>d z4@jPp%?FJ?iWL41Mho6%@%7#P7zUEJ0NJWfCm4gc^rFXCBEZ*W0?z%^h0pP@ktOWS z1Nk+{@UzKY=y^03%3o=MtITJ^UIS16v(rtVGZe*4^+w%0*8;zkKm6UJ`_Lj^12nPj zJiqZ|Aj9N|duV%tX}OS4^iIheELzBuw!Hx$eL;|H_=qxK2hKpx$8p3Fj(87}iif?2 zABLuPZQj;dDSw=8_ zQyU9yTjzldYl?9W(K!Q#o{$-sCNeu+-{F`3&3Nc*r$B2UFYz)5j1LYN0aO1c%a5VRV?AU=2 zkmV{s{hihShRYQt#n5G(I9yIE9;#n|Lksm8LMtBjpUIyjGaj^Y zj0z7I;{d_M*jre0;tZEH(-IpDvJu{<*$6X^kW+TI4(`!42VgCJ2s{Z!>(Fq?Cv!Qj zS6Ts9-}w~8eJzo#t8`@*4{A46I{p&-ZIZoOm{T9c&|sSS&69-s%@c$^mkx37bF{Fw zmYnd>MNaTB7=Yh~|CLb8ZV}^8Fz-4JNLqs)NfSdZ;p&Gfu)k%VtRe+5SF5bjuh6dS zGIaMRF=BmQusms6@u03&A3Bc#$;X4jPhEHG0q51Rzwrp6;chCJezGfPqSGBxjJ|km z7fLVzRwpITU?y)8cM<>U-UDVP=gG3J?f};AQj$yfo=itxA~iOWw8TGQtyWZc#E_1N z_zMbfo%KM$`=T*4O9%jGM%Q757uP}cg9pHN_c?~C5Dy{a2akxDHYYpu6*%yWmSAf`5hQ|db*sMRhL>Q+O zhX+bx!5OkISbp3N(AD^f+rc!7*(8;`JYTYk*O+564GHs6)_Y)CX)4G=fC z*#wiEQYcZv>u`(idAw?fHSpQ!CzEdO%Q7TQp51{;c1|#Bc{%)Jbc4mc({$`LKL?Yh za#e6tCWmjTDxgQ7GeMJ47QaL}gj?-)2ZRE3L|4;8)HekLGqb-;vdT6Pd*$TeXwzH# z4gX29OK;q{{K^|JxO)Z6^ce}Qi;JN0*)j-j-yvQ$7oazO53VkbmNXAcmL$cFL_3^@ zL$7ChxQh!%N!IVgaN&TB4DNY@bg?7bEc#?K~Wib{=mmc`vLgYASNcB+g=S zJPdl)3y$^6hhVIfbwALGM_h3!aJ{mIPc$$Dia)j>y%9w7NDM%|iWk4~;%{g}I#%gw z28%bXimv8upk!l19G3UW#rHN@2}K2=SkvSo6CUwLFTuF+U77H>=O+q}do{Vxczqdo z7ahXy8yO2CazoJ~PX)AboEr$!E8&BeD5G%uNQO}mAAwqe@%HQ{c{L#h%W87)?G9_f z`&0_-b4P=yotT&JA?dq5gFjGZ9pET<_67)!>zFCgPx_i*Dn?0QJ*94z?83rsq z`61sXO*GRsl30iI!qZb;!(k(x8RmhA`A9H-Rfb8=eVmKe=Hy_*m-p}_uTZ49<~Y+g zR7QQA6~N8~{tFOPE+?5dhQ2WVu{Itt#dfnnZ@ zJy5?0#<>rWZrD2zt9;DC_imR+yOo?m*|tX+hE_bN#l)iKCy>S=QdcV)Tdkj;0Iz*E z$F(ujz=g9WNQik3yKY(u{#fbYr7OBx+EX(p@BJGiW0dw(ftH^#resBf~wxQw5*d{&oITrk{kl!*wHDGb9u(kK6_l6cEpXN zm>}}+NmgS{FkYw3COnmV;Br^w;0wCh!0|^W8GcRUKI%Ur8(Ct+K(_3qA*3nxQ99HJ zAo<_)A=~u%#y1hr>}fZ6e%5~Jr-y z*|aVj0Z#SE!B5`#W1l{8NcrtVAn#aBdN&eCz$5WVA+A=oa$)czy219)wBqr;@+2{E zxCK`3AINVgu;#yZ`w4tkM+%=t81a+)Ent{TadT@+Fc~P#=4QSVi2s(2UsUVEM~=a$ z%e%RfsxC5kuOc$k-I2v6*?;Ix5XBr}~x^JhrQoJV5= z{-kk&@B1i1LT}n9QFzQEm_I*9+cahR0+Z@&oH1Te;yY&_GI?0exja4(CzG5amqlWL z;0C#gMCauG6CUrz>VPg~+GuY@3^#EDF$m5ch+5~xf$iO6`KdC*R#Pkrk3|GCsjkp^ zj&U?l_sYiZg9A9H6Jt?*#!_H6=Oi?A9?x8@Xd7Hgg%)%nC2m@Zpmw?+ZC&B2q9y2L zZ8i5fH=MVcz7B<`$HF;j6Zn~0eE?m}ZE-cL23PNG)EkVlCP(HEtFiOjO4|!n2 zzcXCTFfYX4#+6`#n|>AX{wKlx-dR|G{S5r$YXP2RoCVraBB7y!Av=er6_4*T$bpxF zC_LzPP)%QlbO^r%Ur?OTnTJiXvZv^|=C&T8=jjXTp&s<~l%qBTJoC^@lL4xs5mKHa6gaPYWr}0y_%hFWYB-!lhEKt;q zgr6ksWz9)6a&OJjB`jlwx?0iZB&)6_Xw5TX1tzxw6hBbFp+|P1A3Fx4=1I4CqqBYt zGe*=mK?Jj@IIH+A+y`_fox)$EMuCdG!Lpx{V&JKGmK+HkXBgVxAKV@UTRxGlRpM%8 z-Ej`~2r)qTh67sdvlv)k>yEF^oq-Cb^hcL3-{udI8%ZC5lj2rAf?&>(f9X)?nLy6@ zB<|R>1H9Hxm5r?r2PSJsE)n@(_|Hx^elrOZtP+I>)i+b?G|{<&!3Yho0XsMM!6(1> zM|1r(kZ|`UZyT_YVP1-@R*3{7SD#oE^}Y{im!{%Fy9&UsZ5L%n^1?yArHr-2(?BOW zvEmdggYF5$p@--j+H*Vf;$OIU`)%l9qz1C>hTy0658(0_UC~rOIdY6)$}k=xCWBxU zyN|Ik-Ji#~{y2fPy+4Dg<4a^~GZO%9i7&d=#%gP{;z6C0{`0w|8In=gy@jajn}oEw zY%aTY6h1kY6NWG0gzdVT`1SWDju=CLhoU0LBbcqfpV)Y{-<3Sum5gooJqD}uN@US* z{6Nvq8_;RZ7q(SrqEP(>v~IouZ4F4}o&4Wy^cy2=^fMML$1LIIT^oomSAWHSdVa;u z#RKr~gj*7d=_Z~)6%kCAxzi*IzsvDZl7#b{w1Av>j;v6!n8YEL!eG;{(CN!%*3?HU z9(FZltf`LceV8M2B#kXJ>)W;U-M`>X+Bo*rAG1jD74PHVl;MhS*jyc<&~YZb z?{pgcD!-5KEx8Y(4m|`F)#n(dS=@ErCK#*K7)jhCRs2IM0f!Ci3hLt1WZepqfNkLw zc<+4+j4+CW?=wU@U31cEwX^CT%#iuODK)=9dx(JJKJDca-^~^bT;lL>hZJz*DH3kY z4gl=85ixZHqqFR!WX>9ZM_fLRzh7RlDH(`{KJg^g(g;jCs=5bR1OKaG{p zU9)T8V@?g9KsLI#o}oWhZCW|TSS7*of$gZ!NFtDfCd}*5;<~R5|yMc^2(t0 z+ARzdAnKd11k<`VgX9xO;;GMKurXJRAKz#a)~&xH@$5;2$3rPpQ|$$}PQAd~uIaod z9WLMgsRX=kn8mm6G6B8(c97=&D=<2B46w-B#FvE2p_JMXhFL8BHeDRa(9+)hlJZw^ zIB;+b9-hYuGY|B@$bJXkGLlp`$SKF-0b;9F(VzmD1|GqR)Le)fuL6lu5PyppnK_#s zLk~80MN4~lljxRv{CbU^X!Q3;hLMr~8?sebCYbCqauVn0XdE;*8cQ@s39ql8hh5T$ zP8rz1VyjVL9~c~enZ>%%Az3OswlDq$eC(?Ex4rU!7V%b(+o_Izbq@zOzc=tx6nmjR zv%?tXzE~sBB$)M!-&zleID#b~qwus44WVeqFqEq?oK-xiBG_PP1$(8I{Hu6apS%j6 z>>!^zGZlPzbuw5oJ`{EPrisF15<%ZJFZc(`x*>UgKZcngVg}OH)WsIRSm}>(VxR2k zK+nV&1tyb3rqjzoqE0`&bn{vGTB|GK`z;3xiHstfTM5C;yAGvSl*;*Q*P`%R{l#2S z*+rx~;RTBnr^3VcNFm9`eai;_DJEh4UKuygr*fnGPdj0PPq2H~o? zlZC3e6NS43LpIYCGnHUggc?h;r|R-U3drV32>>0PB2+ghsF(^5%NrM%yHdK8lan+hAS6 zl?yvE1n*fi5yQty3}YsKZ=49G;!Rm`?*3z3f@Ks=P_+mC)nr#axrohpP**EDTuwi0 z%BqEI#v>=62t-oxm??LUFByyr_Qw^iGMXa1)VTuicwem{iD3(vCQ3#tg(W~M=Nry6z+ZL7}1?Wr$8 z(m4+}TfKvSA~{=pct;ex^gY|wL7GSPLB%X8o5T7fJ zK`W*@g5ZwZurn}*4VSM-cnFgpO{89&ka$WB7Tn*<&r_+C{%9EvWp;sr z57Od|hAm{6GEv{`AsCCINbBnEtH81e5m;_G#(hkJ(177u@JZPA(7}n>A6^~y%A&V5J9$i%5G+&PgE0^h`qoHfL z?(dHAB?pJ2(U0GN_Xpzm_{<}0HMc}X5JE7r8jYgr#uyMZF&qc{Py*#Mj8L}C8gOse zNm%PJk~v&b;Xz%kcD9^g`lf!xWjJwI7@V!L4tYxIxCx&Vc%7EbXbR4NJ2l7ff4v3* zx|-MGYGMdxt#(P#(sijo354MuTl?YB1sJv$xPea6RH^Bv$Aky%wwt_IfqZ{rned=3 zBd0(+99I*Ju5^Py%jf{_{wf4r5AA{~_3U}24I3DypZMFP5X`hkYQ^qf)4+Z{6tCUT zjNKOZ6yyfS0r_rXj)(kivEs3;s3)mS$HJI94bb*^9vn4l0NS`D8d=Of0JP2|@JBMk z(C$WUE!B{PEE8ZEO2=ose#pTz|NMH8rC39XI!~z7LublO7 z#zWH63bq|if?un}9w?dCaMbc51WkLj59GI$^0j+{(3!OcsOG^%o(m6Rm~AH*<|4tk zkMk?ud?*w|Dumz%!A9KcyK`jCBNKsrSSs{f;0+@>a+%5LugM!Aa6HY1%c-62#s$Vm z+PNDY*I5NBMyueK$6L|M^@a#vs^Zlg0~zLMGQ(hk8S6E_*x{rbSUfBkt2|H#w|$Sw zie+g)|4TMZTbsm$$De6LcqE50<7O&6dk@UKfo|{NepwHVB*w17ui3U1RRe9;oQD%;L^o(nVr=}pzB=7Vnl8d~=> z8#-MVg$JEj(IE}Z5uuvsZ_;=$&#E7;o~enHh(~mP|DU{n^%RED5Ha@%M$XCEy17aP zIB6cj;pJz+#E%zcm&*fzZv^S*tf+;y8u^eK(9#5EYH~`2hdDv-R`?EkITXO;CS{;L zdN7VxDTk+DC?Hjm?B_7C4=C8U5-cMa@*!v>7|Zj=Y`T=6;9@-j@TA3efL(-4b}A!; zDT1`sZP31(ID8RtyXjw!$L(|ZaO{`m!q_h>gu%(V+`aLm@U#;)LSUSY@G(RepNp>G zDCVMg(DjmFykq1gT3L~j@FD(qVo(W4-_OfR8`gs?C1P?)T&>!=6fmpfmV{TV!Jqy% zuB2|DU*AvA-`Yz!7O%rK*$=?B^Y7uY<82JvSc+K;Y@hAe1FX* z@@aXM3J+Q=&bjyyx(+@LhsVgnK&g^&*?l3*O2`L>26wR0_*$^ItsXeOA;H50BPUio zx-KStooizxIn(>#CBMA!(DryxjM8Pw4ROHtIhiM{cudR};@|_@`|!Vthk5c{7`n^{ z_BnQ+xR)2=6;5log{P+q<2vJT2MPv#3dRX%8~xZLu#UV1$gZ;&!Ti-pl|0azgk7Ay zuu}FFo*QvU28mTs>1_e}e!LGql0WI1asx)B-eswa8V%)8jm+nMUF!=HPp`pp?f$Se ze=@G0yaV@p*T${d&<*SPC9&0vCZ9Ee(IJ=$?QBUa*oxPvAHbFS96{jIgEBaB9PoU6 z4cZsqgyWw%!gUs9Fu0_WY0u!=B9ewN2wr!}=3Hl==jY7qj=Jt?1c(0S@YBan3vSWy@UKInSfy>$$%SwvtT3UZ2Qx z{?if|v*Ir7Ovr(7hB7oL})n$a&%X?UBjjy?xma5y^sNF61;iw0}6?(ogs)KOUBF@~YzapV!O zBbaleO>Op04#Cskx#Nt-1BHO0rYLBxIksydb!d{XIQ_#|D8H=){+H~hc%~f6B*UPc zpEhnc%b{{1^;f55^DJ1%P`l)QiKD+#F{NA9zVqc2UNS`c}x2X z(WADZJgu{02)9o*bo;Oh=G?r=ay;lBTAz5TJ!y4>71#j(4U7UCR(qppp$|H7G!B%0 zlEbgyd#KQVIm7(F@K`}GfBULRJ#A;`@ z9gtcWplGM3@Pp?X@WrhkzChmI+Qf#s;Nmh+KrrM(u#;dOy&oi<5>m#$$#uu*m^(M+ z<|WkD-Y%i5q5cBYBHShO4GR#Y7?&L%VA`4j`1IjqJfuw(OiP?1(CZY5vq(S1r z1l5GGf|Ovoio#<*!DxjkOQ-Ai<0Fr{W4qnMK_e|%id_Q4&O)zTW{tO$4U#xmg?8a|min%Smp#urVSNmM?<9nf! z6C>Pl#n6Yqw%jg9Y9<=C{wW<~FB*EOhJyh|4OiQlg_!i79 z8ILy|p2$t!=L>yW~`Jqs?3zC~s5v*GpE8KJL1Fv5j zzz=QFR37@xw;Ui{={Dzee zCG@7Xi(B!B1>m;)RldBj0%kgm7%0bVG*$m@J z0=Ncn$3f&}Lu9pm2WPxGnfJOi0zDnp1}+Xd#amq1!d7!$6dt7nz0iKbTutvDdHx@^nG|GI5q|J*V>A?v(LERm6zexYFAKoI2NXR>9P$J zH8y)IlOsjr{|OIo+zvZQC7l~R1Kg-{;&TTbMR6GhN%)2!2^P6;ZGH% z+)o9%+$OA)FT+wJbs^+>2+*w;D;`vM(29rgM-?)SCkl@ib@EY&(L<)`(Fok|0$_I( z?5k&(xEw_9YwpRC4_d~b;GctSAYm&s7ENdj2?dIRn;VvwZ&3UyiUW5gVI zSR5?BY4@+kvlJlc}QipSGK#>hP>1nunS2O`4@c}voqtfFFw#%{dI7hVitm=ok> zLojUw6J)foSgRp~m@KWs#zP)SRz*6NnKrKkABPvh;JPd9rcp%@IQJYA z9&`^)d!XL^P(%9{YN7(u(ZF<*E-tX`g9gj@LD#N-<2`Z#!+aAlN=wM8`p~J?S-RbU zSH&`H)ENra9l0a}1zx~&l_)&wn@P=v=o|gNqVS*?sy){(_y!+uDS(SFD}oc1`gk`k zgLm~5(Dx!GoGRZN{N|T~M+8IOX&MC6!^77mH=1|`7A?VDn*^|CeTnQuvp=AnDO7ma z)m&hh{59m0MoJMB^HTi+96e;EFgkR(pg%K7s zM=;wyeX*f@%`|~X|*_6s}}R~b#b?e?GlQaBMJ{Af?1<9MRKaUC4bg*AwIf_?7tS~ z%9hm40j}ny(3d3R&|^C~O++z8(@Vq>-tG%<*z@z?S^5GY+00vdt*IxTojO=JGx7n5 zD%$|2rmlb#Gn8zg$W0qXFlFt5k~IUW_%})maF>lLK*cjlrc9zHTS!{0Q^ji-9G1)9}HPs2X?G2 zz*{66!JzVyg3*EqeB@6Ect2{0FmX~ddjx19pX_WV6U@&?F%s+C>G;d$IXJ7#kFVT* zL^j1X3*;w?!XxV3Ue*%-pYRA&FNJT9%z`fG4gsf(<#@hpJXFJ_ypFvm&cFGF8-3N1 zU-9A+yJ@Gyt@<2-37wZFDc|UZ|L&NDJJmD6aTPC_gMkHb*;m2*p)*5f!H*A1nDC%B z2A1T*O(%=@JGO9fTnv9ULKAg0=mmSO%I7@>_2=dX41_-}>LYs7wvf*nS z>${_FiANd6M|=b}6HN1#`4W?d@%Z7v>G;E;l|rII1D8@lG6>u2*gnm8vOH8SJ`X)V zU4&JN^=viQhui^L?s2?-$|+Ev5Qd87l+fv^zMysU3%-anFFzR+#W2~TB5)^|;hooP z_D+kzE|O{ZzT-q;ta%j#jA>X zcWZ#H_=e6TnAY=#Qn&ESy!Ong*lkWIw=J{){d64jFF=sS9#Fd}cZKt8#)A%DU=n+< z@W%u^V#p_svz;N(tH5If@#N@@Cu`aWlb4fvHNkumPoVM%=E9(!(ydi;{P@XJ@h>+$ z@H6rfQrhXpTCMayivfakxLh%g_;wQE5!hV}5PaXDhevG)=bk)j$MiC|afKTYr-9>T zT?8BxgefLk#7GHdgTjg8(VH(z`dylWWjZl@UlQ2<^>7k%wW6(7E@Xu9;ELz4YCf^n zCBma1qLl?~lsIbQO5Y!n`QO)Ks|9NKjBhV)Ti`$(w@QMK{{cM3=!i0^f?zK8buC^R z7|Uh6| zM?8f0Zk%Cuy0kfo3Xi^D??Jjxqr(?3e}4jh=6bS(yOYY%uov`AWK zm&hIufnEpkHY6)Rx$*A~ZZtd+Q@#Gz)*Nx*gKZMc(?By#y)#Fn*T z0khM!jjw|eWezqgcPqX-*7kn6| zUBrAR7$x&o>(Ga>;52D(?h;`E9Gvw~R>EfB@;Mc1R*ztUomQh}jn#y0N@)yp&-5}J zyZkV`Ww{=$eE5|!aLnL0M(;#FW@p0B<81j;f#U#u1p14eDe_Ll0p_!>wViGn*i|FJ zr}twXj4FV~p9PRIb_{g8-0xqj6&)^D9u?2p;Aq7obWIzqpLhhB4w(Xc=Xvm9cSBKM zQt{|Mbp-!@>~@A3O8#%iBhZsz;1S;m=7Udyq=E@p&8HhbpgUiMVrWJ z#e=$9(YZC6C#~{V2kj1vLN3AqFh(Vj-#07**`(^AZR3;pJxX2-^E!cH`Vx$~@3ErS z4vAph@3HvJ;?I(WS2bj2t0O@E&{*hy#}1ZW5obJ%Ge^U9c_-LDje2*hpEN`X=0{LU z(m`N`_N^2{q|(C;<WE&2@k1u=W*C1FV?{87Cz@KLClf(foGHfU zTS4QB44G5AJE&iC8CFdxViWo1KI91RKsHSNEQQo!f(nm8?^RKcnHnfkum+V}KYVVn zHkxry6Ger!^S`ezV3uuUzW z9j0`Sy~fU=DTW4YGqyLOeT67I+OpOQ zZ6@o5g(*2)pGFJ(Y6cJr$;El-;l!X^j$+1(7<+?%lq8{gZPU`n#SK;C7-1P*ZJpN3$M(mU99;T_!W zq>YD3e@G~XmWjw}mJy7T<8DdP>EV3ijv=@usvV4V$dxGtE&x?TebE_qn&v|*9<;Dh z-(14p&=ix?N{k!ymkK9uRu)GEcf%TRi14}K9(Y-A3k)r%LyAckG3y9s*yNLvy1c9W z2d6>!kiu{nKI^RPjm8n6uR)rVNX3Ir6HyC2no9EC9>bV<524BDSg3uqD}39%t8iqN z2b`H&1AGdraj?;SFs9)dnEOmkpqS_425LLO*!0el{G6zb$AAIYG(iL8a_O=F;RN%! z)kq|sot?y8t6oHQO1Ytx+IKDA35;%<*A$&cW z%N~KN;&#xJV2r(UC7O4p;<_!mSch-p^PUIEel_NS`gNqKFZ4dFRXWIohd#OsD}G#s z?q+q_myzBV>Y<8vnQB-C5gC&pJ6v`o4C34Cm7Ae1(H)r zJF)&C9qiuaFu1$ROBQ1?69iAX20P!}fZsRT!@e~oaOd($HoEAWRs@4S_lKu5?{cG` z9p*>Is-kN>|A6#@0=_t{KR4)=8a!O4hv-e4Bw|7drk{O@r0_~G4z22o3!GwA&l@ZAxVE?#pC;=R&cFjyA-{(=hBBxK$GS;Kv&1(+!viX zsqgg~=!|zTjIM}@BN(ryJV`)i44$Q@g;xbM;%O^y3CqlGNHnbP!Ma2(`Wd{-@*e2TkWhv>Bt8OZ z1ao^`pybrac&xOs4_0(sDBPYlgL8U1g;zfGi0lI{z$a7184s6Z7g@3&ZMC8^?E4iG z`AuJv!R{kR(fhkyk^Pi?VCd}ke8$c`XnR8x!|W6{x7h^a^1Hu;-x-64T~)``={CX~ z^{a5h;j=uo1(o;DfqPc=g$FlWW_>pFCf6h>;P@ zYeUoG`v$vleVQ7MksmH73~@shkNue>0L;~Y=2hgzB>gZ2J9I#uViu3f|!7nMx7zT@&DuQV@?kxV5Jp;c~Q^OZj&*PN8 z5vc!~>3q?H$IylR+%3lsvuNbBStO(uH#5U?eGVrS)*TS2A77XJnVrmH{GfrFD+0hqg6Ls&t=`F8*GZRhUpCP3fT8%OZPlHp}JY!`d zilKYx`0lCjkct&vZwZ0doPlH}q!BJ_TL>#dwkkkSlXWd&pfLoq6GfEKN9adlfq3Xlo#j)-5+ubk~A=9^N?I8FvS#$GU_A2 z4Ez>c9J}$1WS(ztJm6wAQ1LsBf_6RTXp{@>ho-Go!C}w;RXoznTj9Z$zUI+&K@d{%{%v zf4aiS`!}-Ta#~oSJDdN8%VXv|fko~ZE|~Iw-#6Y$GXAX+4vqODeOx;gs9!%TF@G8_ zjY$gNC}yg7o~F2z{5H`!MSl)-0cT28v75ziFfT0~#qA9t!s7v%j?91&dRN&&SH-1N z)@nr?U_Ry-Lv=@aIB`rcEKvE$56xOtq}Mc_@0C$5oLE*=te2m`FkeJPphhr%Z^eu| z@WB#XJk%2p`tl5fojr~gE1Lrir&};yF`NyT(;ld;b|Em3zYb}R2c7W{9!3Z{ju!Cu z+pT=WhAzC(Dmz$t-djjUllZVhTN!4&xK-CBnA06YZRQPf1};g;c&R%85vG19Y-bRs zL3*E}Uhjmqq|#1Zd)?Z$LeH&*3`2XM`fsnqH?NRD&I~(AuGb%FvE^gv7wm)Yzewhz zZ#79AMxQ??wcOE(fOlQJ_c0$tOa@%QV z8HQFoR(T|Y+t3Wjz4zo4&L#1y%|@f^%J0CU$I1Lq{wQ0Gleijlf(cg|WOHOu3}_vx zgnyMx2J6%NA!WbyAlNg5*-gnGx&o=I)nq>%Xg^DAwW7k~VeeqrU2!wAw`k|OIY;rf zsUD~>DHA3Jui`@ztpHt3o%q{~Czv%(#n!L)5Chtwia20IKIh+-4i#kqpsgtZru(Qf z;Xx}NvwA48iU$>iRCve@d_{5!L(urV86cr3jF(#%j#{tFA=$WD{IM!ehVc`Hhb_UR zhAgr^r=1GaXDHwgpNjB2RSjX^tw7+iG!B05t;c#fsPK4O)`zuP(cy9`JPu@Pqt+oY zXw+gKuzOexpRphcZD`d&!?uL*akKpy#!fs{pG7e6ZqK4g3h`h}7ddRYdk(j|T}y^v z>;xZsC&KdIw*M*~&-dD}R;&MJJVy61K+xtWD%S7;Gyhie=))1@@X7%BNGtflY#)ZX zMBZscMlB+kmfI0UTVjuZ16IFz^~B9m{pKaIZH*DYTJIFJa@)gtpyo*-vQGOoQM37UZ7j} z5PaNC1~-qALrbF+@xI*}fZMtP1Q87R-W(*DB8wOs2koO=#K2a*`%mIBVpl4&-MEqk zY}B84#agW>hVG&DJ#R1!t$290ItcU{EREwV+$?aN9~AyBghGCA4eUowqbSCQ+%$p- zBABYy?>1{kbd@Z9^Ng3FG@yP{kl8m+14Y(1NLxY&`@f;05SO(B>pF{B z#iP`MWO}XZ4*R!%!AsQo3;a)Sp(nVDX9vFp=D!XIzI&cxia8^;jARhZ?1n&zj2yRJ zb$!G?oHGyfy__nuNb&*kSBU8!d8(?;he6jlH897mo{f^wAhg=hJ+S}XMi6`O9PXx) z0$h^^3$A&`u?cBI^&oBa&bf+gHLt`ybRNN&{SKCNtDcRYpQ+`S89&4Oe;t*5x*7rK zupe#ebFgxQx1U{yc;h|R)aSCV6z-3;gWdm+sy7eF>G|LPlT<>qsDzNctl7KInHkwb zWhZ+?_JokFl6G3OP>GUCLphovok)URHQp(=OmZWGZng&BU2B9Mz85*BhkSUSPcfTL#tQaD+lf)x zZTxvO)oPsEsXATXm5y3nfpvb@;OhtDV6~`%i9Ji9j?p!!xic4@+i476x4SR?S#tn4 z`)i7p_wNA%TSnt2%a(|JjtqktEBYdK(~@OO5yc$IO%fD8_mi*VZ()7$hB#rsP?gEC zpM2D+^jslq(CEykh8*)Q(#q`?>^15vocpR8Oqm{5u|}?a%3f}9gzVY-rfQyXYR)aJ>$S9>YzRE zgEsP=LZv;&Yw^XN#%QN?6vs5kwP!WOY;E^NvA<6=@f=iwZ?_vNwHI#Dh|oelYGwMG z8UfoFQFqw9e}xAdgL^hnlWxZ!;z+%d;OxaPGMu z=_HMe+k-|`n;_|GJVD1T- zpOFrAKGJvFj_0r`Gzh*$7DRc{4Fq49ggUSK4tuBU01F+ulV@vg!Vzctb4-C;6zWin zdc2xa3m6dBJH>d--Ap_apF&slI`A^ebn97qqJ9FJ1=n(648!#DqkZZNN$|7dFtWJY zC@{jRJu=-ubEf;-fI?>ra_MVV>C&1$(shM17%sQI4Jl@bk(#p0(Q{biNim-BAV)O) zkb@jQ#0#vk5`H9;Po^-{H*0#a#>$l;AK~gZd2n(SB3c%$z_VRLBzDc8Hv%lzRU@{? z21&NZEI6h@es!8r%(3;)3KDF8D*Y5C*mlTeas93=bmn76%(kJgKxnTaIr;!RTVIzjXsL6a|bJ|?wS7ZbJ`2e~5XLovno&lYU& zo+AXGE5@VUsC{wLaio1XQcxd9wKm=t;B@M9%Q_y+4UTm@%%f}J?pqQZS*Avm+Lwj4 z_x@m)_wC8Ivs$7bFeQ^qT9Uj*D+R-p$QUb%acHx)U}vvrarCCEILjm+^y_#M#Z3Mo z#CX%N^wd09N~1y8*E6tv9%SP3)xJ-mIdxOg^g55TqLUTY4Jw{*xlZ9H4Ij`t=kj#?V}?Aj!WOkd|J-Q@|tf=-p&gxy)0r9eN*nl&10-D7Ndg zd3>CYTCwe5{)7VPKd~9SqU!@qb>i{Z9{up)h%oBFr~@a5YhbJ75gc<(-b0V4n8S^J z`Jm%aaNu_lR*U(fbm<$5($oq?^*&|L`Vuw7qOAzlSg8UBpoeJ*A5LOTuTS$LCBOHk z&#c*R2{1$s8}~>40Te&@$tgp>#ftZU-GG=Hc5IYgMHa_;t7tQ=tlZm$?_Y zW%vnMoeQ8L*$LBVODOHf0~qml6ZAetgU}v5gu}h_A)V|bo*^n|GPYLe{=*rYcPfM5 z8tKsHjaXd!AVpv|jfyZB#*tz&?G3C)TKa-cPcGtV&QvJwu^lCjd@neDNT+c+)1Zxg z0moc77z-Uwo#GhQze$*U27IJD&-4>P;s~oyY#wEaJcIv&#p~Sh^bkM3nj7-q*m8>L zfAOAmGv{a!Y$xHf)AoQPFFT;-7lr_x<;P&7(1&k1Sm80#s1vj?J<4wyD?HwVFgRqY zGuk&<4b&I~<9R<_QO4s;cx1)^Y#h=Lu+{99G3zPjjz*^Sxbq2MTpJ}W|G6Ch@;MFD zIy>;ly`m^1K5E6L?OtEjfwoVgpk_iPcjrl_v0_9KfHW6R01vjT!E2uGM{hf5qSyzc z@%qZ`9P>c_ZMIR2sn&7pko}3^b9D~xI@c8cIH)IS%yR~TRbkL4x*Hdlvo7x414dBS zE$Uy#L%GWo#k~$gk&||U=ia{9S~m=tT6ID8y@K$Oi~BfcGku`xZ{tldT_)9z^7V-Y zp}|?$reCfYR$!ot4_*rb7e>M5Zzl4PI`3|e;h;W%n*;w>cxbQeg_g_@K+|;G!S=3K zu;w6tv~y2iG_WoUpX%w&F!GNvgfPBu?L&?Y5 zqk^YR*v5Jq#}vr*O&Z0hiu4r9QCcALaU6~;w*|9aWUJoQxB>lm6|``oyBpf^V2YKd z^VD8~x>_*|^A|W$)&w^#&VZvjX@R9hUCF_=O88B)1^V`-Em_ckMkd>D1RnBM{T#)7 z(Ti4ODx$7I)B;nqgb5W6-Wz-Ol?16TVqs(CwXKvS`bk6N*g2TR1Xp=X$EIEg>d zjThi~PYE0tGgC?%@XdPj04<_gZ7tm&Q3Jf6REUWa`#^?ik}>5J)A5X}uysc#!o&OBeePdyu~N890z)ATi8sx$t;QF;S`R!Yq{u>DI~*Tel1cd&6nru_FqYo9Dr5Cpx$B zCxS;KTb0os4waIaTHog4@}dvVfubOXv>X3b>=ZRzitd<3Ebk_QoXLHpSmPA_2-L}& z+ggeV9==!D4JVR-VcxjK>dzSE`K#9Tj|1VF68%8mgBpoD;HT{+P?w(lvnP#dJX{9P zfWbq2!P{b2a`H~q8+^UxhB)c(Roo-KHCpmV172>( z!H1rNiY`UQaHSFT@TNEInmhy5L@|xuB84tKK_uRE8-Bg<5pZlAq;iZm22OotjmI&! z9?)$#ZBFi{(|5G+&{xZV?TkNyiZ-eFb9Bu_I>~@W2XBD7+x^8Cebtp0pHVBf<8$LPIpDfx~DlIKC5n18!sZ9Yqv``D?_soDXSXrPTphe#)7hr2asQr zCK@ux43X0x*f|_sbu;G4eykPYGHf_BZ&CPfIBER7%kcHI zez47VQ?l9PI1uUr&{!vZ6w~cExG?7}E~#&Yc0b+AF<0cRdO!BtXr$yj>~beNMmXc% zZ*(NRyIWC2$wn@|u8re_%FY3qS12DU~0 zS4D!z`E7~uu`e*tVhP81%7w>pin;YZsbE>7E$RDi8D8zXmISXlhL zJOF-*qRq&&r=i)br_g2~9gL+NkKe0$k#=i$fsy)l$kyUFOupg+(t8_`xTHt0+4x}` zb5zD4ikbJjq~Nl?3CUqc0RBHMPa+%boG}mxqAS@CztrMicMfRR7H4&aiCMifKHU z{)WYcI5}U0Yc7l=(IywfZQY&`b}hbfQnc)3L`H0@pw}V7FnRPzqg(Yw6f@RlM#0Lm zIAN3ja_lrHkf?T^K&!Q>=Mb%Lm<=@#NdKS4gH3d~eR;(L1joKNA_E^w!cQj~Vrp+i zZjEjyW^C$4I*hjz%J1D%3-hh`qcf+kro{2Ge+mwI3-YfT8B#8{8 zCl?-W6fgmQ;V ze%0yNZ?d&I+~O4ghg2WO`Lqrmpt zr@}7lc1zZ?r{caX?KtKRJ+qn)~v6wo*w zcN!5wxX|v01MiPmjh9yS18g6cbw)$%aZ<5x@c>fT8Ff+k-u%q+RF za)x47cq~xVt~f@G%n<(d)Lj|SqqB5N%bttNhrThR0rpuuF@{Bov%JEY5t|Rd_i*{nk zM`M-C6oGqm71>VUg~xhKa|)^BSoNGET(rdObm8;vD0xi)8Z~bxIP~xi4mAiw`l%LZ z?6T|l&0ZN(Eg#+&Qq0SGUB#{Wfgt?&AiP<3Ahs)AteRQ9jq7ig+wJCs2XpORzQP?^ z^-O`R@L)Xxi*M%WyzM%46s-Zrt={6LA6!vQO<$DS`x(v}y^*gbPR3lPm|=#U6){F@ zz}3#ZaKoa(qWQ8=)$2p6fK#_K&}md0$JEVy0`=Xa|8+bVCgOZYggT8zJNGXJw(DAv zJ)UFGSL1Hz^5|OpW|NGWD`W0c%>AM>Kq~8lkx_)$W zB6c6gyp%s{jT95>+*+9X_^!guvIYKK9}JqAW7YIS=G;8Xs;U99!h;ospYU61J$02o z0!)JC5~?M+(41qPT`k44Q+twq=Qc@F(qK@1+khlmBnWIZQ{)f9ABstQWGyt`KM`Bl zs$n(rCE()gv#QLbmcVrJMVMyzfsa}-n>MQ}a>paF8T}YAg=Fh;P?R}ZnlSltLFX3V zvD%!T(vV$mz^MlSY&}*qULIQmuwX#9leVW+I&%l_WuHWhMrWVTM3|$ z9-_o-s)ZhF(zp{j>v)70Dj_R8rYjG@cSHwvJ=;KreGh>f8$N-NFCP(8#dDyVv0bwI z*<50nMEO)*pJMKwbQcUyn-SsgYvs=H*5Fs01XZn%2N#!H+nAe(iykYwm-77NM1qvaftK-5x^tRNV0BM0T{+q7GHFtn7$Prf^cFg zSv{HBed@;JKd>_stmn)wPoR@;f|uItKK&c}d#iKl8_ za4VWBUknRBmcrD9lX!>&8?|C;BCD~vu+z;h(9!a|cx~B19F?MvR+^Z?8{r9f(v6Yg z>y4K1jL;3S)x^t~K@@}B4+_S$`^n|xtIGMCT8k?i2CDLfZ(?yLll>A~orM!0RDd0cA-Gg42Aphh0M(q-Mkhvv zfMLU~<2EiP$lzKe$84Zm4*J{JQB2kwO`!%JB1Qw#m19$yNoO9Gz#6KhWrat%?HTA0 z-5y3=zW}W&&hiZuD?Fx%+VJqtn|NLPNg!1mK*471P*r6-7|^c<`_`Bsax9c%m?0p= z%%zxpgAOWOp9GWbPfsbgoqk865063{=%7A}6lbGW&rXekj(_Q>)$Vk@>tz0EKB5(@ zd0<4^9*+kOxBZaaY(3PkO$>Oi`5T8`X@ff3cyr7$dM-dQP84(W{ldKF&)kW$_@r|G zEiK99&o;FC+brHASUvkRjOe@qI`+HC?LXKanin3kmO-m-=49T_gCJ?cCiFY3HS%r| z4nEDHK2Z0X;FFGvIVN7ltfd&A&-MimKH8GVT`9_T-TM*ELy;(J@rZw;R^E|8kex%v zn5IMh?oZ(g3wliSClEH<+lTb)w+$R$JpomA{|8TS}_bOJgn)z-JUU=Twa5~ z6VU*j8+`+gSvd*dnw~^;Gj4_zjCqXlL%S5^-DZ6hHKTHn z=`oeSCc2ooJlsr4y$9bz+q-h%!72i_9h~4jmVDZv1vXhCiCxYgx&!;tP9#}pn3SwD zh-27XCw+AWQcO~h%>@Zgy4X7;Ras_|4SIDsk4~rMDcxv}2W#Q691k{X)ighwyY{lU zkhDvMu!#12cDu!kzxApJyF72_iS;F&NZGtvGPypCu+@~&2by9cC?@t{LH^I8IAPoS zB;}B=kd$;ifojZr{(s_f*70C&aLl#WY(OoHq7sHZ+uM_@zcoVob_Hp#sYf~~yNhsG zH{w414;~!59y821`sYb8@f6eWYgGQtKcQmu?W4-QYcGKOwW(#O3U> z_Mf=i?OPSRQAyyfzW4Ek9~TNrTX(F?17I;bHzWh0j2-Q}xwJNzjJefq}Owd1K|P|8Jn( z&j+TYpTk|RW-Ftd!r?<}ZD{YkQR$I3o@1KJI_WHmx!&;6x|j7}&|=0xrPcglV)NCp zs4nuM$Xu;h5E_dVXUTrObV6Y1n-ZwM^&u?pQ~*oMVx&!7bKO=(Nj7P}={!9A6} z644!o*KV-q7?rI0R#MEOra(p2iY4G)u)lJk`76@y&t7zCx;Y)S%7S zA5Hgxr_=T+6~#GXV&M+-d&E?+nr>jvU9sai9#?KW;K}87+fVVrgGosYHXj9Er9Dtu z>Q?d9uz0-oiY1CKsR!x4hjHeGNWPl>vYqZNin(BrrVxCifEL`WJZ|a@ww~*P7Ip3g zyyqsuqE9^`8?|B@56`Mj(E4@!zm7*?pf@bgU5b1{zlx39z44F_?r4r$E(}?rz=M)3 z09#ED`KDD;%%9B}3KO#gVE1aCvg7Se7|?CS?>7ik_KSu?mHIr#?{Td8mQ=2H5wnBEbGFNYpMmUC{^i(gb&* z{LIni2MM@u*9o00pMwxBNeEz!C)pKw91ogDL=eh6rZtG>9o+OF4LirA+c!Q54W1XX<>laR4?4>Wdq zEw*gCm1AbenAQ|i>Km*$REWT!jm-;&q8QP*;)LqmxDlW<>;hzA!vA$VR^O(G|8+cA z|7L2EE^IC zJYp*33|u8_ZQ-Ywy2%r`?w3?Gk9u<{iLH%1YQ?HGqnYn$bs&#gG4aJz4O3~VMjNSU zm96+UqBFUZ`Hs}Ce@8aH>r9f{V}W7z%HNxz6qD|6FYHtG!*+kpD$M$%0RQkaDi2K! zuJO<@`oB>tGhcdiMU-DmZ_+{0KPqV2Tu*_OsxQV{?MNhf4Dbo&&>f*M#2| zYLH>R({pIL8bC3&AH9VyqpsrI^81R-2mS#6R;N|Je@x*4f^5`E-;w5e(Pr`LEib8` zni3u`tAN% zC73;TG0xqSz;Bu@{SZ*h0*W!S3l&B#-At>8P_45a zJabg;czn$)g-pPF-K-Z33&|6kUr)jBb9B&AJ#BbLQ=(c?M{&wSQyAjh0kNBAB`5o> zpqQ$)$Apbjg2{qYs_pD8a8gaDmQxj>(o+<4Q4)A0HN;o;yUMf@cd~rp_Z9 zf8Lf-Z}ky$v}KKl|H~Hez{0bz^cKxrvAqw|rk;XJz)kQ{eIH&|H69rJ+Jwd!Ux(*| ztij}=$FXC#HuMx~KgXPq%P0?u*;&0sXl!+agnn@m1{w90MunVLS|+UeH)`b|{Q_1C zXdJ~wdDO~=+PE%>y9a!1BXC~aA@F+4eso}(HX8gO2sCSX9lKxdfLi{E;+S`G?dd}? z3#N4!#9xPqN$@toeTf#y-JqBLA)g+Ve zw?p02d^kpu%cw&Xv*O@(>z8LeNamj1!s{Pe(!S@Lk#%+mpMheHmE}Q8;HOn|Zk<*H ztnhG5z6Ey{E{3}t^~vUy5ui`Mt*C5RTU0nH61+?>A_u(w!Vl}6IOcz;B#9K`>@&DP zcZxl^eAG+WWW11!oq7=YkGA3U4V&o7I_l4lRM|uqs|Z+o)qP|Dy!zObM6B`v;@HW^ zWyl}cH^CQ7)HWqfQ)=MMUBfx%j=Y-F6mw*pPeI|)PDI1jQ!w~*NJ&mn9l@1AWulv` z@u<9*09UV(H69GZriMyG6Jh#rOX6`50Yua&j%7$<*Nl<@AU&rWQ9C$NQrk3CVwh0*%tl2q4x82&G<(?{kALGSY;?N?T*l|1 z#amAB!h>l%5~U&-?)naX8j{Ux&-zyNFfptUE}h(iEVQh3QUXNP9yIGR|a{7;kSzHcm4p9p49wm;c@5|BwrheGN6ZyTK8K(@aW&?r4S( z>c0`h{_Tx6_3y|#9_QNi=HhbJ_uOXL?O)-+>~y`9KCpB5Md<9Zr((~}u~;=`GZLcn zVE%Q~@E7pvRbN!|8G%y^H{gC!7z%W0jZV8L@T5aKIHo;)(&(<>?A+)avyoBY1ynBpp`RPy8<64>tRe$LoRUd+|Ly_n;TY zn9GI70E*dRbWrifazAisY!nW6`i(2zPgmiVK70&rbGbXO2w34!^w|~GUO54os}-Ap zn(?$ds+;MG+AdxL#vOT$Ptw`jT}A`Y*5NPkHuWtW!<>`oO&duu9u?t=jrH^{+2QETiT*YSPxy;2m#R5C&PzzKyPMsK)%l#vE_zo9HSw3qoz>I zjl)@rHxISJ$!;CQZ{sUPzx-^~*LRD6`cD-P5M&w;HqpiM*4TE?@w@D5mAmaL9Q5}* z%)HtWyuEHjc5c25CkJby^2)Ykv5Ou!@oXu$FLyj7^Ip|Eux1@}-XEN2z!vJ-sLw!lF#z7GNs{Wcev)W@wSB zeio9V!!r;=+Th6-^7&2sPM#DubzVGHmah34@6DtG7vH;L8U!m7grONZ=iDMpDlXxakp zcuXH!4y)6AVcEzhV9~%_VxBWmF=DrkGH_Hm7e(}H_&^R}I^=~T%-jmK*3%g}$zeAp#m3;1%=nRHz3 z3FD4+AbrP4z?GM+!_R)PViBU(Qe5# z9@cZN!-UDQ0dYyVDOfBJUDEFn5eD`3rq|U z!}!Siv^a`+v+=NSt$i@bHJC1T53&FnjYCwY!C#SCvoJf|u5sPr^kX?Ne~LV6rE?<# zzWdn>YG`#)PMV9v{uRSe%=+cfXw6McpxMjHmNwKi#>wTxZ-_*ma{WyubY%Pmg2ba>q_Nu(+lL)a!c* z*Qcff%lHH6bA%o;K2N8+*4AS!)DgXH7tS#w>E8`~po=JG)P6~EB_o8K4s#OC)|HVi zg#*yJ5_Mj9u&sKA)?m6vlX$XUR1o!2O)rFV#}9zr-Svs@s07fv%pbkgG(qw5629oFB^)vK{12J23sqd?_M|VVrJ`-7gdp9Ld$Jv!oqfFXnZ6{%{L{r&dpHpjb$7YNrz!6 z<^jbt74dTbt zY+CID*(0Z-zhBjm>-=C4Nv#lOTE2!yO-FJ}f{dxAm}Q1u1=kw7lF7-=;zaSHQad~u z0Y`16^*WmMO&!MqmmPy&TU7Io2g9)B^0cM|SaH~r%$;cq;%AtmBvmEckvj|IwC_t! z_q_yfyl#O8k8=bGvi-+9ikYxIs9VI~+ zOvBD90(L;W)gF-W^KHPu@AeYAthQK!cfl4U z#I6fl^2NlTy~%;IpXgOZ7zWB80=1=dy8CpOyqt1NVZ{EGVrZ)h&^|vInVpyIblK@3 zbG4f8`|6*o74smrp*7F4CS8*K#!`%jLFDted1Q|5GSPaiDGdQE7h}?tV(+cWL3lT&+C%KIP_F2i`r#RoaUM ziyaqn%kdlVhu(7)xzz@w?ehX*P3~KPt!B5}jWVQ|Q3DMW-u>T-d%=3qpx;`M@;w># z7#%B?I?6d77LJ!7JBQwVB^9psy~~}GoKi5{m-7PH9@<4yP@dPcx%n){u+* zv({_=L2m!SDgrjqmEQS;^s?VuuyH^uT(z?g9`m{_oKq1dXRebZgUzsvUHOto&v zVe)lwbj4BJG-oegjX+CWx*CCET4~)X+xL1SG608rhrXPof5BtK> zK6#MY>HgZ=o!jX)t*0Y#wD5TEx&ns(nvJR|E{hRmQMlxQ8`@HO4n|L1jnnYGDCl&=M@*aFOPqa*n*Dr-+)lS9T^}-c9+u+~SKEebJXnAr>v){@ zd<5@V`JjU_5X_c>@bPA$NKxAojqGoOXOwQ`7)SZHaiExdsfB>4arx4zfuhGGL($p& zF0pRD02Dq5hdp|maE%8Omz%6NpiWAW|8hJQr?f*STZWHzd2-A^d2{PXG0!3z>8_Jbb00b&s^ zhTBcC;iP_pyP%7`1JEVW7mOa3f>-*7qP{Z*BbT`n&hO^MG1KYGhW<9oDQ5A}O2x$; zA)w>xaBL7rik5e_g4yq*#hI7V#TJD@svNiV zAm8c~jM*0{dkxW3_52lK)UJ)rMK7fmAQTg->WD^tpNLL1Uk2(XY7pbK(@@5`-e}3> zdi?i|JI9pEm~9lZUGY$%T{Z#Ot%?&n%#9PBXC|nMO$6ZWOb7RFX2SBfazHwp7r1hr z9tr&q^F2%#1=P1kfn&#l(80#!qNX`|HLDW}dGiUk3U}g|7#ZVDF#~QlD$FLd1In4l z#AEZy#U*C6@R&H755TxhE91%K%ud&8a51ezFL8`1Ev-6T_)5opB)HSh5F`!gOhRJs zL2FAL^!A%JX{Ol≥x|tmW@bFvSGj*B3%AoD}C5Cy6QNT)T-Mp93j zJ*Q~dSNyiPGcht(lm2L_NefmOlYsZ30>gBbKWoP*W@hdJA$Oz>wrfZehbM)B+)L@I zDYeyN7JW14kEheZy>lUps$_*n)8;}x(KTQ|F1-IN3g~IikQS%Gya{pYB*T$K=A}elXP+Tn~gFpF9FS zyRu2ISHJQ4FSDe8p7CV-@WbHwtclX(NhkSg^yFP9p_r?!Lxt}O8*+EWIdS@hD`a(4 zkg98>9WOird)$ZlPM$EiHH{M=OtbN5V$ANFSGfD=D7{r+O!-za$=n%Uf4Q85d#@q$ zJ&l2~h8m=G3E-;av@1;!XN;}De>VSsmom#h*CXCIr8-{hJ^T|WyVwe`oAz49lv7OT zYZ`}`8c2SW=8845HUZ7YqgAtSUJz|AmqDwoMetBUZ*I_3RZYDim*0XmG%Jtkq|LtT z6+~%u5x4pFLw4;Z!ix*Hi4Q)8EAP=sutATUIVOkh1?aBxF~zjJmni)1c!*Ry&KK=g zk0B?IsH^O&O~fWc8nLrh30;nA!ttszu#y%bSy}gBVdg2A;qnl)S{{sBpC15v1g%1$ zjRa0QZvn3Kh{3JCwM0K_gE(fe{0P)i%ssMS*#GeeIZ&h&*Is)r{Zd|~CQGexd9WNH z=pcRrIm1r#9FH{DhaAH?9{wAtvxreNNU#Y)C2^W)`Ys>vdT z-%Lj^{8<@%mpd1F^yx@uQ5XL&9XwFZq;@FVFba&AXh`jiG!fk!0wU_66G7QtOGm&go^*(t1Z%48)z!z9l*`uoy znxWCpgFy1`4kQVGf-O!$jxm!lCKPk1ck_Zw!#-rrR+YH%qc!ewJ_+5M{eo}RnX6Ux z<|8nE%QILk^0 zuAXN|cFk-d?V9BSN;UAIu2*QGn?ka7Z9WUIvT0$O8IJ6$$vmGh8V=>D(pNd71n9&Nhb z!5bc^37Z~;;egaIth?o>qB^H7@i@>-INHohV5_O1wI{{cQq1?3U#%wvJQfeFyClAK zT?SHzrl7Xpx{AzHn?C~7kBdzZv*C_v({lm39b7~) zj}L__Dr%>LOLzDY{w6z{>vELGWjLHX)5~aq!<^9(VaM7q3*Z~^!|QTJm0ET$g1%{ zU-Y|*7B4g4xzCQg@L-tY_}P3r_+R0n9Q8qTtZR$3Pl{sQtvT3?W<_n8xerWU8h~eC zUc*;&M8>#LOfKB7IH45|hL)Fz{U!wfr@y07c;#o&irP*UH4NY#4_0`*`)dKIw3Ul5 zYC|u;>UbOYE8Z4;*C-PmTCTx)`<>DH%wzEF*mc-0q6=WZ%~~0=lVWPZ3KY5>B2C4YTKr!y#^~IOc)8RrjTsZ${4*&m$9oLu9!aV!H;M_`ZrP3v}ci51%Q9 z&?bTE2j)HE7L5q)zx6lL0S9=<;DvN-PtA@fXYLvyq<;zbGhAfAj`P{Opp{_NZ z(Dk%H)W5qIkcP!!b^kClu*CqhaO8EYb=HSttm#{TJ_0cmv*qti#XGfda8y|-p4oK= zm%LV}Ue-+kZYf7#gmMM+md?Wa4Ugf>FH7l3)Nx*Tu;lU{YUXHotOpu3*A*0YsKZB$ zywKi^{%BiSBkmTvi({5Wa!eA%w2muL;8}Y>_did?qBD)+!(o1^?-m|F|4u6Oa1H%e zc!WO-hIPZv@U1$F6rbI(6N-CjkGeQHfruPU@@mmMv}sizlu`cz&sw*eW0uR9GZb^M zut;%vy90Q?phiqCY%XpOj#CY77!7pbId0A3L}$^MlZEehiluIFY!A&a*$(Xxq4Dk; zHcS9XS2~bJRbMpnNN1EVzS}w(G^?aq6__+gcT=H6c;NC|(TAroK z>Zt%8i3HjlE{5e)(!(kOol}=!ZM#B_Vaes@>;J$vkMF_>{fxnf51mMq+IzTdN*i?R zdJEEbVqd7bcD!IBKE%ZPL%pD2d$<`Dv262)r~ENs|%j<5|`IERKToW zQ_3-Jr!(Q$vX#=q!dDrc2s$rc1l5+LII4UWmnQ=YU>xHT2baonrnr z_7vRvX^HoaHHhacjKI7+mCB`a7Z5GeEK!+cs~u$#sT4;JFUZW@!4d^$8(`gEv= zG_{SJ_)fPQc@b+Y4Sj1YZ7S?YIyC5TOiTLPP|SUbnYU`D&?Tr$sY?DV+RaP?R@c*2 zsW;z<`kgP+7fl1SUVK5GxuxQAvsRaQZ;e?@w7L}q)Hkn?&US-}BdhdCpH-8k>@B(A z-j+tJoSa|4RwKxmXB0Ey{SLwS>Tx{%>lg9RioM`=(^*yF5H(=!j(PZr4V}7Ue>cpv zH!xJm4^#e3Oo8KmYCu2zwo+!Vwy;gfGJt%WOLO!as3Xifu(cNJfRv&pnHO^@O2=~i}wms?S+nyM{vzdO47KV$I&@}HJG~X8jw;lZf z4t*^kL67&5m4{s<>y-1v=pF_$43afaYxIV7Bg$a>^!u>v!rQVe|(S3<3hAs~CpL6YS?8a_%pMSSiD zlC1F)!J@1CN!u0c_-Y=@=g@yB=3IH4FzW6KVzWpMq&8m&_MG=qB^sBB<k^!(TcEN#9TA*sJK#qBMh_9v-#pqtn77X6TktNpZz;N|YV(exvsU2)) z9k`@|Z=jw<{s7g#Ps6VrE7Y4FyVJ0Po>H~tvA9~jr~L(?WU!Jl56fa>dg z>>X!{-d&2~nA7x0qc^P=#iV-%3$vcalI5<=!Q}6S( znK0fli%zA`Vk9aP`Y&h#t!u+^cxoD085WF)b8B?wWe9K#{emlF&C#sIGUg|J*-*?N zidiGh7M!*nB;ZqXkd4lhD~5VVJ*gB|?tBab)6?Oh(4H`{zJMDvvBJaZ5{6TvyTTV+ zE3s{Q8Zf-*j}kVtMV1fZL0q63vFzFjjrd8UcBIB4x> zO7zyXM)m95IObaj$Bd;IgSc^uZR?j1DOH2cX}%}Tt%A@4cRI9B1y z3fWej4P3H(Pw!Gaa&b;5nD}BA+B`=cjr|w`ytGZow&dT?^3^1cIUC9`b`;YkB6-wQ z!$CwpS_3?t=}X#HB%suK1;>2ypfjB`MwGoen;xIxg~z9==kQO*SeRPUg_-~@0OnVE zp*wqDz#uQ`&*|BdIIMdBgGZQf%t864&83)8;@13>EuXN?0S$0-*9#n0mW52ZpHZ;Y z*lwgQ32ZMwx9Ut>&Q>$s{w*|XeGZ0WE7Esh4^Z4nA+c*^>#;!4Fee5}r$`1%CrPVY z&j6>x`5W4aV*0i_oWE4zfmx_$%mYxJais-NfJ+d>DJ09wDpTWZ3^t&^s8V`-j7XlvK!>fa*VzWXu@%MN`;<&Gqa#Y&_ zCBy8M>l;ss89lSDqUh>%(brfLT)fo-cn>^@H1i${PFEj7H?2$>`CiBqWBzQRCTA7* z`L0v*o&;lRPXOpJ4|Y~uz~tUVCCOL;&+M!QE!FM_T@rzUVan*shTgP5ikZK$mEvZZ zDe&;u1n2Uv;rI7rP^njjs9t*un#R$A7b^0%yZ!)P(Tah#YPVov3jH`d#BfvF^HO&H z22i$ZH+JaQ3hx?`41)Ahr8o^I<)+pn1%^3JU!8Pk6G1VSI#G(u%E=(=q814MsRU`k zVd!*fpvc0utdjRaeQIhF9{B)H-?|s7Um*P0j+p~joEt1nSsMitW=~bNjvs=Lt~~~C z#A-{+%x@`Cqn^kxDe@jVo??Q&1u3FWxr42S+F(`OCfsn+7wvRBE@W-Uf*L*xV9Zk` zpM-puJ)aN2H0jG753hT>#JL~nN$sN`Ve^zA>`ra;3`W`m!@PZX$_!tQsgw`zQz<60 zC||LsTL>6XuMNTjoxtpTJLIb4DXKq9freg#xG4kgcw`LZg$ICgfM8r$FF1eISTycp ztf*UY7;ii5jQVIEh0Byy*tSbQz*aL>#$-`U{VQ$3AU+m!uF?UIbaX`>td4@i-;3qj zV|n3W)t^R#P(c~Y7XC_>nodB%Xw*jL}cLTSK3OrQ9o>v4Bo%Q$t3>&rb$!y0*typ5rpYa)R zdlyY~Z`1+wtC1e`TW`iQ?GK~Du3eGE#a#R@VIRl5kspC86!SblUkEEZ0%qv91xbbR z%6N+ll6GQG-tl178q;{he|-dNrVNCYD-Uy%Q#J!NyK6_JZW4@U?Ar&vr2676ha=F> z&I8e!Ay;wd+MOIToj%a?NxMZc14n2Hk(FWKxKBIq-rkN_&Kst>akUdjONgg(ghkMH z=2@=s82e}ueex2y{Rb;N3eTIPqF$b;c}p7es(%OfvGhS+x&zSX@N0P0o!uOBS*{2w zDQ4-d8bz-$p5T^3AGEeL#Ljp3s$8Z+U@?M9t?PoIjX6zMpdAluhai}xNdH$69N*U& zRp-n>H?y35Xiv8cY4H=3 z-5U?94m)-QO|j?T>O-k8-;cWYo}{e^mlWuv^M8d$u9`lY^0^lhhS>tQgYAg^qJe1X zv`*;v8ah^gcRR;?mMemKiU9*2D8k2d0$TR%ffUh9)asU{vT0}y3ZVqe#})D4#;l6E zl2dmc7D?fFke)&Xoq;R5sG$=3YIyNsS5Q2$0~slPgS{WOLMA4k@gozOrAJq@M8B_9;WOb|_xFu4rT=_$wzMPshzV9NC?d`;|6(-BpSP7hw>U}VLfWML?T-Zv<1Bv&j3}nX zv)zJyk7GEt#uU^yO#n}FGgWshR3gh*VF7|3rBv<{EC-~g^}_r^kRO`{$EiOAK^ASK z|Bt6LjjQR4`gocsNrfbYBuSD~sC)L>5-M}%%$a90CqsiK6_QdCib{r3q2Zo=u9T=m zgDFHs$ecNUJnNkMJkN{sqF3L~KKHcuT6?YEZ*3p*k1&6CvL{+ya9R7D414vE=zKT? zBIbw^(;G3{><-8-WN9*^_ua{rzG{5`k12{mCUBlQ3>w0pgJYLtpxXXEG+5yjbHr@T z$1}(K5S(pyk0knKvfbecY+l|v;n&{`rs9)_!&8PVRlrO{Bi_S zmGvYpt-Z)#vm*+JNsU}fTfBk7nd|QF{XsPW#~xg{FQvFX5v8DRxfWiH2que@{Ma*d zI~dVDm-Q?UWNOF85LLgUtaZmCX*JW77(2wY@!l^Rn7oXI7MPIzpN4R|yu%b;Uhia< zem9^nqXLXBdV;O`b@1}7kP?q9PXV5^0(Pu+B$e;lus$Da;gQBZqVc(fe;sv_6DFpT zW%qwbn1Oh0hrumDOnli7a7(zgH~Xs*7_x3S~F& zZmj|gKjpx~Ee2p=pD8o=`O&H8nBLTWoCPd-X3iCj*C?oI$O4)7Oe( ?I3YBF6Pd zyo}3?VP}g?NS!Q>T{~u^n5!_6iHS#{8YUit+exifg^^4$ni0hpvqrxm4i#>^?OMMBz)V9C0ULVlZN zd|})JsLi_qy}N!Q-dg9tIP)r)raq7=9wA*GlP+bhWaErTc4h>z>l(dCT<;5POwKI& zv!R+7hd78C!NX}2!1~G!sjwn8j+uTe1-(;K;E$>y8+z|B>F&0ZUNh-P*TN}Mnxe-{ z-s#e}Mw=uI!5A7bK8RU0&)#WW;!@V!wHLYdI*4Uxhtc+1M)6+vlyf}9`8Sr0RT4%N zFpCxwDGEPWmZQbi)&!C26c2hzH6ae2mvZ-?U!oswoR=yd zjvX?g)aMfV-oJvFI7~ngW1H6uwzz9A4L4?=?&^_q12{o^?gY*t$2W{-6Zg6Z;-e!U zO`MdW`ccH(*IDCq>m-f*cz7* zR*-&*JEcFIg&ghAqUxiVxSAN{v34FYCuY2NvV1U*yXM`CjBPuOY*9NyQ+My-S`C!0 zy-_+S!N%J`(NtS>yA~@RVj6YYtC|0CFR`HEw;mhT&Ygejt;U7DGiQG%_v22uM(`r$ zo$?^Kf|#;Sma@JRuW|E7_9l@HYsmVeY4m>YDw&wyh=mnt4m)-YiDN`l_9`nLA2tZk zXm82&2(KbT_CDapb?+pP`)?{}X$WMnTQavv(O$xI$IS*44+Ua0+E0`DOzcAPH2RRu zu!pFXB+@pEw{oguYrwntBzkfcg8_FR*tA4wJyjv8zD0B3;70|*jGxoF(~nB{w92mh zOwxw5smT_mPkJNUerAbWT+RPRou!CrtXUze5yp_mPfbbg$4FQ|G>RVl-pDy7mw?Bt zFfb@8gw}`mz@RipvY!0EQiLm6EXZzc2G67nc}avRZ<4(aw(OP(181C+|IDA~Bw}2Z zg_Rn_OuDpO#vSw~(ZlzN!*Gy&RtW|cH9L_9sk>+ZsNmtdkT>ZGGE zUQ5zqPW(4G5K$ltyyDLvZ&9UQrG8F(hXC&|K3OJWmMAlVI>c<%-6LBvCW1_GHY4dH zG5vY8hVJS=5sE4R_cdN>xcvFd7W~yuOWoaK$niDL7-m7IT@C-HNSLK8#+p@HxY+$pT5`= zw5R7w+1meAJVZ+)(QBx2P%I>MT}L}-bR>(*ukvc6L#g$NW-tsM#CP5_j)<5Y%9qxH zn45?EWm_GR$*@oTiOq@8`E?^N6D^%UX{30LX(tf#o5Fcmzd5OeLmQ$&bW0GshJ1_O zg2mQQ%D1k-8+keJpAt_i)4S8!FN64i!>c7so-*

    22iddXI`Jw>*p4j^sE2D9kf zLBist&e8zE7Z3Y`H`Z#z+M0YO9tb!folSoZ+O6kcRf_>NhX^`l`XO?#DwFR!K9-Jg z8%X;#MDVLW_(+(M%8G~PQWXC0wU^0m#*i)7Es256D)u6NprZBkFyiy*I8Ivjz_|Gm zh>Cm#n<%xxsruJLWc67HPBx*%v4QkLU^sb|_LhJ2J(R{=vZ6cwoZ$}!hDn$@+@bNe z(L+q)!w#~$GlIxEYb)}1cQyYydxv7X)k0F0k_zeV_eq##|J8!AP5`uQO9$tR4Y15N z4XQkQ(8FB;VMK7_5yrq)>K50tKqzF~|YRq4_t7A*r7n-pm$M$qylO9g|eZ=4SvsuEV zC^6QE$$hCQo3pEt6D(|qRp;M?eJfCGUv``G*DrxWyrOGHp@r)F$KZId21swbhepgg z?ks#=Hdgq$Y>MEs=nIz{J&dKDnJ)B9o-W*1d&9HC!-z%GXp)N<+|!05#=NMX?8UCh zT$~-w_RJeeHmP4%=yW;2wSFrH?G-pi+#**>*pt>bfu&QqgsJ+M4hDXlV4&|LjH%A# z`u#FtPi5A^A$;bfv}N`iUUMR*A70xb#u+j1VkgPwPBoCPsUJf2{D~)}E|(QM<2vD< zb_;{q_h5jv0`dAml#=9^6odEHMi5inu|X@z@=tq&Nn13y;6i=2W;zwD-AzgPwjca^ zzy1>Dh!Qg%F|9h@vZIFsc>TXa$dl7q`&solw&pN9ZsXCN1evZ|RdC#$b@HA9;RD$!z=TgN(^dL5#dH^ilb>PUMXN=r< z#?}Y=2r08-*a`Pk;+wHeIDa69iI^+OIBg+fjvbDZo#|%H=6$dw8!U&Ad5y;vIud>5s%{jF+{d_+wM**KD|{pm)o zAA8LfO&cbyCP5i>u0qVM2}fmHuFYi&)$Pbm8&7tl=YGXN@8O&&_CZ&9RKQog^N*&Q--1jv89Zy4Nj9(*>}Hw*7O$!0=J3AE)_H#i{RoY%-YUh1-*;6$&`afv@GE$ zOj%_>+Pir0_Z?MeY-q5A301Bp1Tl6CUG!l^? zLc2WGqMvUik;aP!eErA)wBpzi2~(#mMWi6+@y(U8-=_PS$GidLbdZeww{kq)vl1J~ zem0_hAQeR8W{+M4;PEa;>P!&_Zx*c_3b_s@tm?o~($94l{fDcm+IEce*zlPTDeg|) z?E)pts7NVP&qU1iw-&N)wj0=-U~_W!Nj4iWY9H-9GMCl9MT;q0w3A-58)Dv+NctO5 z<|Ez?cD}e2V&l6p+sB7V-oTl(jonX}PmYjBv;OeV(2<7pTOwh$L`ax?#7t@GEo)ae zlHGo2O1k#yCp+kuNLN3<${KpUlq`+J#3RbE2I506LzU}&5akMvd^n`tvtZLkt|RuB z`_l_eHDKkkjnpT$V_Vz(gIDA1C5(y^Q-qjxaaOX|-E>%~Q!ldpuoZEWXVM3!PqLOt zFQL#P9c!J+xlv+mO~gcv_yqYqQecY~u+m;;M0HO;L42wYxsiRZ^w_jHw!*Zlj)ISa zJL!Zk4R`1Y#2gA3E9<)VG=HvZ50bcS6^TvEr=jB_B#f98ni`czbJ#tf8v^S72zIaF@<{@I%&kB$&nv^Hk>er3* zt^5sN+FYU~yC$-%zSxI`{b^O-Z%e`$^Qr>u?y8Yi_}x4l$2{@?;lQr*ZX(U5NU^T_pMWIhvv2$F%M1!DCSlG_NX^#D3ySvs`rtoqQX> z3$+DzQg85s=>U0wSrXs&-1UM#HB({nrUp_oN{~6L2FXPXQ)0d&rY^Kb_WX<%+2-4c zY}e^e?6XhN7_&>P*7q@#W}X5ujZ*Di2`#(ua`;dQBnrTp8SUM$EO7cVwlR zA;f{xCE6XHvaN~h>B4ivSj+5O>p{rT}FUpeVZQ({aIGby%Ewy!yswEol~-*X2ruTLFmW^h=6 z_92{0^w9{au<{i4qFQq8EsQ=0-zU{e&aeyeLLjJW1)cw^12LGhiJx&Rgsynp06te@ z_^=o&B4T6FA?!A~lisxH%AfejI?H+D1qkmJXlyn$W>U zM<|~XL1KKC@G<#O^u*robevNXZ!>a-gh^Efw=%>S&hO}SYe5Y85w1ZNDrO6=d~bzY ztqK$MH%lT$;PB1M=rw#FwhObRIqXr`rTV>78f+gjn2s(!K!-6uQXKV;zp55M4|nKJ z!xrRPaH>aJeeU>e5p<@OPuasPqi4efJ!6_F5~o^N4P6 zrE@}|(B=%Jw?$VA+&V*#*-(qszVzadB_v40h#k_HN8eO*rnhkZ&B_laCCpAGW-?;( zvpULGxqFeoYyY^g#5=5}FiPPy!jbt5y@H!e6f|HuEA|d%-900f@Dj-jST*4c%rEOt zHxHadZ~U?)4K>5r=dL!i{hs!8`q1;d>9QCJ^LW3s8c)Qmy4zRYKi``8-f!hn^W*q~ z*Uu|XzhA)`mMFk+H?~ya<-O>ZVEtJkY1p%pUV#6lGjQjwA>C5ZjkaCZoAmo*!9K54 zp{f)9g6YT`e8{|=62@A&nk9&tSKd*6{#-NXw(&bRdZ#66oszG(UcZ9*(^7~ZfU`WX zjaS4JKEz0;`Z|ahv1{mp$6u)bJxq}I{LCdD9L&OM<_Jd|<_KZGn|SW7D|z^K3|WJ# z!GmBOVzLqx1;^hn;M(6|5+c+;h55^X{htQI?mo6+=N9357;;4XNpzQ!(Z zWo@ll>o8o4x<~%=f5z67sta|;d<3@&#!kK}BA6}`R6#XNjt)7 z(ykM);x586w?MXdt`BjpQ5PcWj6lTPQesXb#;DO;cHyrlTQISjyS1}SW*v?i5Bp2Z zqb=GPOfLiV)80@RD3=N=o?~&hzIYpQ8%KfGvB9K%)Fd>O$$*W+^|^U#d$DgRZ@6w& zJSS5tmoP5M;5HpGpU1n)hHVdEj}1#XubNXNXXqY9rRr-|JLxX8xL=2~^DdzK4ShIv zR7i8!#i=Ak`UarC-cBS~?@dQCC%Dm9O+Iq49+%)c0p>0mL&eqjC@+X}5cASH zRMy=vn&rp@?$^y4qH)kx@o({UmVX>0%*Qyn99?@Id!<0ky&F;q??VhGBYWx-s$302Oy1U$va0w*)`QF8*l!I|c=4#9 zDLU>q;cVgs*>EsM8#m}RK;0%Mjv%Rci1WE z=GN4r8XA_!;dQ(~HjcZ&ZykPw2ya8^6Dt+kCgmvkIs@-(0te9vOHWFeSp2`iTlFf$ z^mIs(8OI-ELu%u>PU=rc|KShd(|KdTd2j>7FFXtFVg`V}(>ZCZn-~s?b38IPeJ3y5 zv|+Q_rV#(xfwbh_U#R>qkp!m}@m}#mX4bAW{5dk+ zm(tX4{e`5@jbLyx74#}RAl)Vxg8E&S5)WOR$NKYXUwFp4vHm*~NX)y9bmgM2(ED>D zX}tc9ubDoGx&|JQF!O^YOcP?ddS=T?FZ!^yD|T_2>kGKZUVCVANDrYZ?}e1#7!>c7 z#vzK1V`8W-x>`MHI}JAU>%we(qRDlbK=l?shPW<=$&)*(%xz9zdRB9ngsBRWFrN_9 z#-v1+XfTn@C|SsjdGnI2RF9|Ae)JZ^{Kmr$Esd_kLH>uk(rUzsG1j-5z}P$hV*6RJ zXG_-*SwwfLmyiX^?(8D#-eCPSqALw6@sKcgl$ch;$ojpM?fKP>-Pkmmb7=ZQgr@T} z?X`{&_5KB3&EXXg-m8U0VcGlD6=^Wdy5x_rY*GTOcshc$ZZIX&()$SF^RjXhiQL+O zts2r^ST&@RU})}6ULgjzPW9!Ot(9tWGk+BF<4#(04hbDVf6En`JnIb;Uz(VBh$F?t zIqae;BLBrb5EBovgE-UO0iADtaLeb85X5I{kN)J+f1mhX-!+6@-~TcZ;}#}ibPgtvk0uHW=u=Osb`)U{Mjc6L-o0FO)5a;tPXy1vvNn9@NEthK4qm;mzw# zY;{;3*VU+zrJ;Ak^DpUKqG>CCykjb}x~wT-o+^(uBg7O8AHms=m?yJp?!fK;6G27} zJ54puUS{4a8n7`b3mo&%!y8Kx>6T1VeUrD%AkM|TdZ8nm-1n(d|I{hW%*mX0{Wypl zwfqlna;TZlN}nSaS7WQpZ%h%>bZQc3?6r@JnfX_iYw#N0MxUjl;u=}Y-RIKOMaSP| zQq<}3Jx6LEts0J>1~xA{T~hFmo1Yhi*xu(&G9Nl=_gn`q_W#I|5C7zzo;flRa}GBf z{B5idqaU!GGrabZyBb<2;~LaSoJ|t#XZDAQyFd~}W3!rDC?=}}@k+IJ-VHEpsz-O_ z9O#=Xv`0~#b9!QWx$z{qJQwNaf+qCbz|_w+kTM-T2oZ(mK|{rB5Rn6Jv; zW(8tO2ECBIofSt4J2NMDECP`^ji(x8s4;)N2`|qVGILBl3b!)af){7p!-I-3V7{kvUnk`{QC|47N zm{UO?3I?Olf6Szja+tJO=rtokF*`1e6{7B@u)`rVJHHH~x83fz1Ym0~NEnYdr{PMq zCAFVEi`rJ0l0O~X*qD-GG{j$rPSp(H{Z^()7_qe%|2+>PCR5W?etW4U`8Ro=JZaQ! zrfZb0ShDwx^g)~EodfslN;Q$VLyKc}#Ed{3SZn^%gqj&z&~1~uk%E4XY{;{=H2Ap+ zeU|Wquh|+YVTLO)@rYSI&`KUx+sKXd%aA9GH|Ljo<|=k8)P+J{ysAq^WyH6ul4z;n zUlke!D}dF!faVt|uqi}~_LJAa*9tY_x7msPoPG(+aDMJR^)_t7-%&(2b3AcZZk?wQ zvpr8;-n-*;?!wJS@*Vegk-_Z>63Jo)jksDr4n-yF)O{I3wnoim0v7Sg*}DSCm&5q_S1IaD*?^amCFfvQ>0h?1^aHyTtj?{QG>~oCs3F9! z)DSkLwq@N?0yuFsCdyJoE@DP)tj=4zGlc)Ux(C033FOYkEQM7MV?iveSnhcN-gw&~ zX41NczDlJCPlHC7@hA_4-r$%VM5fh>qL=`%@+UsLB!-J8^;O} zbAL{-)BQ=U{MXwK{9hAmIK1e*V!5ieU>sQl9?P-1u|81>IYe{d`>U=>cQ)EX_CsUB zGZORS6&r>Z|FbPi7wg|=~K1{t8dovA|_IKt6q+n$k{3~&CP?^`PxZ*uk!}L ztHdduuKK`4@r5|Kyvj8Q3_Wf@`X#(5LD7=ft3GXj7igWmLf&3F#rpkpf`x^zm`!v% z8#p43ta(_%KJ;59t!Aqdb00DM>3*{C2lH8x+6o@MZb*AROtITSM-UGJ|F7jxgO|Z$ z-sgis#v`bZ^OEFO6qld>HHs_YjENJkFrb=03VwsdkqV57U1oaKC#gL=`b;rzjwkCZCfpFFVf-(emnrkiEQSZaeDv{GfzU;6Z?)`d7s4%&C!Wd4wHv-Bb8s)mV)h?j!VWbQMI^w{}rB z{7mZr#$~5q;w%N248J2O@>je*O#%zk`H>ORNOwJ7`g7q;2v{(m)S;v7fktzxcI1?V zu~4Q_e-UHj_f%GP|2TWRA(yw?mP1_d}%bYd)GoZ zSy4c^H(C70lgEgCN+7+yuL0KWk0!o53V4;@_SEb>T8rXKGsdkGSJQ3rZWS#9_aO=2G5Gx+}^RePl?;uTG6mQkVaImUpISl81lBF{q^Y&lT$f&Kj z8k0IWaW0l@d3le2@Oe1Zib;|%e#%mW0b-oA)ws&9q0IY4JwIf0H`t{zh6YVqCx}s} zc5Et~zKYEinBqpwRMrSY)4A{#Gl)Leg_RCFO8RW@qQm;!fkPHYiI3ese$7c+ns?@~ zgeg|m2znr9+5=5)qTPCSyZblZvF->_-{?q|$fx+)8_$3~Hgr+@hULo6v~3=-y?GAT4i%-S!Vxn>V%cCVW{ z+jF}sjB9t4ULQR{%5Ow3RnuE1rHY4`Mu`~zt~dqbfIqbDW5GJ#nnc=T-0|bJAN=U= zO^(}Yvy5B4sJhEM3G+bt(rgfOHDC~Tp-z|W`>Mm#ZeBtLZuA4lSzi za<533q&ZlMm>Li7ehy;~X6lkok7a`R{4As7t%m`VHEId6Ms;Duw5h~LxkEc5Cd73z z7tLSf)73h&r9IYz-{)*vuir*`X`;->_Es5q-fRTNF}YH|id4&+&#{ z5pz$uLr+A^&HEAD)V)V!UvqmhdBi|CmYdK2}z}OP@_|s+A93dVws>E9cZ_nK66y5($%qy8vbcvk=p^@fdgMMmTq4 zhAEplz!oe|oS}Jx+6v-uN1q=#&{|O{sfk+tOObpz#BqqC7B_TW4v)@A1^TY}{OhV{ z+0qy2Lo`PR&dt5X*A2TRVY(?b9$tv?tVrh~hqiFuoBOl+Cw1hT!*S}|0n;d)vEo1A zvQ+U9Q(TY2!&1+!7;;$e&4hI0GH&jLYToU92H!b%N`Y_GLHUU`SwctO%lv?e(`F}$1FA?J%E~>-N(e)tIeu-q`fGHlrStpe%}TuSFx`H zPtRr8=(q6b2H{`YXfXO^&21eLA{*H-2Uh=?Bs6b(&L0juBoludaf~Qpwj!n(jZ2p8 znoJV53}RDdgM=@A0_b#-$;4ichRuUS>mPP1}5R%$C(#FR& zOm(*$>{7N!9$h!4RDnv6F+^$|g+$yYMb)>(;NPTE7c1&y`h`ozEUcu9Ev+%{2XA}a zDp#|4bL)=ZZaE25xm`>EeV z4AsS?@M702=r{T)p_lCF4A*8ZbZ8jgZeau+^;w(xXGHPyn#(232c^a%8Zp0a&EQTa zN0Rz6j;wZDfe`)p1u6cqoLlwc47fxSDe=hfSp&K4{*rjza0w&c3w%SXmhisbH2?Gh zQgY3Re^z>!7Jf6P|5@$e({y_g@umGzegcVzx&F8<=a&;f;v*^B@&M1pqRm3WZF|=G z?*w$VbWwJ6pigw)MqVt-m^`$ae~C`am5UuZo6EN{d^ z4BkzPeKy->528Cq1k*)3!%6vwr~L8`Td}3L8)b{m@dZAi5+(&>0sPXk5OZzBQb&E; z739kN2}~^~L(r&Srx-f6FROisGYKn#Ab(p9*g8A})iiWYz%NbAZ!GoGpo4=Q9bM^7 z-!DN~!Z>@jK{lCYJ;cOgK>+{!cd~>LV*$j-5wl}^Tlq<285wKk!Ake75+)r!tT<5n zhS_#SwYTR9$zMS1Pjh^C0_Wi1zhym+aLGym)owO4@!dF@`%8zU`i^H!7X7GTr$ZCF zoaC3F1C#jM@XCVZ4a8_#gIqCJi+BXgVt;V9SF&}6!ZE#*5VbEKERAxd;8x6U3|7k} z^DJ>SBBr>m54AkgjdrlE;hvg}WiDqv!ml=}bhu|a|7c6Ngb}w+T+Lm?s1!QLLt7KM zg;(aYO&fj?-LPCmYj9Vgd0G)TVhe(3-(EPR_Wv9FS7~6a8nZR;!CG{G|10p{*T`>7xw~#zlhU&G5@wVB^KI$L(AI|x69fY6wX zCTI3jCCo164*dc#XREj6*BB1v>+M!Cjc$4{9;cGHc^CUFWk@EEdbF@dXhO@ZukN9X3!X z-F%f9eb^^3tscU~RSo3J;XpzA&0Hp8LX-{uKM^CF-Bs57$C#yXJJ>ljBXG<*q_9lr zA%x+CrLZd0-~0^)W9L#Zj(H8Hb?6a!uNJ<>tOW0e?ct`Zl4a~QfEuSh!t9Y1tnSk@ zGN`AXAkTM^Rx=Mb8w>|kS7LYfyAiU@ZQWS}>}B)nO-Ps42t^AF6vWz^hb2xf-?API z8hQAB5HG$Q@?ie*N}wGb!FyH?@ixz9$@SOZo=K_vSZF*mcZnnhK3ZJfn5PoPK`AcR zLCmTnQ)KUCTUkTDKo(TC9}d-SR=lg6B!rDBftI{7c&EH#S^Ib(me4Xz||Nc=H#tlnYGt`=BE+L z>aJWSKQGxUZZypj;-l|C(z|Oo3A+!}bw~q;oZC|FY1{$lu&drC!RE2t!W$NHuhHYF z$CM@TY~I-Xf1~Gc3zpTx-mm*4%xmRK>x~#|w^Op5$4A)lXA#WrwJOFQ8ajIPByoRc$&-)h zQ=JP(C5)L;N@9tay}l=98=f3xtA-tBH7>i!?E7gX$0b-0<=CRh>2P%eD78E-Y1qAQ z;w|p2642AgCj(Rt@;d@|kWNoS==)(Wp|Wf*xtcqj?=i@fYK5PYFb9;`njK<>oH#Ah zQi*0ge;sAftsjZ+k#guz6D%|*K1X%rIe5Jr75V7eEB11T6Ux3P-vyOr@5s^%<$V2# z1TrmSA02k$HB8zXOL+MOJ~_2NjSvzg%oJtrNf0yoPo_-mbO?L@Es=Q#Y7whsTiWMY znBYIB5xkbA!9nxsaQ|m6_~%@fuDeBrq=kQXc%0mcb=n?B*xD`h`>;9~Q4~jhIXvW_ z95=(tZj^*Mu1up`5tHbDMYikJdgfGensup2CO2H&x~0`-|YV5;3fwrS*M z^7>-yLUhH|5Od=W}A5urdFA)%|%R!^E+AGr%o(zMJCfr=nwhUDYWCS zy@F-IOQ}qxx+P0Frx07MM9iw^Kfr5!Gd+3eY= z09KHe!);#BhDGtu*trma6EV$7RfG>>x)pnH+itkX^dIpob7M7x^9i(a&m<}L6ff_S ztZ$>0(F5>^m!quY9%wK83^#74!=dM@EQaRG-dt(N245S>cXqo?9AZ?+0L>t_CTau` zF;A7Mh(N@2iC)9Ky5qx*6Rxoiy&mEn|0$Zeb-I*Eiv>wl>>Cin!KB19Qr$Dm4JVWw zIR_(qH}L)$qvfN&pXMzyXUT`1KMV(^Ys32wo!MYhC1y8nHu%ya5wm-ZKi9slo_qSE zm{s#|DIx*=tggBREju^m8n8$4!hXe`|Df25H@=k=V8P1DjTm9 zj2fj!{$9xxvV8yYL(hGZUYemYhCYgz2WJC0HM^d~_47?;#kCP$FW5z2SQrS-s`n*Z zP*IWZQ+NlWBX;25IZ&#J#?3QuD#oET!u*PLaB+OJ>_4w4nXZvP@TP9Unl3H8Mci@; zlc$WKlMpkZ>qc(O$+2YezH;WP?JjK14WdPxw4@s-=X?HO8HYyaU+=)Iol_*Qp)iaO zM7cuD5@5gDyhcxz0?x&CN=-EC^rAYtsI)!@R2;q*c2H||xRsr$5K>=vpM@{45eiR~5RWdtti=lJ05~qhS&=Ud6AmA006yFIW6NR#RAFPx zzujM;CUbigL@q9W%!(K2 zDRM`h6y{>bgcw8TtQ#a{1Y%)D&t<5T5qL~#kS1R|d2UY0)fl?XI)?0e)180*(w{D- zYIJ~p13&CrZ)r7#%8Z}}F_nvd7aV!JowT3%oaIc_5axS!Ra_hVg^4~;cAH(L9w@Qm zQB>vyx}W2v!ire&7^*vxsvbW=d*2Qu#y1}DbM==|3wITIb<$?OYEOWKNy5zrgWEd9 zjLE(zkFuUkj%&VPoIFDq(a%?r(JhzdY*NBOZP~i)8tVxyOE7s_=Mz|e& zNU{88BNHe4IbJ`EZHZTp*AL9L%LT>aX&9>G2Q6-$VSFycti&M> zPp?arLNSdJLv_z*BdBce2zus$Ciyd;W4k*sSo%c))lchrn=8tfR)eP}zO?@k)8~gF zFWmJ<+vxW!E$J{f*io*SuiZ^>zIO{sYi>x*Nn)t(J^ZP(*@)r`+fixoYM_zuYG7}n zZNp`5y~+RhoA#(!dSeY{Ec zPS+I%-#ZB{*;pfJ!krmIb+K3+>GMI#2t{u=$i19t?+4UjN6x>wvf^$>G#>NokK`Xzjj(-)?5OCKibUsnA0zPliroI2y6dT;#y zsnELzrAzSU2`BrB81W!jcLJNv$2kjZ&wfygzecXVT_nub_9yb)X2j~C2Z*cbugnOH z5p#5oAP*n^g7-fDojJZ732DxmiYM9Hg6i3uP^$YFYCYnxpR)>DFMNb`GR)pk8#UuV zICKpuATw5cW&_uZW*0(s3uXRo1>-3n$;Xs!!tEPcyoh+jf0$FGh`FN72%Hh)aWKYd z!<2A#YJr-tr@tS}dTpdI#?i*5k5RgaqNShrxA zml&?0cm@?V_`%^6UGDfb8!jcX0k*D0IW}UJDpxZeF;G2Cw&rm(D=XCy2Dfg4SEYLd zdTp4X9sCHAY%as|O?p5&rb}*c6P?R}g$tnAoJ%UJC-MCkjUvHqeCVquc@T!$Dm$Z_ za-W(mv~tri3G+p%VV{AR*Pjw(lSvHw=iN?Fe>xMi-h4*S&N+gpUKM*e=!C4cKTd5sV)`huZLTxLG_*8iy#>J;jW`pj$bFO#Mq-+ZOX9 zb|jFX13t9-j!Kxk;sDXtF6QUn8A2Z}IVE8pC^Ldph#BqGBHQc~$RhrB5S|!Kh9Q9* z{aLy}@H~t=F=hl}jlgkbp(MVL)T<%)p>q#2D35N#K9n6HM*gpQrENw`+)ORbnJs1G6netwBSx@PwuR2r^Oky`+<#$>;C!%hvLD9K zV%L!AhkE!an*u9KIZSVN-C z+tXg__Cn;PeZ>2R3VXSw2h}ZDC}C=qm=MG~$gtpU<6M=;*kC|o-nSHVoYrXg#pZDxr|M6so zGE|R3%!{thT+ZV&eCUs^LPrA^PJ3peDcMk8yj|iI&cjWg;Y8P9Uge}}6CO{dgXClV&UI=Fs z7{)cd?IDz1>jHB=AEOB;CrFvJsEY7UL$?vUQca(B3K}MqLdEyj;CbsjbemAYuWsE_ z5MAuYNBn(UFgE)vWMr5_FJ6T;D;lNM^i-}UA2IdG;ar^VJ8pKmiSP%7NWAkQddW&% z+6BZCSiON5BJX(_#!=^m82;f5?)q zRK<$N3YaXUoezL}n!((H#t_*L{Rr@kwh}xZmGPB}$4HoG_|h=ss6b5Hj4fOkW&|6& z`v`MfV+47bH|_qZogk|4#G6~uPFK_vx-`2$Qv7M@f>G zlreMzVxj}AIN7N^B&@n6O z-nt#oM{g#byG(<8*s_tgS%}qKvp1kU4vhk3|4Eqr%HQT4Vmj=5F4Nx|KoqOYg@`53 zg_0$~WWMT3X1X;EIzMv&Q_Fl1RS_E|=t*(~F(VM=*cGwA(7GjF4&6KtBti%ImYxe)~;8ZS<81ixt9iC(4+&wv~KYs?HWKUrJld+fm=zY5at?2PMo`W!I24VswLd$zNoY#kha>nK;~0H6aKb?_QQ1$4uXafvJBgBxNXX)tQ!zE=%7@{jxifLvJTAv#ld( zK%6=)-xa{`WM?JJLuETpXT&sLO_!Ib^dPbygM^kzT5M`ntRlp(yCCXsO#dWGCZ}SJ zz}z7fqRgk z%;-hKzi5*F*>=n(1LuOHH3;|UA^*={frN=szBCKOXdJsF@At-*8-8_&ux$pAH@|qr zyP;^j)UFJ)bzo3pUyausKjKY%^IJ6Vy7{^UWzIezN1u0o7!SHXPYTi*7gorLLy zrzd6vGQ{+C86`iVlE`1`X)oxTwu9BqR~74W2V+K14(XVgt=gXqVu~w<>K{B9H1~WC zY-AMdSUH)@a-AwT2rX>atNp@@23Nu8=^-+-GE8{*FO7+-X~e_>Lyj?s+1UPGL9nAH zQ}h@nbbM0)PJI#-L-IxnRX9T}eFd5`jz54iqwYZS{0_oa%lZ6*t<7PqA~IK>q!Adxt>`fe5EyW*H})J|{Dt|Zp!`efRi zK>oi*XBt#D3N{?s#k-w(!YQf?A>rR13G)N@H2iJWA;!)qLNq>8M`88}NMz~UTdP*t z5ZCt9K0Zdm{BPILcEsrCUyvQ2bA(Mub{3Wm=myq5#xYj5QE*gX_Uw=YD!E3GH98Ga zUSETlXP6P-fb^S5XUM*Fi}?|1bI8}^0Qxbt479RGk&B-{L!CTz6Ouvj1N&WeWHRy(9vK)e^A9S1|owG1E*DEC1*_Ql{bN%g&bR~XMn z93~bc1L>{4wJ>qaRxR9(3(>h|E9riZ9|UsAblE39|uP;t_Ka zG3L5z+`iO_%w@ntLBH26;?yOS?pwE45Vg4Rm1*G78Y4CJiSDDKPFf7rU%Xrb^BQ`v zo2&PbgZBOD*3L&^J_{!c6F>5wOMB4R4x1!QLx_Y)M@&;*7w-O$-fVmQWZ}$PCpgxe zKtDZSE5*?H-_J^h=b~9-)_Wz!+4BoD#fJeF>)F96lq^eo1hJ=_VfYGP($}?x|2+5- z`#iXa{jHlwOb~;6S`K2C{;=WvzCYxHXH6CE$4&#c&S&Yw5;qAWPA(UFIUH@V?Fuc8 z#MOj7#9Q@;$02O%U=}b?g(U2D6vRiDA4{$+YR7(b%*Q7~!l)`6{25|Gk4)wE*UaMQ zOq(tYU$+KQjn2?=M^ovgiIe@BJu5(Ucms%+_u_N~58oeBGwjvVJz2MIXF0ySmi1nj z&BE%xa1YAWnIilRTl3*2C$6TQQc!jiF?nsbb9Zc_3jVar5N=uYApL#g>5TS+gs8s_ z7z$pJFrqcfs=sonok#2%GPsZm`!}eveXVUdSKW~;;&%++<7s;`{;wh5w;_@>dJG^U z<~*LB_|mEnqwo*r9J2;<_b$y6zU4K+vBCs;F&_j`z-$?ZbBXYHyYGxLY|FD?>{>+e}8G>!s^MrPOX2P*o{`BUiWQi)8m({ z8FijwMj#599lBJb-bNQpmq$v?Nv0Ds!LB}+gncrlnGtun9DjelNN*42+&;p!Hxa!1 z!lx3(PKnV)%zztC-0UcS@*>Pj7!sNyyz1ow>Ol$2dH)4CJ#-v+`pKn`W4u;7Nk<@t z>Rx#lp>gjSXxh4jY6*kMlWjVDVtyE!)#=ba9`krVcMItg_@?{>j1Uuk{-dnAGJs@6 zEfEZ7{#1CaXUszLH%qEZfoU^FOA|50uA%M!^@OT+5mMq2cIX0_$aU%Ix*+OuDwGty z_Lr*+4x;3xKAk?jfN#p}E@3t)F{X%-eI68tXSvht9#B^1;+SJB$vqjUzuZLwUPpTj;qqI1l&PLEh2K zTf(eW#?V%Xd7KemVA?dF3|zcYaP+AVHieH@EWPlI#V4SSz;qX+qXBX~ww2So`VlYFWIc=Uqdz-eW3&tJb%|^#bm^@_+?SPnt)q(Qb(f`BK znaAbyy#GJ#5|Rp8ONB_u5_O-MDO-|Iws*FK5Ry>dSyI|dDp9iUZBikr`^+3kwj{|G zLS!jIIxJ#R3A*LamCWB{>a^11^qKGR%|+-#xV{u22so- zT&~maB%Ux1EHYS2~~t zjS!tM(*Wb*Cg3>xCb+5Y4g9W8_X9oSIi{G(N9hCYLNRsg-zt6FjtYt|exy&oa(v}& zfdr1*ksH)kz;kOEe+1Z$z*IrYc4`aCR>KCEkGvm*9wl}_*65)SSBmhU;8=L8`YNna zzaWlS=m!ejW`HB|Eba`7$!~tAtaQy&IA!}2aq~s6?1&^?PBtd>Nfprj?L)3lW2@Qv zsDaN(7gNzcvzrR^8%hHG29RkWNzh$jkF8C{kUiVR5I=)*@%)IT9Fs1;Iu}rk`GqQ_ z!L~l)%25F%_t_b6bF?URtm{pfGi<;Is_k4_$opw*vba3>5@ZLqI!E*X(qjDY>uXtG2x)-GNvL;<`Bw@`y(If!$B^w7m z15LRR#9*x&(?)2(`iW7+V2}klj<1g?4K;TzvxEVXpmDu7IpD=jDq@l zRHL5umIkF4LS{p~UvoJ;Ip7IMv8u$M3x7kLYUN%9u!sIdX2SGUME8Tyo%F z($pyq41c#ss)Az(8(^;Pe-qloK01M}ckU97dw9th+^~ZtBi39OoX)t>D zaxhg*+Tx&{b|A)f1S|m~5yK?PrFtU8tP(zzJU&AGI$vxes-1P<+^*JA#eoTgMZEr> zoM(b#7Od@j8#03?Ho#m|Sq1j>PZ4f63|5*BTZA-y>7bc`ve<3FN#S=Q9Vb{zQ_CnO zSnfloQ;bSu&*IN!iTKHat>nr0S@7qOC=&GtkboPsTYJ6;jvj8v=LnM3$|1gR9Wv#8 z;=40oRKp_WSohAL&-`$-y+bXW-qR2)Kls(5SBWYbH7|){e#(!)af%7t8Rl?mc{27~ zzl~f8vx7B1FM*UbzFf|ed?25ywtDf62Xltitf}Pt8!smjIE)v?D8nTnx+V_UI(>&@ zBf>zA;Xu)TPj}>#kB-wkwAx1Kc)$)BEL%sI(F}7=GRRrXg=2N+W#=T-3lCtp zesB0RR~;7?CW0%be&|-|6Zp#{1+>h6As!lPj@Ec3^3@p2lK4`JS#6Y|u!!`+vy|b4 zc(_96fost!^L4zqWnJ~^kuk7-;&tddO`aoQn%fz-C&4ReMtFK%IM_Db8RhLQh3mHL z0(BoWv0bOW=s6DInD4Z>rK_o+7`^wm6c414c#d%-dEwR{h%(F z&NY0pn03`zy256wVED*LA8V*=0ZtCxkZVjjynHnl)OS(CcQg!;bLMQ0=_`*b+@~1L z9X}KxxBO%oiw{_74iI!G`UF%-a`L(wLas0&+dY$2z6uE|O zq?rCgtcAI%N@e?dF=Wg-XLx1%VHC4|B0pGRmPT29?m*8;&)~PT60Ybv8T}P9&y*AA z`(Pu(1H#gx%h>G3JUnkjfna0O9_x;}h!1|r5!h-H*Imtx5WKjmPPB9S<#3jgk+#qD!z*f?DaHy%~vm^<{< zNxwJRtJPFub>|CxUH=nCzK$m+ZtfP>RL7z(Jruo5`oi<36dNdCeH{s*|oTH0?6j9DalhZ1^rd+Ix}Tw6${QR-a;iznCJF>X`$V z7duF!;S7@GuoZ2mK~1cAU*MZWM|-Y7zr@?HX7XydXE$~6rE(rts`qnHkfRN|pju}q zAxyiEaD3)|xa_q7aZdXzX13^aOoNQ+MKO1+tf>5T3UF>nATK8-5p_Esq^@R7Y|mbS zz9!pX^>rG#M`dvS1>+%e@Mp3FPv?9X)BUOPzx!&a`<7Y4n;z}O)D#`0G_Ms7>^dXn zAUlq^MjKtUvaz6;_n94qC979~;eU3LZF&AgZNNk{dWimIuy5YdR-F%aZ}(i`1_i6Cz`5D8{|vxJQ}xK`sF4F5a^GRs!h9b{egqqBEHCV*jPjhfLX;criWbim#ae0&YX zT*FZ0{_76Z&Gr$G>5t@(0JCqWtFfn;kHjAq4e1pXCYmEOO?P(SzA@MPzkqDqK4$84ex zG{uagn9fpBNng70m^f}1Ig$36#4LY8GTXY7tja9zHKdQ+EFJ&qnSF8ae_oR?3S~tk- z;RB_<{$|AU<7pV)@gFYdvAugAGFL0_c-nTLI|5dxtxlhSmcQJMwj5ps@;o$flGz;e zuX!`fyfZ^=+?vEOMBWk1p%~@8RwW$f3jSp5CdS@DWP9=!DfK8V2UX7VIK=v$g}iy6 zUX=*{G@jxZCW&7b;)2fCN1_pNh9GjvI6SWZFtlsS3pj8{U$J9{ERJcDYiMtZskqfe z{Jx|g@J`)BG(P>tIk(fK@AJ$_@C$0K-)SEm`K5hMY64{1D+ktI%I6s7H8k4~A-n5d z=;he1Ajx|SHtMR4=6$&fKiu0Vs^Mgg*&}0CQB3sU9%5Yk2g1ydR1!LGfq4IVw&XHp z6xTzulR`G~%W7z5MsK{o7?zHI#m@-Vw;PJQ=L|viSM@=*#!!5`!+E$qPze_d`zXG7 zvyo#8~R`iGE$20QhbPl4!|6-)Y+@=3mWr;@r{0 zm5t-}k|7sgfaFz|q$c%2q#%f@A1_c*5;Zwxa-J5kiSG#5WHFQT*gsb%_RoJ~H|;1P zf^^46HPlGkQ#JDDq$*B`sudU}TE@gu%;O!8m9aGAKF>0p^ls1tN4n)o&C@0l??IK^ zImw$I7qKlaQw=4TD*52QacL?%qdgT28emJD%Tl1S(-TnEG=c=>8~|S)KLbg7KVydZ zOdn`k3#3p?eA^Y}KhD3zM3a4F`k);kbl+hKSPE34cn#Wz(}?Qy6fRNpTl$W7)malV z{8tFHRVfDN7fQH5r3VNFOGpRfYD~A6VA-FU#LDJ8ziE1M4SkSe%E&HdFGnkUWWauM zOJ^8dIXOuxG9OP0sMglq{ti5Md<$1UczV!|l->o{De4}ax6KV6uFD3U&TqpVx9)(U zDRI~*C<%YRe->=|=85M!AA@W)Pi0I7#ms1pRH_?!;&%fM5O?*P;D)qQGTtfBsR-&d zlyU<~%`b65_woVrF&*(X%OPnvz95UT*W|5#u@-}Xqjn-82?CgDD*6T#4B)!?dQ zH^eYYWlRCZbouM7d^;!vN4gv&F=@_l*l8p=o_FITzxCZO!%x<>u-W=F3>NP2xi#OF z-|donnmh2; z#6zSuY8&*Q@QhSlnL?P!sVXXgpVWIpZ>p}dl&Dy#^(r*#eF;|8o&i+{M>`DOSSRR) z2csJ;<*;@CS7CDeQ^oeI2H0#7#W5zd(M2)k6!Uji=Zn3wlkt)lhlz6i0(fN5dwhJw zGU9F~o1ALT=?RB^I0^llCEmQ(X}Sal-Z}whzKIYc$4&x0e#D@Q+Fu|MeLyc)O|ibD z3$hAKap? zrwYcly9%$3xCTx_rMPuhJPmG$LH*~o!8_iGK!5Wdu|mrfP5ro!W2VccdM(97{WngL zcr6Nlx^j$I*l&jiM;oE3>3&?6pffX@KLQ8;T;M5K+|mfr5B3ao_qG2IdPMb^Ms$7n;x#;5d$nWW+LO|Hy|3G3=Eu_#1;0I zXns)~U(HjwhHj>q_pUD#_Nyo35qT%cvBm$w4;Q1+(U8?#GIBII6Y9k8<&_Pqq1ga4 zJ1JDJoDchJcE+cEhJ)-K7N|Dp80!*ijk z_688V`-fOO+89lp;DWN-+kib3LtmY$erhVYBW#7WI(I~KmrU~6Y$M##l!?skr*I6@ z*|0nU*1Tsr8-__9^c8yM?1x4>ZShT?oAa?gpwl^rOiP~*Cr{XmZ03w6^{Z%ahI$Y?J-*B9G*5J# zhoZ9G8jIO6j{YnLKk2MoYCaJghvy5G^?TufL+xNddOJ+#kO5mwwX9OLq?o0j(}d#M zn}TU;4jJ-bx}dr&75%>4i+F3%zh`eM@3p+mCGjm@$^7WsGwBUv){_ZNC1if(5In52 zHcsw;Oh|3j#2fdWCvg++i0{>|^3|M`yXqq-W|>#IpyJg9483}qoNmy^j+&9k_^bt~ z#}E0$O3VHm(0yekT;dbR?c150hgF@REQFBnCUA78SM;;ES0E*$Vd#~4Brl^z9JfY` zWA4#cCoKm7#mw?a5UflcKv`5S@v3wo|BMMoOO`z1rgQdZQ|Vz!8635T#_im3g_YhX zU}X?}9Qx$J%@f0L!rNlFzq6xoxzi}YXE!~6i+?F5%&rhOtDRP`o3>4E-aAvwvGfqZ z>)Ar!xAhFM^@t}sdyGZ?dENQkTGsa{YC=m}b##C^#i=)+#brAJHo%;DuNka&>w^N~ zh6$@w{}B)CnWK%b`oITMj)}EuTls1%jz*6C zSG+gCh(7{K`KHaInDakvg)PyM;Hh;!nXvyRSz9;(?tPqqZ!F1%>(gdI+ukL-FVN4c z6?hxO@p6y}VDy?Q;9=^W)}OjA>8qzJm)pl9pO7x7|F~n~=RZ9-CQ5z;d?+U9*;U0D z-6+sBu7F&+U?d%E>_Xgs-@~yRPC^5_Iee^?3CA)t45`c2PI*EyF$exp>48**9jHY; z1w8L|PC0B>7^;}n5v|>QMI28BOYFA^rGHQQ2>4UXPm_fX!}GTQ_1$O5vY#ELz3U95 zjx)aD^c;$zwxBGw+9iXY+*&!o+(T)+>SPm=KZXI6GA|KjeM|&iD~iRW@5@m6CT+CS ze7pGlwlBv_kxTVpiYdB0TN$>-8+ctgM=U$tCe=xErL1*7__#vs*JxKw>!?mzR?x^WI*Z$Oj9TZm(rlHrd*Qcbxx7Kl+YiNQpd9waFC4t`w|OHP9pTxV4bdhL!O7J&(vVfM%kVu@mmM}8~` zSkVzD?=2ytye#3I&_wB*^+ZzON#l?s9zmyv$<#*o7GyUqcF{#1_x@|rQW$XbF^G*R z!sF(=1R9~Eh|S6*Jga9BaD8S*4&5{5t7$LGd2UclU1(xSTDU!KcS=b|Nk@Rc9bzQg z;)(o>!1o~4LCp)Le@h7#pR9#WU+9PW=xtbGJQ~*P?E*J?M`P2wS#;NMP#m)|6dT*P zft6)fly!6jm90ia#?(-Z%7vh5og z>F({71poM4gRX)$9JSFLh&}q?h=3mG?ck2EXls#p-9`rpF6hW2u)n3B|>-Iy02I_zr;=PVzDrD8rTZ*x>?Wy?h$qwA;BN6faSh%<*gVZiw zOoD$=lOn-3-j#^j75AyY`M5r<;4eVKcMY-Wk2XJ6z0IJLu;mkQb!KQh6 zO6R@0C}v0^$K=SE7K&NYb%vsBKoX9syhM7bHNgX2uL;I?Lr7`&CouhXJ|B`jNsXFs zNSGU*7toNpj1vcd>)pfRZ5RZi6%i=I=soEZxf%!nW9yDX@`;Cv?%&nqdS6M z6l0pbO>ygaJdPiKnUtz^gkPT#*v}-2n*gzLP`mGVp0}1ht{4`7y#upSufmMp6=31> zTVk(XX|(@NA{`#BtQ zI}zBeydaWCHfW<`3SZ4-8KXxre(0t`WyxZ^WKlU;3>7e@a5W0|h~RP_W^$VRBMw%Z zQ)^vnq{+O?2M3s8*RkQiYN#{nzo48>hbMwLKDWjBqlchhHjy0DAY+Uv zrju%$!Z>maZn}My7DP#P3ADXR(iTYR*lBtH6m#S&%Yd9{@2M&oe!zM-j>^1>W9yWwsMT%gspyY)(HG3zXntdF9 zNEiXu$?vqG6!Xy5MHoE#q&RNE4KncpxCz~IEE>@f*Y!MPypKzu+^|qJwWdO zTv%m`t?&`0dL+j$e5irFd^p<+CFj+34SQs=CGT_94^Ch(qJwvU|C2VYeIer$QQ?r zyrNv&qaVKU?Sf#VTLvrgC&JDiy7+`cQ}S){iy}D{&7BzZKP7k zUE*w5*aWvDPN{Vpbs&Z*}6msT{_3*~|0Rd=}h>LtM>x$}g*I*jTAk)Ob)Hp@K}@ z)(B*7dxwXnTIh}51#mF(p_u3y$T88fR((Citnf`0Cca+S9;9a{)`ryRhuY= zL_FY_6dALXVt&q#5XLSK12(m{$*tD`ebo|0s^I1NMNT!&Vse2TQ`i6n6&+d?=sbi#5DRrb>MKr$AK;=B*S{O{D z-I?mL`g@bdbH{LtO9bN0%9u3>%B})3~9MeHQia1Fz2R%+G^DayRp+$Ge&C1(k@Y;>i zkK?Jhv5}eps_f^spe!BRDJ%}QWzyyfebQL_q2Sg+&WI zf5}Kxe{_svp2|lNc@z^jy`A`ER&OvQu!hX<6h+iGr%G=(v|=4=8tY15HY~(}wIAI7 zoPxOLdA{)o2sr`&`*%EAgQlVchnoT#I1le=X@+Y4PoeYp05Mc`C&$>!m|}_aPE!nhr@J&CG zJp3k4U}ix9Y)3Hb)kEk_U3yiW^E<>Gq(OC>z?vvy-~Ewq^QijVxV z--gL~((*pww7jRd`#BY%=6FB6r{EOM9(D@9JM%)!+pwNvd}Yi-in;Z5vl3TPQ>9A} zNZq1Y@P}`f)O2eI2@5NSo)a5j{nR|}1I1KBTNfy~t5rc~Dz3CV2{tbtO%7YHhldWG z1D8}Z$gP57;QZ9vAo!gsVK+@h{z%tTOlN4NjMe`jb}N2J#0Nd#M!gj2nToPB9g5#HW>zu-;?x6@NYZ78I)*uJE%Gsvhg@lu~%01H>ps3u=F>~eB7*LF1 zf{Vkgx$$`Lbo$El&j)MUtCHK}wi1_?N6@(REX)`&7)EY61wo1=TZDfia9a6cP&hMM z^rwD8i&~>m$fh{+dqfmdloOqnFLj6+Sv#_S{==m_iPr|Mt?5swEjFd zYc%>+4Vi;KidTc5gMNx9q}{-)-*&WQygEwgmInH5-68fY?2X(&0>{M5HMA|oEcR7X zct7yLrP=kQ{{uC!&14ojb~b^RgRE3{SrA6eG$r1=XCuG&?VrHtPgc;?&;o1wM1!mW zzG(QvAMi-tZZLY}P4VG9Bjk7|gkvh{TYx^$3X16yHc0W9Kzz&c6`7f%4QF(ZLQm$# zl63Nt``Oe}+nnIBH{nqixrVm%dJSJ`%!gIwCU{HxFc7H=P!JU~=~l*rqPT}*oJnUi zBW)hXoR_6m6DTIZXRYGGM?LIys)6(`vxGLC4j^T14A-i&n^sCC2+b#{xhdTduvj+bD+7dG?Jr@0-3u>@-vzd^k0Zu&eCI z1TbUJZ!za-EzXI)hZ)9PR;GATOrZNK#i4F`qW+?{L?zP&Zhw3lUB2VTSHqh3_L+Bi zsm{WLM{TKr%&(KB`8+S|jqexU7BqV|V|J|!`XVe%)4;>`tfE)Bf?=M^Z|EfyWBA8N z2)_`e*d6tbJah2^lXVZFVQq`}Bfy&XzH4iEU~O1gK&%jWJwn+7f9 z4>YsWjg7A2Z|G53$GB^6?Wqs^u$XkM5<9$B9aDD38Yle<7b5D?;hJWe`C({{qf>@* zOf!8$)34`7ikYdW5SGG5VNqriX)r9pW2^U}n2lrkPMVz&uu|RWS|zOgmBhOo&GEAG ze&);~^4oj4Sl3e>m$#$~*=lbUnQpm6ue%l=Q~p_Ct2rar&|wtQZN8n5(WM{AEP78& zL$8podJ(8e0`x%gF0X9Z$S*6^_YV!?L$WLjkIAleW-cH^e-=D#SMLzBJww>>!WZrs zZBOo8)xqN?t>YLgc}O;%V%{|L5L{QefD7k8kOx;>$lTvyXn?i}_kPH_7*8!FF7xKS z{~|YTo1+;Z%X$9u?}}&Kx(BbRE)*tD+^-nlKbD!l5*p2=-Ki% zI#6{MhX0wuXK|VG-oH;ru2pA)nAOs0_@rG9++(#2X~eV%3%sX`^MY5P!P_pvbI%Tn z>FfLRM_{%*@|#65J9nINxIH)yWc~O=zTjKr?b*M;G59jJU6Bco+l_%PX2sBR3LTQA zm|69)yi{j3^r^u;(8dqD(9)6skbU=|^7*U)R8@ZmPHj3aCO)^}7)yCaaE@Z099gQo z-a8Jsjcp-6D%8nK-Hl{!2Myv`a006T3nA0l)UUq>l`{wPJOZ{FwkhnqX*^mPaTq;_ z3kRWhw~5AEd{DgcQ=ovJ1KK7$>MDRt9`B!dtS5u6d$5^rPivmQf zY$dlonPcmMC~3xGbrMEZ-7NWn-88l%u-r&{Hz%k~OQ%=R!sIwS?L8BnpSlj|ztaP% z?v8jvs0Q*_Py??nIwE#kafo9Y=`<0&X-_Do+y3#QerN~qvfnq-cm|8HeKIAV&7DbU zC4r4rRMfZd0>|tr7h!eCdDsRUpgj$-^$DGTPU<W&2?9(41R} z&-?x(g)e?Xb$wBC4e3eJ`_oZUnu5jrI+?&cDPd^KgVYN$KK?9j?o{+c=xFS^o3K6mQ|-KIxNKI`c*9(Cub z?Rp!2g#i#`Q)M@`$6<2>3I4Qs-^&`>p56vFcG`@;+uwz!R|rBzY6RAnR)XVS?g*P6 zedHJoxlS{sm`73Dm2bK(z~^&*lHQk$;Ppo{q;1HQq~EN7E%vk-Jbw~3nW0{{^gqFN z1ocVR;QOEL;3QKMpx3`jd>3znHb*I7Uk6RBJFi|?U@-!sOgqGG+Ey7egknPcdn>EW zH{&zKzX*b(U}j5S>5^gyvCO?g4Ye_x_Sp&=e?JYKJSuqep4sM%4pxH0yN3$#|LF=7 zwk}0I8;-%GJ8HtumZyq#=@+5Os34B9l*_?U6w~DjD%nN_{!j1yCO6+shDd)4d0ab+ z6nuLCYcCeU#80Ns_dyn{A6o`>jBfHB0V+KJHsax;&mjlUZ&o<^Yx)STSYQkC_bpPk z_ESS91CuzWg1$QGBY-F-;Etn%!`mp_wZ~twx5g3fN>qbGE=?zG`cI*!kjHlfM!!!( z_7-4irOp1AVZY)WfQ>}4cH%ZLw{IMpRs9vV4i5z@vet;3-giSgZ>Mt%l%F&giiwZa zQM~;aiVs_>NOROCLXE~ZaIDiDZV}F06w!)_&`13O&n!Mk?WpUf-hwFLIVfL#UCb*< z1$OBXNLTm-o9`wAkB&<5wxtOgdv`C#?4@sLx|$gj(-OE&k+WhY{_;dcDy>)zcNqfY zc+~rU(P1;TuYp7DN};Oj1!zlUq;6;L({MCHIAekiCO?zFQ#C)Nw(b!6K9OTa(6<1^ETEWSUO9@rOPsM!OgriF)v0i5zd)q+%9|@wnCHEIzXWcZ^M5)U zmhZ`i%dK3yG*WHv{@lKq%%4#O}3jNgYws5lk?hix^%9fm9i%e}gwNmbGC z@2MEzQC=?wUo=9^N9J=(sl1v1iZQJ1EVO;D5szL|l^&=phDPEERQb}C*U-#Gv3LU= zipi86E*XZ6l?EFoLCsF)*z2_sNYk1`*wwlJOmH{Y-^S?Ws}WB{Ko~zc69%Pha?FZC^_V?7D2X(51c-_Z_(g2c4`0&6=-;UjNbb=Jf7> zt>&k^BS@r}9$PjE%Qnmq-gi=$hV_05>o@F0_kQXT)4eZX{i*^U9mcwYVcIA7*%~uB zWdmh4qt)=Vg_{&V?wjE)GxZf4mZiepUMess*9X^39?dak@{S;#VqWcw71mRo&9p#u zX~@A;Fsfod%F*r4|2NF@KA4V|n&ww?hf7Q0G9SKR&3iMWYvP)L{qc^Od7|oM8{vzW zF5anKLe2*Cz}jPtIp!?gNz+>3IK}KJ-znVe-W7DKQkRZ8{l!aHZ%56i=~yYX(`Dva zS^n2y)=%niNo5JlQJF;}Gr!KMXeXI}?JWqsWg)8f93+T7onX?aO(fU4BVMY!Ca|04 zDwl(~6l1a_Qi$6nfVjaL(z$_#B!D_x?thVp-T$kA`g9m6AhL|>)80l-g_`qELJRE% zo*RX2MEs;a8@6tV6?Rz-7v^WtfME?UJg>(Wu}fPV$E=r&+aijwOI|Om&shR4#cN0b zx=YFW;F)MioH6e}*=r=ye&;1V^84vnPw2ZYl{X=oJCEJI>p+^_6=|4+3yOGEv7*Ts zX{mI8y;^d`a~@|o=9XNlmr~4$p)-XZ7eYbnR}HCMWGH!`WrsTLE1>pYj*j+N5p{p0EP zU{`lK5`-oJpPf&X>fNHyp~JdJYxiOCgi|k$`6}<$?o-T)inEFjU*m!OQ%xy#UngnC zoMNn1oPxugsQ`wW(Z>!g;=(Z%4IMha7RNEnOSN#6Im$SefOcrdgKr@b%7-ID(Dfx9 z(71?d(PfDa#~hZM_s=OtB~NX%wOb^(AE70^+oUhSE85ccOZTul9qDD(lf|0yknH;* zc5v&PU3?qGp0tQ#<51c7By@VvZqPj;L-aqk1V!cQpcrwt2r{;E%x(EJs*z$M8bg&P zR|7zXp0@P&MH!j2#zoQ|SdEi?vtYW>4xZ`7d~S16{P>V8Gn!$(>W8;aMK!IFNMrjn zpb=+{4eAhb%+^5tj!qFXA7pUM|5tQD^vTgwv;=;k4*X+A^rF59`@~0 z04-k~{h#N3;KdZ`2StaN=vXN;2i`M(G8#8(ISTFADjbWLfp@*_j?M)9hK|KE#lIz| zI0n*}4gGump_o98A4;R8y+OY^ZE41+8+fSxL1|P!bCT{{0_!u2c~{+jL@l&W%Y*t# zdU8lHta;yVf`D#C*`Wn%zYD*oB3!5c1b$O#f;(J~h<^(rIL1RhiqH7|=?SN!~a z5y#ljI*slKdQr>8Bpd+CN-f&E1o>X>VIEig{6FPan;}a{%yXj0W-4Uo# z#{`BccRLABQRk~ut|3I}(@VIt+8B2p?L=a$w}XJf9l&~50A#DVB{x$nD5fD_S84k- zQk;BFN1D{u6Qr%pl;%AcPwdUEaL;>t+ib40vAFh@m+CCv)Avg}4M2Gf+6Imw{VM+8 z`ERz7g^xAJvf6qet_mT?qeRRwvGngrYXKXI*+3AbUkO zGVO^zUrmtQRkx=YmB~)_D?LoH&ZQ30$!{4T`*Mu5#cvRIPV(GG15k`3VB}RgPHHEY z>b9S*!<0h~@SIH%=w6qF!S2J57+8tvY0I>y)Jlwaq?FkM*!-M`jAh&FuT;0^L755SYY z8lYvZ-QbliJ@AV&M&S9?0dUiBsn(v*CuQ-ScRsXy#RF$H9$YhPbHT|bVN&&hfL1nW2k5T)=dlEYq3ON@m4N?VS%;bx0lmi%_Ux{ zd(WtW1)5b*>D3WtpU}h^HE9601t9mZ2AChV2mCZYCweR~M|;~R@zt2g?e1+96JeLF zIDOg`tDEadoju=xptxn|(~}_XtKMdNiVw-!p1c8>pAD15=MH}Y+0^$@QxmKg5(i=q zxuZ;K-{M=B0yY{w7w5(IMp-MuI0nmG+*pd4A5^9oG^an_R<0*$YHPrEzvIyb^@Xxa zy!|N{cJvU`*-SO+G}DU()-pXbGobxFttVbeW$=esUTXnETZb|t-90ZzNW5U0<*i>J?hjk7{lfJFIt^&rJ`3G5@hv2dYv=-sv3tEt zI9O{d=$z4);%U<=$YnpOE9%BK9xQCD;MpB6hMh1uhqhO5!BYPpFm}lim`L3c+Xj>> zR{f*EjZ?D48+Ug?!wntbjd?}*O=~8{9Fso;N{Z>VZo81-Q$j~WyGr9z?7;wfurgfB zgzr7sj)3`f7Us|g`Pg2XTv`s@;=jP7*N(s*&(4Y0LPC`QrHL!gYAZ!m0=GF&g6F!e z#yjZ$iLJ(0F4fB^W>P@3aQkIPKxTK9w7p!xioH>EHSOpbfgHBQB=Jl{UOXm(4lvnWp(&=9qb3hd_Prbed1_hTDQpf&+l(rgq4z%W>h@wUbKYP;F!ybQpMQ>Eh(F z9~{$P#=N4K1pyOVg5ta&{KC z21n3zc}>*Gal82DqC3YV$u;zMiixJ8v8c~UV8s+e>7L3jsV2LFQ1Q_M>(KZXHuB31 z0WD0cp>D1kWO5!hN5H!3e|GmpwP^|HY;GLr@OMec8^t!{YOjT!C0-Ku`Py+zIW3@Q z)v3CUPI_H_J*Mg94siFqp_H6tAT^GyBVVUp!_3b{J%2fG5L>>ihU~X-`b`td{(tkn zozny~R=FEZb~_04ehm}bB7M-`_ZmoYtr5kS!#HN6EQ!~pn2WpiDs5(lfy8hlNo(jY zVl&!OI^jXxNB!vg?BRCUs3Onee%-YgHtyZaF$s4wVNm`oWVJj2nK^C+TBF zr~p+oe%LlqxW1EPuF)tTpw@wpC%^*95MZrIEF z(0+i%glH$i;y=gv{)QE|NX--F$813dQrZMFjfMDOR1Xxgx&`jN+)Ld2AfIFMWK2Jb zdE(qt%$YP2Oz`R^&2Kiui*BVzwrPKHH64y+CxvaM)NYbio$gz5s7ucoj^SqnKV6aQ zD_110D-)joo{0+&*TdY6Z(!BHIPpn^{1#X(pAlG6OtpV6@vu`nP<^qR^!~>PLFIOi z6g#ymX}dp zm>bvXxF;l=#bu6T<$CU$FM}+=&Byj^gq=Qdjverb|4-KRbsYz zt*|d-B>va_CeERk&3#?$F=0H%T$Yvh&J@$m>6mg_@c{A29$4`Q^)m?rup}Qr*hJ$156K+O#l5X<+s-90AyBRY~#Vq zfmsOm*OraY?q37g*Q66^yt`5`p6E|zZ0ly1InW;?>EW;?`TH$=fpiiPto&*qqua@843F}m(M z98Qc|k5lY=N)c%j;T?@;(lyYYG|~fnOKl}gJ0y>l+AqEaBgJdbxZ@S>a9KBUxnfaW zmayuoFM9CnFf{zOMp$mBsW9#G44STr;+To@YQibT;H8eD;%^9ctn4ZI`*jDm`!?b& z(`bWu+GAM%vjFyM8^oLU!Tsobhd`%RsDS_Bwp6fU-xkp~ZZ^nR6p03>KY*=80?_%T zCr-ETfZFX%;t$=fe7l0@8UW*oni2%6AqDxV4;e>G!!2a%TQR_crbZf~0j_D+K)zc`Z zKUt{AeYgronD>^p|J0&W5FJtF{cXH}GQNHa>Q%Z!oKnQgL8gZeEWQt~RWySyb?xv} zbQr989ftN-KZC}b(m+-F{oz7}+-ujT|S+Yk(o?k|IZziGsd(S7>&tmos{*V4P(cEcxW^k93r_Hf70V@b zs%YmqZZyLJYgInELgRgda0S@~_MUV?Beqb#=&_Mt(&=yFmy?h6YJC z*vv2-bh@OAjt>unYZj~o(=L7xE$J83vj0>RVzwQ8l&vQvit)UvD$Hp}6wiL_D}7xz z4*uPfjm!g9a*XOyYSi5B6718lo}UpgOxTED(71XR4EQ-5+kR4jxF7{#SJg2A3}5$7 zG#XKajYgco3^P|gUcEsvpYEFqN1MZynqmEr5;z`?gm;TdnSoDf2x=x-XL1l~Z&dC!vCWn3qD5iyC#*AMqv_rPw z*D6yeXu@~x487cF#VFi?5=N!o7JcX9ou!*`Q&G$`!f46TC zyd7wI#{4wcrAmvWE_A?a%&rLRw`q_?7QZOw_}z(u{kM6b*Bw)-ZQx+?G%*nMI?{^- zKckZPSMe}-hg_ufrG3!WUY^Bu9d%A9pP_;Vsh<+=jJ#ix-&+g)Z3+RcZ&dN! zx8FG?guXiIYBbkV8-vBB!hY4Qpxx5`(wWOiB&~-7in95IoidcrtkoYLy)E&H6@!Eh zu;t(mUfkXgb0NH@0Rz`tq0_XbTDyLQc=44NQhQkd>xP^ZvlbZen-(Zz^ccqMlj8M1 z@u22)e`(je6!J0mE-Y+#kHa<;z!@WELF3VcTkAUy{08cOhjTw0<`VB3SO8DBtVU=3 zx`3O5{KVuRp(vAT*P6Fwh&l6ya?F1DrWsR=%}#GcM#D~U+|Nu}-11vmdfWzFACQ4P z{izxK&`CVahiPt8Mz)8VDG?BKm6K#0wwfc~Tf5MOmD@q5t942>>rJTN&!2FiMYXuB z+=OEe$WNLX#XNcNz2wrHcmVpDOKFZ>CAASX$5d4bA(wp-Zj%(8JLwVEfi7;?{$U(36-psPUy-^uL5S=7wC{4yBlq(i)}znB})-z-LfBXnv4KqCN`qK-2RED922fBiJhW}vT-wi?cCU{M2xcKDJDUMl2 zU!C+xbE25kSJtAb%}6lxu7$K((!*ceQl#$x8F4du=Ka8|S=bptOI9xQ%+BT*mK&uy z&K*5h@j$P#9|%v+%*VQ=FW~2fSJ21pfS5RZAIAjC7*~qfw%uB6ThR_o9z8&c_-G_t zzM3Nq(H_8Cs;1-1VA%T-UflW)rdDmP=eT5qnbB`R2>o>Gh0OEr3o)6KaVNt_*mk%Q z&b;WyD zRO+nWz8=%Ugjs8F10Fi1K;O|`e*kC$xo1-^~C@rRE5>QVcG6}KSU zcr=^S9FMur;QEg%VSH>C7$~Wb!@nxQMR#gOKcEF?7Pf~|?G@zODMP-RS{bvIVjfZV z{-JJ~_($>}>Ha-?ko0wn)MtY;Z{8OSzR#yunHhbbuzDUK*k*c<>jl=AgA4lH3Xe~~UOSy99>E96o=nqqo>{eL{2c~nl_`^Jev8c3#4q);7RV3uryUNEdgUbew#B(zj6JyW_6Cd|T201$YDH!* zED~StA4$J@ErR{6lf*G^Y6KV4J>VlP;FvVkYLXCBJB8Wp*tHn{Ec+{mJlGDK_cJMH z+XTrxxdKW?6!3EQ*&*0OzW*xPx8k|MT+GEqKbz$}ZYpwvbA-=7SJ3a}hv7`%TVdXF zg>X$#3vWI|a7=p@CLJ*q-&-kqCaz?)Kl>|LD{p8>*dnF`ujEyAIsc}e=O9!#C%`yb z!V}%w+`&I(K_)S&4HegawIs&d1F7C?bn%($N^E|#6UzqZ(!ZAbIcBcv5y(NzHobL< zW7M0OoF1T@>aZ00X2e6EjlSIe!yx)NziIMOM5(1nfPoDRn!p{_r$;LM{KF|e-dAcl5aYJV&bN3yn)W+B^r$BwG?H|CE zja=@&)Xf7lPKi)pbe21jYhu(}X?$~VyWEOx^^YMf!dK82xw#NCd^hnqTq@oQ>_@fF z9N?HTm4?2AnA1{|qGYl?)3UWtmYfQNU#q9m<(~qih_SEnX!QtGy$OcfFRt+)NE z@x?-U@5U;aQyD@h9bYFEk9fnqyE9!A`PrJ?Rcu#mTM6k0KEtG2uGl4Hz>ZXfla)-=};LbvGE(Njri$CRBx~M9iQxM`7*YQn4mwkg~IL5Of}$K#!gG;TV6d zBanz8G-X@yjBPIZrwHhBRrLd$OSeG6r!K73_~qo$Zf!}vnu>_%Ri7|E z8mj&pu*?`BHiiQw`D(V*oMar=Wy^h>+46Q)9CK5pq2D29W#%qn;_S2MA=grQEF=xK zZce3-?i=zQf$TM8efciG%X0>T0m}z7sj4YEU9ck)5B^7r+qU-^|(-4 ztJjXU92+UNovO}nnyU(9jhHbtkwRznaO_VXtekm#r__332D}+3u|Ur=V6%M<_qxKW#T1Q(;OykM0#67PaD-SE}De zff$pR(L%}L9prFZ8|Akbot2*T8`;kN8O%Q<8_I|HfXl=pxV;LUnk->c|eWhh;i(G%mUs>KZP6u)U6s$Pzfh>4qjT9K#|NQ#srH_3 zh*=P|rfAr*aYWa0sIpV!9m%(Jn{w^1p;Btw)6jG}75r!A^PO}}Rvd(mOyL;$#G}Qo zNmQ|EA$^gmP4bk}7-{NE6MD6w(f5-?Z_{9o(N$pT_ckrW-%bzs)&vTqjfBLJ(2Y9IvgvgDv*~S&y0bYH9A0JMO+RhuvhFLKr7%})x z+khB{ij1NItw5OA%NE;sxn`CzwD;j^_;P_QKZrtxdbtRetZ$*#je6$FgiyQgWN6i1#O{8zQ{MQb zj{lcym06YHQb{u<1UB5qpgPRM3oZh=sy@#k52mlX4VP+kU|qW>#5|m_z?SXkq@Tyg z&tFP*A?_S0?0f zdLCj7ub)xO%$~$1B`K7q$=JGMS1Lus?B`Pvz9tuVfq3Lc)%5Cgb=-?eC6Hr!l(dWc zEX=CCP-JB|gYN1!5mw(aEecX+!i9P@y7Amzj@hUBZ5U#%J$a>g{?Uzn-6$w6R^wdt z-C)+HHkBLA=$W3wdu#>9Z%%Qe8M#;8U+WIF z>@P1dper4YaLjyspi$gjLyTQzE5R*lCcCkWD5JLFNrvuxc-!NIq_3F$tW^8HPq zhsYyd1M?s7&il6SoJ3c*6(lg+pLQ9%AJW68lbNeP}Q=4Oqui(;C_TqwA!slq*(^A4DA{sW2~9s`D{oz8l*M^|9E-=0KHc=$R6)19ZrX{ZiAmml&>* z0hyKo=nGxKRcHN)3Xtp2idWrW%vfFKF)NU~JwA#$`iuo^2_~8Gv0}hDYr4xfm9HjD zg?WV-%V+b2j2YT2+Q31%efAD$e7%;QyBZ;-_IwQutJ5LTE0((@y!xKYn`VclMfYwlQ3cN)hrb*kK`Px4K>9V)b6epO7Xa8L&A z&w{V1yXe(HXf$*3HCHwbcwA@R?kUKah^k7cy7Y(dq5x68L641;@vS;ls+?aHz03b?g=mBX0c^e_rqw7WeKhl+W~F z5oco|JEbe^b~BQ^9_n(8sQTV?K}=)KMDoIMk6SN8ddY7%`)@BeHoG8p{1zmx(?2O(FKfX}@`j1^M%Sb&!*}fAmUl#6 zO}wfIX^faoIe!I*UCoK0=d4_Zn(JVWH?2v;fb>B%{ODT`KM1d0mP4NJR$LVhE#Z^q zQJn;hYg44Uo@u0HZkDiN*;>(Uy+|_0L`!blPq3PqhdE}OO4$rROlZJgVNxeE@?*BM zGX3H&w)62;s&O@hCB{4e*^FLxQIxCdCWB@|V9PXan`5}~2n^_l?g-=P&eQ#J3MI@+q6}eV~(nJ1Va%sci(5>`?d+hJjYpCddpQBd%=~yPSfQ%9{ga1 zD!FaW%|c_SpR*fE2G)V2=Lxvh@)#+we+OeEc@-m)_TiKmQZX&Nr!Wlz6VVA{i zU``eDe0&ggcr^)=My83Yi+9t5=7er$O7Y2KExwvSRWFANV%WAjf^{XPm2MfKJp1Xe z%S=MW@73|NvSI>V zIB2IBv|5j26e`SA#Ar4@C|ouTA~TweR9;*;OgV}EDhliwz#1HmLetVv$aE6wq12&<(D1f;>`!E+LcVFXDh)jkF+PWe z2oKBs$ok78mFGIUD_yNMmG4K3EZ6lg@9vhpyX6y)%5RSFAv>I7%n1%QQ+wK{BbE&+OMpCK34MRl?}3!g*@gXo6*ao^7Utrfqzsr$OkKHUe2J$Z}y>$ zwwa2d3&R;5n+yK^wW!}dFR|HKFOJE=DhFah5o2Hcv?wtkM_6@xG}W_B6@!g3m2O4r zCEw;}!QAB`ZyAxLx?7+7aC_G&aNASOr@p-n1p4&9`|zYqCpfZVZNbyRPpkp2?k(fR zc}C|*WRE=3sCq+3Bc|Js!lGmI)P%>jqv_v2ec*TUdF7W?3njaCBDh_t!=Rva{#k3f zfwSxMEXXmUHCN-nbD*B&*-=-jxEBKMK}o`7(3GCzMIClXy<)#J8RMV!QFF|Nw1FC2D$Fx zN-y+&D8YVCgNS!fb~YHAj$^!z)@Mj>lZC?=_h8)bX%LcY3vVB}OV@>U;MV^fi0<|ysqf3B@cx;fGCyUT+?Vdifa&@mQ4?c!73nWEX{7L3zT z2dhmDq|WgrGjixf{RXCxXR8aCQxYSy{eq!#?HrD=R$+<}6a93jVrBIJ_Vk7`?GkAP z{^jqarq$bdXNqg#O)hTLF66`XGiX7Lv$%5h>iGc=$i92gWa4>m_BCicP1|h=`JLUE zr^gI3{q$Wh&5q!hBo*c+Vy4f!qS*Szj!kHEqLG1N&?maT3i>73p6IMjGrqja@aEx3} z!{4R?FBWIhPJfa%sr>avonz*<=wC&t8D4wzuI`b|ttc z-6vy};fliEy+}cxA2l-E2`v`A7fNRTEvz-tr|*WOag3VkfqsUVu@)M_;yzZ)!OoH1 zQEx^Zh09=?kSXP+$w9)$q4ftBDEV@UcX!LagT9#jD-X%mz6=pz}3_vX2fAFVY+8Gc7D18eLwsn*;zA?M*co7seQrz zC#-eG4ql46(zn3F5bas8a$8^i9?tJDhURr2#D}`kq~BUk`ut}Iy#5zT>>9Jha+?k` zQJKIoFI1}YD`G~LcNE4v`!4qMrL^kMSCX9RPI2=mWj=oc*4c-_^+_mvX!8IH2IWF= z`9s*^`~yr{je+$Vnr!j4NV2cg5ho(YVK5p-j$FSlUOL~Fjyk%7V=jdA)%-<_ZlH+} z(>GJBi2~~SNS*ZA7e>EJM$o41*FJ-|gj1k5_z|?IZiWS|)nK~2CmWR# zN^Y}`bo}pHvZ9SIu~?gH_O5e!pS) z!gxA)@LtI=xgOMBrQ&pCHpJz=fv6>?VC2BZaLc15l|xZeKI$^*$TV{1V*`_~T`_K? zwa-T}z~%%Cuu0(k)h`aX6HU^1@gL$l* zL0}`KYbL|J7THqv@0Ji+L&>wA7OeZUZZKixeyOav#0Hd{BJxdZqmqMmh^aLDPsnX; zMc%Epr>T=RNX;Ub(Jkd&q(p3mS8KbA?{8#xp5M-1n7EY5ySwGS&cfL`(&y|nc%k=!Ft&=Cu!t$%=STi2B&#MX|!HVcuuzUxl69tU2wGkG(Io0-Vn5A$0&&1&Q?QFdS4Fd@P%tJJoDM&SJ2^gd&E4UoQT-5hg8I@c>wm!A zOPOM;k!?AqtqS9Tm>ph5iZr8bB%{U_qodm??=3#bK22yR8HA=mY_PzqgK|~9^<#i} zCShP<`2;kNo`w?+i^MJ3C5DGCqQ^tjXtvo2QEkryL4E{Isx-6@V#cne zMa>-7lFdf8RCMU5?Bm;BdAk<-1+JxljnQN-pk$038YHKc$^&KAtMcH8(+oO6D~8Vg zxs!bE7%wgk8%?kIwxrwpo)kScb>ypgsd}K-Att5IhoUu8-N;9;VN_SAT5??s%Hoav zrNEh~ke0ZfcczrN-UT@{s7X7H8#l}1wzax9wSFH;`w=hVnbVcsN$5-8mA9fSy`T7c zt2f82P*rXN5VOR}RQ&wQnwUNtN{3jbNg0XTmD7G{b8&0F8|OQ5M<5R{CmP@cc+EkG zI`9bW@VxENU0-_j;woxY+J-2WPGSK&KSC{TrCz*u63y&3aEy&=?-_xZ_HRdsQi+91VezmaQBv-6IHjrcTQ465BjYUkx^I75u;{$@x-yt+*MFU$sAY1va)>caW zbrvF8p_|3ZV>suD(QepeVHk6YTY)Y1KLv_+)9KgOZRmjJu~2_z0vWvMG08Q&2PW;u z2;&CgER$9VS&JC_5F{h!Z_Ze;dBRD>;kY5R;NvS29&}O}@1W`+E_jTInDgQ}Cb01v z7%V>rtmF~T!gF8#hq<@-!i?YTWmmudC+R=7mwMqfe9bDU-9}9&V=`6B<|tw;$zUe6w z5zaFAw}bu(1Ejlwms$IQ%j~InPs#O)z*l3YDiG%)W`Ju~v0H7jn0m{G{)(}M<(V}E@D-G*e2s5-?S^x1q(p2gI zwjcU2kC6{JCPGz&EJBQL?9ZYf^BTk*GtpSSWIed8S*CP2&_QzBnU6@eo%JMjuR+wuw-s0?_K}>9+QSu}PQnVI3zcu$cvVUD z3S!J|6cl-D8L;owgK3?y6Ep-^C?`C@^tdW?Nw|3rEUgT=nMuw5*Rbv%K7ISjpxL~( zu=e9OGVLv6$u#BjgK;MB6z1$5M3>noLfDSo z>|+g@G>(mhuBo9Mqoew5su1(7F}Ltq$#8b(qBWhcDHZniKFVf36eQ#KrI7ergf2`E z{P$ku_J$L*ag+G!0nmnevPa^fS+Xg{9o&FigJN!V9JBK&)@xdT z`T_&t$Wjd=whO1r#_oqxeeMXos||#}Gw)#Mpk$8u-^SwuVip`)qKKQ&huKG4(Xm!x zpzF~H=UR`DO3;s6FYGv!PIt!Bs0yCLKH<|n2#l@+eZy|h`#)px>-B}?D+EyARuRx$ zoJw9EbrnD6H9@C#NgUHsC2oHprsIXPip)$cHsQA=by%|zKF=5EbW=xOPm{%M@cX3@ z+Wr|h{!|qq>#u*tZWRT%=rS?p?^ZIn*Ic^Ccr^SSw~<(GD-e&}X+~X)VmYQlRk>B$ zfCFW-TL{iR<>H+smUOLkIHXpuq9tWxq^2B|xGiZBjw1_o;C(j-$S+J;NN<9vW*%tw zp~fc1N0O-vE$NH%_lU;zVA4MLqquU?cbL)`!ZD*%7%jw!x?t;8qy1EfTm^W1M%?*>|WKJCT|IWIY!UL#ml|O=ULj4e6_Zm zL+(2M79%6Bu*isF)_uogGF&AGJ0V8D7=+Z!T}8_2gXn!NGx#tyfz}5CSDiAZ>;sxK z5B~vr4miR3xfkKFQ%UvSPa)q(jmovok-N0n zy2`Uc^@2!pbdDee4c8(YOJ0kw*Evf2XSM-(HS$RzV$2cq^q!v(b~{=axZZ+J^}Y$A z1A^%0`~4-yC%7ZP;=LNSkv3X?0Jo47C>xEv>O22}YtcS9GVYl;^z1Hyw!cUk?|x?o zSB8Rq8#UOPt|L|1x96B}{PRSN4PtuF4Hte|)(Tnb7PNTlDKg`4C`}8okgATo0lAkW z2EY4yZg_aVZ#SG>i|to=jS!Q506STaiLQfBD()&%Nq|}|Ygup(Y=2FL%?@R3VV6fl zUX7hf3lPLK%#IS~P47lX#z0!}(M(*Ow2Wr99*9Q~wJ6aK@?<~RtkHSPW_;q%E%wm| zZex(tDPNj%))eL&M-!_>Ggy739R#&YmtH+P#-42q;F#~KvfXIJEL#{NV8w_0Ck&(~ zcUVY!Pt2vCNJK5-b7x(Cr&9mgnt^DeY`>o3N>~m$HG=JS`czbm_F<9J^?c6Cs zK&85ruC|3encO7Es~N9Sovw%(^=Xx`yW;|K>GA+N<=zZQd#^Qhk1&?}C*j1(wm^u< zQl-jQdRszG#UXxv^Q!%6NIZT*xF6b{c7Hye%$r{)wwTnJc09e5{P$g#?Ht{juf|j* z2j?JW^TH{@e|3Ij_0$3MZO6IN$}R?Ub^beMtS3V7%*8x-Q#J&2Pt@lp?Dffy!Nc|p z;O2`IZSF}UCw3rPtn0+G~2kwQ;rky(uBkmsS z#hf;wH1=Cdn(?)lSl@Ff$J|z}W))(FxqndnT!NTY{ptJ3cP0D#I#QQDRm>yx7+0Mx zc>bw*`xb8*sj}M%O?nR@@b(!vda4cmEpDU5J$wj6w-DD@1X8bwdNh0M3DJRe;TUVx zYWxwiXN{v`%{)J{uF9Nt@%boS{i&~P+5Rn)8v<6P0jXnqW15y#Fj03a?AtOBM^+3*>ry4ueEbYPbYJ9LA)lt zYn-NxFVdCN4xu>{gz|whW9!>+7He(AF$o;wn3@OeEJo1x8#Yjn2cG1DBc4Ky9!VE; z>p~sHg<@$B)dMX@ilZEiLd={j_oBATZAg=3M%P<}O2_qgDvQ<_^NmN~og^^!mUs$Q z&Fo}u2q@n)dE*h-IFhQBOrc~`8#33mH%s4UM4!5Mq7O6!#Qa^m_-cNu>d^ZTbEr#n zk)j-pVMdzKPQ}@*;BlI=*J(>BFzpOP%s#_UJmfQinj;0Mr8D^>;ES_tuB!w(Bc?a~ zT9GI0uCrmc4C`QQT6_A>xk|hL_{s>?jQ%HC>9*Ys+Lzwd#cZEMnqM z#S~6zZXo8K=}X1Lh45HBrrh*>w&b0KrrN{M{$u%em@Zz14^3Zq5%NmiJ+Qgx4e8sT zv-D%7>_$vqDBfSq-s>bV4ZJF%FS0eYQ}}A$<8BQLT}s5%#5&m^kg z7?)mReUcrh!@TYQ$LrXj?sa6`TRgP14(6D#DoizE#+^B*uz%g z8QM>cc2gv9%x0BTe}kA06;BmCZJpT4B_>qo(MT-*Hi?aM!%^JcMdK_HW-c;;f_vw{ zqu@H9$WM;B2VHz`km;+mNR9Iq#RZ%7^y}qN*nIMH(W44OqI9tU%v)7MAv zcVGihT|21#ZwQ-WvX9JvO{v@Hp0GP~HW}Nyg?Pf$h`udLKn-1m9p0$ZJd%Hb&E*A9RX&Ebt&1V&Yjvsn zq)DV#jSI2toG8|=G@vj&l4BZFQr!SCt6v2O741ds z@eO;y=sGY6Iu7Ys&mrr5bLx-H%hpvktgG5yGTK{5k}sQ?qsS2dM)CBdlkBwO01M76 zBU4nW(*!XU1LA};H!l^nb?-@yPldw^|2S$E(3R`70*!R+PsfPL)OVmc`8YJReF1W< zvpymU0>3-5ma%h4zpbyCeC6C3LL|TD?C+;xcv)~vi3($ZnAFGF0<<`yn5N#79=dP{ zCTE1w-63swTS9TaOeoug0~c5zP92v8e}xxZ+?E}Q0d+%Lrk+(U+>dJ~*l)PTin8Jb zk25-~ciarALa+jPHL)tyX^R;5Uy`t5j-OzhW<(PT9bw*_KzJG*So=YVLKf>!jAh6YK}O`Q%O?KJq8!wT_8Ka$o&Fxnosr8YvPDM z%Y;*#9|-LqwPD`QIZ&842F7^3Vfy4BkyrCjC2q$dCa3>X;e?_+Isev>9@y2Lcs*N6 zZ_IzsZJTNi#F)!eLW-BqE1Z zoi4z?{$0FmH?R9WNXc&w9uDz%PF)F^Qwu=(r@v&gCljpO{1qbp?G+#P*-meI=u>C6 zV6oH8FC3GtYVBQvn2%BCgwg*3$%2F)w6JQC)c0r-D4#_0o?G)ZK^!AnOdQp%C9=3x zn|2>w=@!Ae4R6T6KV7L!-XFpGji0#JdN1uca4?PDF-!~?-oP;@RG2M@v9XC4p56{2 zJ%;w629N5L8pB4jl7h)hZ|Y%)oxFv+CCKA(@@iypE0>1sa9&FN>}AlYn@AhCuOUO0 z1QjK{kEYgV?P#t|ig>OmhGRlhH*Gs&tU|^L_DKO`e?oWK@5LacPK!!uj$bj$y_XER zLJ0VmoCEJ3Wf0KT44R^LLvG_eNY!KTw$6Zdp1O=~otaMdl%^F{j|iY)>O<+A=Sp!@ zSt`feP)YR|#9Z83saSS!2|20Oo%(m_s2t!hMmcZ75tfJ>b^ni8U_`wv_jOJ^I+te? z$rw#EI$0B7M<@SYOcib++{9@vm!paI*;exqDNvV7_jxpyU)Wey6x;&PS^6f=* z{KvCxfflqCnA1xC-$faBBRD2Qg-J(@f5V(Y(*%7oqH{Nzs2?tkv)->P&>bMfcpt}c zUvy0Pln-`Z*dA|^3Ab0`zx#X-a%bS2;Q&gvdl=L29>;{w`I}i^eKqQS)R>yT87uaD zw~b@AsW3T+30ZTaa9k-9^miLj|5ZDMxE8s}qi1GIx!KswpuEq^-Et1QoGR}cnafvm zrRgm6xzmsS)V~Eu9cxJE2kxSF^K&qEh!Gt#`e)JaX4M>HrNR^-rt3M4Lhqc8!uDnc zH1bgka1JR@UJRci)x1QfzFlv@`eG{DemsD(rfR4fah|8g`J*4irpcqFOdO&(u)4tvDVn=oO* zd+?Zp-h+=WLHX2~VB^#h7G4jN{CwZ^wX*rd+Tt=&@udCo)iXp=4C!y?<1Qfp~ zk2D8>PLQS4`n@{M2tGwB+8IeUvmL<1><&5eyaSanlT?@*#1trc3*le8FmJcc)T<#F znzb6QRCC`VRed{;c81SjW{N$g%3pv?>uMe*T#!@v*he94AsCwHPHgD1mVzmL*@>)Ux%-M|uqYQLJ| zD--Rf|CNF9c&xM|rsuW_QhdLFR1XSdt!x}eHZ&U^D&dKKX(~P{UL%~B+gL(D1oE*>&a7-9AUeAZ}MN6551?e z88$by7dBiQt++OiQum&2U9VDYiQZq z?tHruy!;^hr#0QKg1AW!K;OR|=oNPs=YDr5CNW;rbMH1-G-NR8d(KTXF6~Rzu!C5B z1R_-(#QKQo?hV3<-A3%hmJYOqg&u2p4lP@k#7hMg&oFl4IFx65f``@vxUG*it#8ps z?RhQiD;)xxTE7xIxAh~xR?onI^tCW#Y6N-G`-rIaz8jrBA%SC@RZ`s$F?XKX36U@U zh%GMb(GB`P$xCk!S}`Jm`$Nmd%}w~dm-_`WqmDsUMh&>ZN0{0)4}9x8vK#w7$@7oa zbgyU$vB%=b5r@-ampkq09yH*RSCgxf>irPY(9c;oJn*DwY^XZS4th2AIJc6jaojp=J+89E)@4?6GlxZKW8?lAE!r?sPj9>%B33YP@4mI zWwIwacZs8_)@h9x=N5B?Yx-v5qxkkz?U^%VM90ximS%j?OJ0qmF;;A^dVYS?b+IQA@kca(uQmAQKH&2Xzso^=C-&3 zQaumwwuD!U9>S%h`Ovhcma0VD1lZ0s}<*R z%o3GOTY;FTMXAETCRZ}=q%NJEVI@gJS5UQ?8La6%&UK)&k@ME%VL$g?!y)r$4)28Y z_C5pd_mkL-a6!IlRw_5R4TxcTcL{c{R+7t( zx^#}>KPm9H9yRZq%3?5B!)16FmxFS{<&PtJcq(-mrXR+>4)pDEy!4LzDL17*rWumj zy-a*szLa`|+=OFQ6=JJ}uQ_I#%D6cYFCNrW;9k;&Mc8J- zrBnZL$srp8(vE+KY;5Me9Vfwa3t`$bb(p-XAMH7>PUw^HTrBSsN;j=-OV|8aC_Z@D zlHW8#6($lf^S(I=xrW=xoFW~p!akF{s#}uy*A;@b;sE!DPMlQ4bJ+97sdH0?61Q?t zLpk!dZ3U3|o^+ObAJV_Fs96fdD zJA*FD#p(N`!yS!8@2h+Hc$^%tA)9B(iI_Yf9W}I!QHB}QPHVQ&ju*qpoC0U@SAai_ zJ!nM7?Kmt7o*EoeuX+Sh5K|XdYhUZWj@)jmLx&w}A;q5^q`c*0ELz`+g_1)dTy>Uh zD~Ih)uJCtLGMDNl^#$N+;Y@|r0d#g|B>6P*s+exSn`Ln;xARz=W^jxwZj;W=psT`G z(vH>($>t6Hna49T8osV0t-Uiy%nS+Pm`s&a&qK_+KevXphdUh?2gxf4=$RCfD|gUk4l zUZKFiNBnK7=ADBdwPWb(%lb4c|B&#_V*#@noD5|)8Z^{tg_tQW=9p9!<{Dxu_SY31 zj9xG72-2o4+eeTsIp>u6-X<)fOD?!}e2I3G$N6d+dOg5x69f54lQ9Dw`bq;GtfdvY zkziV2Otz0Ul*X4EN-wTN+6zHuaHPY1as+=He5aKm=G6C7MU(3O*oCgurZcRTz>6Da zmGNKNi+Xso%=>@Cih4XmEUbjas5fxMAIq#hccCgI5rQTgNkQq|q@V9DFx^6LspFQm z(m1?I(-%ws*0?bl^S=PW$B1#eKB1`DMprRm7KZ*A`a*fke&wY|Gv+@SgX_Efgc|d0 zaAhKf2nW39ZV6>QZbD7}Ku9R>4F0A`lFwIl*nG6TG{$MOG`zYq%m`MO8f&fjYU=Q1 zgUaR=Vze6<7XGupE_UsuO>^2i!{doj%GTZ2G3(Abd^N$TbGWjRrMf(Y_rY1Eq4Nif zf`cc#q@Mo@puz8i*vxE*bk)TQHX9p?(_dC_%ny~-@h8O8Ud^&^h9#ZZ^;$H0uQ#~G zFH(L|y0aRb6^OB_hih>*pizCD=djC(F^QN|BDeNNZLx>v&fTOJ^K_}_w*jPbxTZA4 zwk-r-aDc?CgvvK<4tn0>YMKyp`S&md*jusLxmtAgDovuNCMXxgpT=2SjHyN&>Q5#e zp_A(sh&ovTjlnpXr%}j_oA<2wK!&ueV;4ra(6crcFrepAR&F>!0O|a;Nn*bGqqZ9)oK0_T}O6b<(TM|Ur71< zShO!3!rI!crTRKM!7i>3Tkv!wv3`UB9Cu?l=B~=PSqCwq@ixVZB@@}8Hd@qtx~K4I ze_p|tU_G3ZzRCTe`#GyY@u};u;sXxZFM+w&4QrkBc8y9;94J)f-@Z8L`5%xX((TTEp8b$7v~CSysnHI}!hVU$a3 z2cAcuxdj_9aW+ae%$V7u9b_JkQhc|jIDfE9bIGw)dpdIB0I4SXF(30O9b>7AK&rwaOjeEmt`d@htl*eY zqIhx&`V1NDq%HPVz*#FV61l5TyqEI;S`_Wzn9r)c=K#cLXD_mMKGBVxe6LB5B!w`W z39d9QufOEh66pSp#UijCXotxqM;)N?0E z+I>qjX;B0p)~w?g9TjFMV*Zs}&p%o4UR)BUNgEO-v9|jDRI8mSH*VI9&w#JkWzTHi zb2(^S{sQEHjSq7JVMR@MRvQvTww;+r1JDh7smo5Xc<&pr>$rX3_1T4EoKzT!n3$+p zg{<9P@tmn9)!8#kv_Th&mN`3A=BnMS;&;>Df8kZLu=3Xj#b*l}%q`ys=(ep6v zmHLm#rgQS#n&TRj=x)D&G(U>Fx0fJ`TWhDI0Ie00dd?4gq3#sfsgbjBwQG4l}fXJzX` z%Q4Y{hjkme{6Z2Nma>CRxT3*#1c`oGU_K}t^nQGX+%5Re^2THKSCG@=Ty?rKx+g%0 zn3+wqavRv&#|b2`!CTlr5x*A3w>ZX9^&#*=Ou)$x`Kh7rh1BP*snrF2(kC^Ril;TW zhBk0H47r`qPjyW_Bm$n`;-=91^jmO^KLNJr{yIpQ4}XG#$n7&HS=G02$O!#KH2dvi zOE+EQm>zi3@D$fq#xP^M?u$*xtjN~1%lH)bGk80Vvbe!&vLAu}s%RWvJcA#A8Yngk zhwS3J7!>e=PvjfkxGKE}w}x&z1)`X}nDx;b2`jgpmG)el$v)eKaZH3tLvKRNrPCMf zjN6POWn){@Awm7vChg_4ko{!-cdl~}Vz+PSAh+%@l+RfSBVR}`VL>&>;P$n-i!-rBnyxV<&Y~5a=P^Or{^TEv^?4u$woQieb%t0Q zDB#9sHUkFye@Rs?cNb^&r9&|7s{5;XWX7-zOI>!rLQPqs^+PnMOoH-l_IUh|&oN3i0j$IJ^CG0d+}kQyayUIy6!X6b$3=e zEjTX9s?+(&Qr>wlR|juaY=tUMRpr*s{XCqSIG#Rg6+z2lMw5gheOBW)jw-C$(0z9| ziXrAJIYw7?uu_be8$13Lt=~0+_+HVV!|sK%t`_0SYpptna+5`1YBXPs8g4Q)ZT9oF z1i22~^z|HUQlCJJhc2h{vj-8YdEMDqZ#>XU(4foq?G|%xd2`G_Ra?SM#8}!l7x%R7 zM`9!m>M}i4xbiwh3E@=qczOzZp|da!IiJt1$thT}ovy4pWel}+q*{B1)6c0r$fap! zOk>?Uuz%Q`K7Vsf4EpQNF(IlB;tIrExAgef(sWtWyCsCyUHOub^Nw`rIPM z1GiQS{#r^4I`^06EPG6n-g*>m9*52ecx|bb#OeF=IVMb1<)}xDp2?vi4ey4+`*_n9 zc^H7Vj;QSE-A2g8!R4keZy^zLIyzdm^{ngr#$WEB&y*-q>Jl& z$i2OT8#MXvZ2-4Qbil^$2agMpaIQr&xSYI1@@e@(csFsN)FNhyG`ZRm>^yr(i&OXW z)y!5MFa zSpY>%@%$N(HT2V)T}e>sG%=y`VtV$?4(!N(E)MtqCG2Zc4}&ara!fDPYWg6? zXmga})6~Um-cSv?Gw%e+8S|bEemIUroGjzXh2{NI{y`Hz6H~83>VxGd0x15H&YSd)QV1cmdG(B`0B)shb3aRH^wL)Wi4bUv^D6{ zST)6p(ix!mZxgdqK183PQ}E-cHcItt+%3Vt^AQ>ZDk0!}OBigpzo=|n5E*E`gGPKS zh4eAwNzUPwqR;WRG<|gv#{{X$-FAr4Hw#xxD4xpF-l)@qLt?~xgVkxk#`Vm1_)}gW zmW`W-b}Wa2oGgrZdj@4aZb9isV@O7)7q`26$jY-}^uek!Sn3~2u8sLDel=-DBfIY9 z7fwrx7oxxb^ZT+C{m9RlTj{U8;*-Zh)u&>?Zb7iCftvzGc64;IX6=%l)yPlqXN6 zd999u$@{%z)9JRX^w<-SG?#LWQq=%66ETsW7c0j0y)PcxtWNj+y(A>=jG>3ZIx{(y zq`n!7+sYWwnAQLdztbV}z)Otb`2gupc0)pwE*laOOun8pp>uTW zaa1MKm~@qRs@`cHh$%^3r8sqYp_sKqojzD-DER0drv4hgMY(b--?Y@VN1 z#N_LZnikQ|>B44CvX<`X854Om|4S}khnTO{35x5#hX~b^)agG9Cw67bZhGFK ziJcFaf}MdOf-k>tt7Cb8b7k;nsGo8Ye(LsM#bf2sx<#aSV>3y}njs7-=+4^Qe#O2& z-OVw%s*OhgVoaaxS2VwuFMM`Xr)Dqbk_;h%c1gZ0=ElANm(_S=_YlqgR=wlp?&2xc z&^R7v4Y6i$!}6Z!6X_z1o3)8}U&>`S7A=H;<#$P?Q8L?h^&rQrR&6{Y5VLqqu0nsN zHfgd`r$fYBBw<`E9a-^8lsoT@G5@9pTSet^xAo3FIR1vmtY~A9-8mO*Q|^$VJ?4OE z_a4OGco~an*`M4U@>psew3gA{<2j};zHH?A8^ny6wqJ2=kUe=fOr6Hu(GVZa45F!~ z8l>qk)@f$N@-qU%>T0kt*bK%xH~FNO+&=pAd4{y{&J2iLX-7sK(qU8bS3;e6oK$nx zl3AYZz%ga2>R>WrB0B6zrWWN_IEc(=VnSNL|rA@k#&Q^xNbM#CP!#ahpa{ zzM4ceCLJ-~Ub!o-Xho5tf7*1&-@f9&A|1MB^I{>nh_H^YX1 zGzySo=&Q|U!oBq~=%e$RB+#x_tb4kaT0O&$Q+BX;V}=>W+)`tdh_PGPRk70~niPJ~ zrutt_v+_!NsP6h*Q9R%{)Ef5(PiuAZ{zP^Ix$lH0HcPZa!s33XDP^!h3ZfoMOo&y* z9r5n%-86i`U)cQ<#1}6na?EA*BT$H#+2^jg2!2P&?pNBhUDZDp*bSt}=N z`QZOWou5YN!|>&YF~#~2!e(W|;&*MRo!1^Z)O#L@Kb0d+Ik=blJDbwbrsG88sXiQ& ztB#@XBF6Ndr%Pg4Bw71Fn~vNT#yYG+`-9Ad;%9>x7}|XyACi^NHz^wZf!H78ohiB3 zQD>m99lc@_Oo!QdlY~*fMbF`ZblG_us_Az?+~MQTF-O(GZ3SXnZDO2?ZO#+YRtL%2X6$9H8f#Jwc z;HpwvxdfZl@K9Zz$d}XI)u~gY>ih1}8@oe-@MsX*u&#^LAFphuCT#xoDvmj=J`w06 zX7PkkiYfn=D#squroD>p6Ss{_wRk~}D7%sv?)<^C>iigG`Hp+6$gijC$QYP&t%Wq_ z+F$mz*CAL}aDiNm43=2d6SB?MM}li@uxN3d9uwkZHr~YYzN#i9_$MOPU)f`vJJA_K< z_w8WYQYWc)+eyBf26gG%0x`?q?pB<*_CcIBSDP9o?i1QP+N<(&elE%rk`=Swf=8Mk zSGBSkRSSPdWN{ylnDQC$-opVrhIW>klMqNv9>@B8Z6{50HU>KrBX%P0ILNDsP=_4$ zh#4nED)hQpv-u;nscYP4qByo!b!KQ2hRy=eSojP=*H7STaPh7c{1ND%aRs!GIDp;m z?<8VhEgQYK86BB)k!-qlh23s{oBX%@KJndbOl8b*b)41@F@KvJS6t6QU3LeSE-8Tcfq7t5pa~W?_LFxpyV>W>{pr~l zbEq$##gcpYkjFRAgJ;$Xj)_ypX#_EAr85fehYOjJt~PD8Z59y+ewFUkZs(!8y%QRp z3~zzuh#an;mOA7%xFzL4_1DK_>ZSjLZx0%e6k^Sz37%{K)X2|=a|{*?uVI(IrTSKF}(9UHhaGo?cDDTd-qq5KHL+*>J6&7 zl11opdwwW%?vMgg##clAn!B*)nhBg8r_GAC9wL%rH_g6R2@4GllHZjoagBR(n)2r` z$2?V!$9c;)ZOAgknD)b2_%bcJpv6;h=H?Mpzch>m&Uk?heMzvo%>+z8l<_>Y+}iv7 z?o$}~aWFhO(F_{T{5Q(@UNp){ggs?@eoX4DEBO7Q%{O!I*I?Aw**+JKyIJsrx*c zjtNeN$9IB=ZLQp>{1P0#Ea#XXY9$L_#3PjQ2Ka|-oBWHe>h_n19cz?f^ zy_%&WuhdEwL5P{zEl3fzdZ&1&wHCd0qdi%;BY_&O)namRD>o|3mBRQo-+0T2j46)) z35nQ@dGF^c7VSKWY|8I0$(QomIO5?|CeBhdlV+(jB^l$b7NZYGOupM8McJ|8%D2BY z>5oRVZ2vEj4#~|B(JiL5xd%o?>C&4#Lw09NHgNkvn(%A^I$ToG4q0d!9<;egw{Q zK7#l26n-L*4bok`&cmX{5$t&Pi$Zws9>R_`SuEjvJK>8*sd#jOuC%=MRgQV1#>68= zZ(@PsK)dro=o?MyVa!N#%V^p&^D<@!tGTe5YO5gX~fi<(un1IXl2kOA`koNoj%6X zb`=+&!lP%~!QJsLSYq`s^-vZB(@T=}8B2&Q4j2BMD-;i(90dKFpOOZxpTty$$8b!! zIO4n&uZkpK2tD6_y1MWwVQ8+-#pfrRG#T>Z*97vK&K) zKj|)+Qx$x?mnpoS5+M$KehUoSHbw0SGuFM;H9@{SIl6 zU41}YyTpTfdp%Y(9?O7rpI3scIM#T*9GWd~07v%>9u9VH#lT=*jG%L-6TMRMP}tUU zr8sk=HQo2$Trzdq8}Vb}FOG>;hl39hWBwpQQTuN{X@5CiEj#q5s4Uu-iQ1o2BFTjpyM%)wlUTu*J?J3ea@_=KmMG8FXi(^oo+q& zP0LWPrV25!Au|-~pTv@=>zZ`ME`9do%^?`przNR>iZOJzLA?7x#$>Brlj1Ki{L|@E zF2bR*>oDl>cKYeEC7GK&L45IF7`?RgCsf}#ri?wgm}9=FAA#413HqX=Xj&gfbna== zwPgmzc;2Ox2!5>lw2fJq+kX&Cb;D>}_$!+Z7!1 zU5znC%qfGkT!*e&WVa(?{_Z6;aapQ@n%2ZII2WRaW80gM!4qBnt*?USWyUdb57eL~ zE$K6>YMy`VA2h%G}O@alht)MNE~aYdaA(H^WMYt{RWHDdfLoLpQ>_6pm^X;Hm? zugML~eAQj!uYxSx?78kg+|n{R#{O6(Y7boF7*Eu@J4I$nr^s|^)97$v@u>DJZn&*9 zE8SL#>HS@trqhyR2CMg*o`~^%U+3Zr%@omIT6CjJ1!<0$qguBFS?V}>@Gs1%WpPaS zuQ%W|pa8;Gmw=pp7`D?w8g{6iR9$v~=vxj@Jgxc8H1Ue=oJ+o+KLYY(8t&Lt z5t~iuZEXIK*%eHeR@JPLc8#@zg*T^2&-+C(8AH^OjVogEw3jIs7vC0()@xCp4lf}# z?|^DT>2{%JKn6HgeS+ekATC3_bp1;xyp;oP?eo!IbQ{bXZUb7D?WHcibs@6-D;CmQ&+tH(bkSvSH|lLtK&(pP1G*XEb7 zVE0@I{CWqHwa^>Sf?)v+8#Zam~M*av!|*<_9dn7Tr8}dy#t$?v_^%I0V)>QG#tx2jU2Dr75 z9*j+WTi;*?>Je!F^nq1d&Di~fU8IR^0L{tQz)xs0d8%y5ZtAFD{qkuXqaVyMF^KW+ zJxZxFqXjFvsYPFYE@0i~gj3(%6@sJ7GYC6>9&+7-FuVQ%;>}M&a>sfu*(%Gl=}l_S zt{z2Oy)IMf)|<~kmmDV=>kOHF(J^q@--Ba%sWFL&c|UuuQt!hhv2C3ejp>^po;r4d ze)(=j0+&65nk};P)iH2|2Hv75V;pnpq4TpdP#0&z%8yJTUB+2U@)er6o0NQVV8^F+ zk&Yj;k~TcgAQgzgs51>QkKWBy_HZ;7SrcvA+Q(i|a_2l9^6U^4NjabRyc=}K=p{bMqwTPVlmA}0UaJf(JR zkV4B$o2n)Tl5mT78ndBZxJ}UMH-`3ps;3LrHJ)ezQzOFCZ(0#vP5kE=z zxxcwIU__}<_NOD$?yM{A>UCI=doD!r7m0(S`2y)iE^IZ0e=e}vX0R0^h8 zAdx$|Xhb{{;c#S}AfGO;k$ma;; zmJybn3(tnwl4}iJ(D&Pfd{{JteaagPuq}s-?PAWJPg=?`OpPf+Ox`gYW#9vAa&Wyi z9c*u|+!1?_&UBkXeD!f~4COzPAEGN+B=$a`%1EH?Q;;X}r{&{ApV<4%snY12n70?Bw3^_dqQLF7=q z*dh$>$6SJv)N1(3Heo~gEuQO?r|>3^Tq_kW*aPI+2Z8!N5Eqvoga(I^lJ^G<=Cw+f zV=B~`cZgZht+#TSkZa=F znF^|N)*7y?@)t|*8}rqqtAksOZCG2Y>8sS7A44XYHKi8{(!}0wU%=BTh4?xgf(7UM z@S7$(Vru--g}TDi(5e}#k6~nE6!sWq#|F~783sfCym_e?qDaX81!#McusMu=I}#!A^d<~Vtk zjD?l<14*Zt!%|28I^vqY2NL>@2IuOF5I(6A?95HTea!Ly1-D)|9q7K>;dFS!Lh>+K z6ceX~(ymLbXmRdW<&cs4I0kldOlQQD%+ye>pM8K->*~;yk~5^pyRYh+-XBu4@&FX< z^Mm->G@S5y3b)!09OZiN%gM3;yCL~^m=-C>U23we3gdA zTljif2Xc%ZV*EW%=T&&_Aoo{e^Gc~M$z15K3Lb6*&MRY~=43QlgrxCs@W3ozh<=QI z-*@lvmXQjZp0scAWcml?#Xo53v#)O^(b0Q*(aPrWqN~MDj*+%=j3Z)nO!V_MyG$pe zpXt!sbIVAn>k-w5C+)!SK@ynOVJk0UWObgXmPdI9@o>%i;Q2ip9p|m--8Efl=O&|w z_R5wFw%E{Np?36xWsbP>k0-~hQezZ|(Fh*symr4eIX6O=hE01+j+R_hjfrdva-3%P z7l$sf+fE)OG2WfY-y0c|j$!;zgSPbBswXgN;s9b`-Ik3W^d7p|bf)6y5^?s1J{+?> zfUjmaV*bX5yBs-CD)^=9(yrCDaNRUd)%{C*kY#h^mJzw`DPvMcl)#30*Z72_d?e!$JjWWzAAPG?iWz zHlzWvBwKwFFcA*tbj3pr+31 z6M=i1mso1e2V!^|>M;Y=vq>SjS9@HFNc>C|?!O|qeP1p)E&ojZP5w!$o}C35Q@Vp= z79b{l?|j9!(%s_U!e+GLoe3FRc}BG}OA96QG9ljJ7k)m`=Ji)O$fbx6?&$xGJ|2gb z9E6W1w(xk?IO)goNEYVoA+20sFTEJq2F{EfE%hsXD9V_g_}*Y-vl210mPaY>Sbh)> zcWh37ZH-h^*zHz@Kf>YNmuXz>+Hz_j)T}E7U*B@xqF666i0QiybVu7k_zWFsG#v;h zPoy%tymu_^#XIuVcOP3FyMV98KpjABLQMDQFomtVHEZx~PVZU?Y@86TiW~leG#<-@ z+^`yG-F-T04&LFdR&uCbZ<`7Fr$)l9sU@V%xhL#1djc$IJ{dj#Fw1IpgfL+ract7S zF(&x2!PNvJW>rR@!lc_+Ht%k8dNVJOr5vBC(pr3rI1UxzKF$v&xp#-$ZD<^LqL8~Q zc%>ynkYOjty|IAkzMsz)AMHwAO0A)%k3HL2(2SHB9)QJtCQ$jNO;Ka^Am&)WLdCt% zrL4Q59vyWoU&<&kQElyCv$f3G>v=XX(AA$XV(?IuV!SJdx!o!9N zmxD%2sEr0{tL;ow^iWv~RwGMLpw^#bcB^mNA;hRO^%XOdeVNNlJ-Vx7KPg&krL;IW zghX52;Rp8W&2Nd^HB=LcCW7Kq2=+b=pVDyluuCuJ%cid6^1Mj;UxpT4;-O3aSsWJ+ zn$&^$#!!yAr+x%ZAf{;Qm)yHve(b{qJ^Ei(n55Wm3v4;sgWttz;*XcWqToOBJr7^Y z(J5SF!W|>g1X-Q8*R>ZfV+!!S!T%;1F@_Vz zD8pW?U;&u4zixU!5)@77&%+DJ($EUtmT+Q(0W7^!f`t>5abH-6{e-y?`l$yDXw`)6 zT$DtHKR!;Y`dHJ)$`iyftwx+5eha=EY~`y-!mj{gG7)3tlck*0(SwZTA{W-;Y2Z$F7>&huP$Y6MgJw^!jE>H%FZ&lUjWcpX?8Vm{E7a$gbair1E=oH6{3$N$B9Eu}D*@gK7$jYv^l6)PE^e0Z3DBk7dB<-3# zKXF;FP?tw7(qNwq3-~SXE}euUUjEN2>y}8L-oJC&@f>4RhagtH}f91TA1ea zMHu*`g=Ev>qR_3fDbpGEnAKH0SIVnVs`r~uh|!MeA;vTu6Z8`GsdH?UU@+^|6>Q#q2KTM#zt*>o|2NThuRxMD<^ft62{Q+Kkn~R}EH*Vp@#acf77*mX znjSVIGR71)Y20rb5i`lVt9Uk8gE--s&#afz$-D-)@($AP zo(BI!6rn{mIGs`nMs55{@~#F$zO4=UInkFrIXDx9%Dd#+nG53GBWlbFb!4L*fElQJ zHey6pA2Oj=OB&t$2O0G-f*$qTP23x>_-K28t0>yDI*9AN4|um7>T=W&2~@U9DM|Q9 zmTuQ1XFmY@I<*xXtUD*=`kxaYyfWmgi4EehKr6&N3O5&5o6R8`R<@*9Kuhvf)*1GpVc3 z4)M3@uOQ#Fbagmrf|$vk?ZuC7JIIObmQ^5341ZtmiLiW*XsP{gnVge?{}YrnI!yo#f2gDw0k=IHrj@*J+8EbyoUf zpTGm;Yx7pL?8k3txNJ|?zAPfiC$VK@R3Cnf`a7ZuXqq*|7p3teqPrPDCmy40dHqw5@SK;8O;mYhu zt2t(;`VqiXoyMOb`O4NUPLaP4TG63)+u+-eST?2nKjQXv4`hNpIAd5?@9`8Y2J3>a z(TV?s>MIU+q^FY)&`vWa5~II=#0BADbVgW9synT};?-^(%)tMqJHDQHBA|$g%L-6# ze;rG{c^J?|dE2qq>6K(^r4O3zBEe(F#Q)`?fA6q@xa1T3;PE;CGJvHW^*I?vXFr%q zF3fJr3YYGpW-Gc;uK^F0XZ+L{$&X{)5L5KwMV{WzNHX-90e#&R9bu*qRbAg>f?fK z)Z7OkcMaXX(V3!CCGFs~nvfqx?APru*#Z z#PZ%W@RBGt77pMTEj4B_Vs2a2&%Hwu-2*YWJ8lNZpzcKAp z1cHuUR76PRhwRB*}}lI^f2@bC-Dfn}ndOBFo2eIHv$3ZYd66*SQ~J_!yjI<>7H92?7krbF$w1uJ@YA^kF`X`+Q<#T*RWz(Iq}i2u zuduXuz?}JsZbZj877X3XF zE8)N^FOY?13eS~bak3B`hvtBFWnT#Wb%E$Tme}p=SJ1wzf-KnT!8Qygq@;;IK`SyU z-?Vk=;5HR8OQm$hu$S)a=s_cTg8pNMDHB!mTGo+zj{=^&ANjFAA1jql1hSm2UP&6* z+315)#31skOFx#Z)0I{<>VSS&gm`mwrZ6({Abfu5&M{GHOg3W5m63{Z^H#D^?~Uk` zNzPKIUd>faXO$CIhZ1Pqauqi9Zp%CG<#BAeB|dKWd8jsjPb$XXICNzXLFe95`rtt# zyevN_G_-o}yuL0UJwmr~%tkdPA2C52%@xJ3wy@>n+tKll)=A6LY$cm#am1}3Ht)G* z0}X4!o0IPE!0tOVKiM!O6{_JS865aT+3xIYGJE+x>U~XvHtXMwoNXB=?$}=nF~%Vr zqfq}hw-95uu6`Mmri=bySM3aD%FI;pDy>O6dDvfFH@)d|W}6p_cWb9ouC= z!e1@eZ+}s|_$h(-ImFTZk?rY(q%Fj7;u~@Go<~q!70fYZxDntZ@CY#zSI$#@7_fr9 zX=zNy^gJRxWt!Bp>Hw*at47(6WUz=c1yk2z9zeNuss=B=e7M!w29B>WV{cC-5ZlFg zBB-&Tt##u`$HPhDs?e+8vd@oWEY-nnHDb2tF{MG4JB#)-rUM82NL@`w(B~(%kf^=t zcAjb<1$ef?x!liZdBtP)0JKRin*f0cW7*a&2g!XnLZi1^(p8ah#I(t6F=y#%xOUl- zV`gsUtEoqfkCTQNal8jJJ!woI*^iKdHf*O0l2VD>&Lc~+JiO(N@5*!V`Y(z1axB%Y zgap@ZV36m^s@jK<`O`w^`MCDf=4>?SvG={`eR4M}xa`C+Ra-dbD`LWT8HlHgG}y4$ z#}D1BN{NMvU}Ss&W{b{Hm9>i>t)@p%b4Xddum&TuxjVmw*$cOKQ-(v+S$ zjWY$Iwc_#x6QRZOW*oCp{onjWOsU}tz_e<=4@k#1G=vCkW5>hB01`B zTC?paH`UNuJS8P7JNvY!+GbaTV0MvS8ed87=hX62M9uh%Fm6o)7#gN;+(#@xYAC+;^L5i>BWg?PX}NeKVkp3ZzTi@Yw1rOm#U62nE$dGcP~ z*7VxoPk%}W`GJ;O;$7Q_aBh|!n{eJ<=(naHaScDo&XtT3KKMKmEu6KP%ZR2##)M-G zjTjrmeE8X@^b6M|w_Hu=y7t*5%k(7Gn)Z=cPQ#vbG^UX=P_k8Jo%wO@?Auty-T<_u&kM)8FpMs6`b)4@kv{g4*3`NYX z!n?|*sW_t3zXN@3>_U$G+(fnFDoA6;Gzhxm#@l)13cGd$1-AjHIEJJ0a$#jePy)IB z*N(m!-h{aN)QGpv_M#;FEBQR=j%al+j$_)WG2;-^O*c!~>BJ$D6VZVdHvbPCo_D6p z3d%^b#YtG#wj0OD1<9CNW8Qf$W8_|r)xkMn^x2Qja&AiYt+^|1xHpTQs0)GlIVZ(l zmgfAwS+D+YrXl7({dlDtJwcAW?m#O)7D3Ix1MuIZ&&1I72pFyF2(s3YtZjGVsuo1M zp#3{yWNo{{C$wp`UIcx9*^c0ML)^7Gls;UB@7L>P;+cSr921Ef0X_m=i1GL|OKI@_ z1PcC}Qor~i@Hcg|G`6CKxb-;*nJatnt|1w7eOn9o@C3)^acIe~A_H>tyU?10`|1A7 zS>*hdd@)Hgg04T=hSEJ-n5~sQLRB0AMue&WGzO8?XHOoWjpEkXymC<*x zcz6WIbWme9Am-H!gFMBnFcR6_jBe_Sg3PCL}J~xsdMv%xH{X3vh~0R6W~?@6ELw z-g)1MiDEfHtXF*wsxDsQZa$6cGvHZt3+ghW5k^REzb0uiy(6s|{tZ>aE~%Cjd?UVd^TAo`DQ|$0G3iIq2M^^x4&8ae zHSbUOzlA@2fIL(Js=b}4Q;?G+wf z>`3Fgd?e4tsZ?dCiWJosy`%MTloUTUGN!&)B{!^rVDA)`ra zc5+`w$pWvMqn(&}aj_s{BGq5$B*e_sIjvwH4HfH~cA^s+&XJgHqUuwxcSJTwm$T}! zq>(^XnqVMwLUVw~!;6?ohiA5G{)L$^F-y=aOm;LS4>%vOQsq#yjfabNNXqHdv)LzoERogYJf zpF?1Bww@R{td)BAc7Y{Tq2y(Roz%^sfg}{2BOa47IOc*n98@CaazL&kcH@RXHdW=+H*$`1ZVT(`2-i z+vf`#&>Xk)naKvwx z=`0j%?idX2iktAg<}r9;*H%>DBDlV80*nR?@ZNQYwLZNKZp;s3Yjn>r@p>$It38?B zop6M&W{5i7eHSsR@+8IW{e+bd?o79Am)Nvn{;COiUr2?citBZ1kDL!tKXGOnlf;(4 z3L()>f-#3Jps(g$k{BGwzOL1z@0uMXr^b(9J2vzqaXOdC)m8>n{%`K6S5twQ5bpzu zzOTJlLQrS=`*{M(IWkP88owGfx$zO0Q4HBH215J?^!n5)L}}gIz^X3835y@3vTuP< zyf9v@S~Y;?C%Hi8Fir7+(P6>l+z}`l>B%w0>i?z|F@2`ZQ{?$=VIRfLbjfiOY1Z0r z(wa@1i0PJlT;z1Z0264n?h<&;5W#*liq8gLg4TEMk=Hi+@-}t7A{5SAPrFB6f(3o5 zg_yg0lr@@np_%p$j`>fG`GAs>+ikc{4Y2`1?2 zLn6(DLnc`eeY>2uTFoVQNIUOYqMgNVQZ+k@IuF*Q`-6a72|6eCnEDEWI_%+?75oIW-klk269`WOVnNlLm)&KjnIzcVGV? z_U)?0ZHr<_lZIooWoSFPeMvZ3S&=S&8icd%8^buJ6}~t4q-h3XYwvkG<@Q$VnAbFO zI!@bJ>UPqAmNmbk_}kzBZXF{}Ymd;b zt{tcpaGL0TzbY30eFFN?0UUEejnPMpV@`;&na@<_xyqbok2jST>3dKO=O|}69F$|| zfrln>KZ5v9$*?k`8d5VK!$aFK5aKqh&*^TfXF;_YBkGj=^4m#Is&1CNkLJG9x{v~w`SP{A>q)CYD8#CQf|Du1=rWOomn z)7q%yynWkZX{Xp4j*+KV!@eHIx4#y`bJUoyQSTu2_Cc`zGK3lKbSAwX452ndUc#c| z`$+OvEmnwardvE((c0R>BnDT5QKvm(-WHryuIqSAY?^FNbKN_VZ(~xZLz)h$uvd59 zdtn=?+?-U=9=q*vHBsHZa(C=P?`drK)J|lyhl34FqWV&% z`}LJDe$HbiUy*su$^8$VnT_%ZUe}n6(ZdHCS3?k^b<0QD@`koxTwzY<4g5k*jXX}{ z{-T@JpXVT#BH}SDFZ4x!@97u$D2aT&@$t-oZBJWcRWV4=tM8^{%_5n`=K#T9$BeCA zc8NVTaS&vTzPdSSBx2sjO;cu>oe>(onNy1yH{t6y#N>@6_noV`#j9*gV_AZdlewAD zc`|n6$JOzC+Eo3oVw(g@g?H6ZAuG=T$FS`L=X2-9X1}diY4eUm#+0esdE61BeV~hS z?-5;6*~x-7_dZWHH;<ZoW2(NeU{RjWGCv_9KH)3+8@5=L>=S_}nw4mpgb`_*yJLxpN));cAaFA>Vck_uWDuV@6m*Ipl zN_YVJYyMyWkOaUOcPqMYky;VPE+namh9< ze$y7KF+qs=GPyW!Y{4l~@!o>|x%@^k+PM%8>mmkYfCT|v`7uhKkQ`b3k;Jb!!ZGsb zV)OnVA@4#M-PEElDc*8c{EhPMmAaoHp<94BgpKEz3F`kQ95F+m7w6qGNF+`UU1(k2 z9MQW+6Dg3o`$RC^Ls<_VQh~BruP#ZoT zTu)~3P@Qh?0)}4L8;wP;e7|&^Q_?$Q{Kb&L6 zsWI`0d9$t}Z;(S2af(6J=TRFK!3R78&5`T>&PYr{G}ODXddh zfal1Ii0VoEJ>N{Xyk0`w+IZ_#-t!7r`N8$4*pw+&g(8T ze?vS;P1>!p7*IsgHBj7qUz{5A4Ig6bQ111;VbBwB$GQO>Z%03iqp5M3JGuHm2d7s@ z(J_~8>9O@1?CTU?j7V@wf zm4T(aC$O~dXR z5HsDZqf1syTe5A9C7mL^Af6ktR0fmJ5KU(lL{E7H`RI7%)AI>9?odI`Z4x)$ln;gb z1Wj6V66f4C3`n0H9oUGa58>EULpt=BHG4I)1xZVdAk)-COT~zZWOXh_`(6;DFIrMx zM@_P_bH1vvR~8S|lZ`%dSx|X3twxmb1hMSzDce&y25gfYTP~MepT`PsSx5F_hJ_S` z*R4NYn9iXKf{X$Drr}2L5HTa-2PsahzoAHcYe`3ZdP%ar<*UwP)3Iym4e)&N6T(E4 zpu}&QrfV%PMaZW$xf(Tn&p>JVo}QA?t--?Ugf^@$vz%SkC}#&=^c2m;eCMlaqaOLK zLQI2yh~oCjX5v6ID_R|COiDYZs$S6;JQ1K@)aFL6+WYwsw(~^S@tY=(W6LAIuXGB@ z=wrdsM4e-#YUp0!Yey%^7R}E>*=RRxxwEJC-Y^a0DDv1p!1bn7PP)H7}gneg;>!-TJTYaJyFb+hFtv4OcuN* zAzi0R=6zQ1n`W$@Uj2-iu9FTaLS8gyTUJ@o`a>PWoEv*oHL2K6eIpC(x7C8|Q<(er z7C0M}bHQ`D$zs}hPuMl9HR$?Rur*uU!LK%pEwM{u50)pAS4)mCt%U)6HM`ZbxW5r& zKWvv`wEqCs<*XGwlr6HliMv%X^Y#+^9ZEh*vS1ksqG9K~>CL;4dhi}mgOiNXtbvt ziUlnceL7ze0veCPyIqqxCP}R|)EY58yyhs3OZ`|#ofWm}ahFw_v{E@=I3~DW!v-7!4sBsbQzPv@+Z;DjpPU<0?2v|WQtS-VXy<%a^keRuQ9LpeS z%npvpRj4U!6qd^$fzO5<__0|JT>aBQuVpsR z4t93D2&=zbA;!7GMPb$yQgJJSUI=YMSK3fgj*-Inx24D7L{{5`!4Qm5w-+E2z znBpROl~$ovN(xl}c7X8aDjp8Xr3iVlc#~s0_+w(gew{rDAYu-^X`|GSp3AfbS<`1j9_NBL@gF{%9BNa8pD#g!sYM*s40LkwAXeNsCTM@-y7CIK*bk)2n#X#vrDCr-$;x&X#PTt2M2el_oTu7flB> zF%#tJRasZvv-@Ez=cBx#={bJBS=#RvgpJq-8p*&GwQ(m$!hyc@dJZ;95_nQWa*bmOdAh!FGd)%6uCfpM2qmI(eSDp*L zzfnj#{Upa2_COJUZ~ORclzbwPL-q23qSUhI2tt-6D}M)th_U0th*{eV$vgCrcwtQr z$F#<88s<8q5c5_#?9#?{Hu1Y{O?^VOq2OOIoie!{k%i5ojrXElE8}7&ne*2{=N4DN zt5mJdlU_GZ(yZ78Dp!RtbEvmCAxt>6nSNcrmB<5SnPb=DfVmQ6x6q*e=)SE{(a`N6T;|orF#o^d|Ige~= zx~kynnn0>EwMME~L8 z^sB2jz2&=69QM|aW0dMS=>o(YJ$EHzb&q3{gc*NEa~!k*Kgz=3~jxdoD(?rw#xK83yQX-LFE`e*laVyXLCjI^FX z{ZCra#3j$f$*%)B=7%~|uR)B>n~iyKD;JTIIyN-4&jm7k!co<*S^J64kaS*Nl|75) z0p`YM8hL*uG=`5XhrpUgyvcABuK6-S3_h+bG zWlf5owqWBbG^x8@JL=G^E!&Xn#4-MA%y-0CWktDMp7T-Yw%Ug7E7F2FkCm$KO@guQ z8rykLvLILI62~~#+=ASqYanCv5dG=IYUxwOR%x4Axlnev6>E}XA?4!LF0cbz7*Qc? zZxTdis`nd>Alz?^+bK59@)nHZZKzG=TN3VhRW;-C3L+0;7BBw74<7PO+wc=xuEpyd zBOg5a_Z}zp?>$s{ShHTxzyw$P8grraKzrqbAE zL1goKc~07%rSg$qx3uTHe&g@=7-}9zfz4@cNUI+tJqp|os~=aA0S~pMsmq>_^2^&L zt@cltj2VU)j0HL)Cg;^L#oOu{G4P)awW2AcyK}6{aFjc-_dtDH<2v~K;~?)Eio1tL zDV+MQfx8fN)(57C7=VdG1#4(HOtu;IlT3ZHnAw5Lq$Ikl^t#_)B4ciu0|h0=+siGA1C6 z^{qY$SMO`Er+tIiy!1(A%KF3Nm;NHZX-s{-aYW2e{cy$Jd^Z*`)Rx}%Su7eCu2oqT zH}K(dR~)yJ6U1@NuE2*KXkd>{OQ}oI^`ci>m@~$MT>E3hf;$=0d4GS9gwvH`hs^iF zR%J^#{MU-gt5K?NngTI{-}oyIWvyVPqiyMk!jIydqkUD2A5T<EuqYSg*B3Qfl1`rB~7eSn4RkU4zzmAWVn*nt2dCt`zJST!iag zMWSkKBT5I%h}NC$bkM{*u(!yP#Lb!|GPe)l@oN{yyi^Cb6A;tWwa~@m$xim&+m^<( zah0wg&rmKdeI(xBQwCo9GoiP&9$3D{W(&-9%FRhjcV&W!(KX`KIz~MCFr0kRJ3#$n zbZMKkO{C#hs<;TJ$GbW1}

    be8{bl#rJf-aqs0!MBsaK7Uz4{qh*i{jj3 zI5DLw>~-$Ix&<62)wYq;=#(LSS9OL||9*tdH;r&AC6Ht8sz*syBBpSMwz4*M9P^oO zOI5vN*(2pLTGHo(C`X;L#cMxUgyA~Qs+~W_O;I=GK87s^CxMfOJ*#RRPCoSxq&+KJ z&}8dqlAvnIRNfe^Hl5EgmFoJs76ZJ9ER^f;VA^@t|%f}Utf^cXQU)&qV6$ zXT&kaYKe(Mh|wGKHMjASZr;yPwsg&uRMPay1==k3h(i8vWC2>|Jy)Tk<$LfixCnax zRY7hOw5q}wdiJH>?62y&@Ym)hldtl0^kGFzrb!d2cXSgbuciv0G+fOI#1y7Gxioz_ zPWa$%OSewGA%qP&L7#r=E66h*@_VxsTNNwjyacb#m|E>p1^w;o`4pZ@NgKv;#|oW% z+Ody&3H$Q0g|K>$Ih)ePmpxn-tB^5+)!SM!Vm4nYa!KfLN2r@?ORtPKCL?E`re<$4 z1-F`~@VV1v)KSex^X+HQKPd$c>6b%bhZnpvMF(x0l>VaPOS-q%)FVyID_VwT4-bin zkSE3&JQQTi3iY;@iI^`>dnlk?M>2bpElsp(0~=FL(As6^m7Y^7a7#OjN2x2&|7r!8 zCLP9x?g!x73(q*HKeXSogq$APThuAsBJQhk5a&HHGfwNh+08NGekz zjYy`t&)!=yyh6y3%tA;nLliQl(x{mtN)nPJiPU|ceQp^GAt6bUIdkGgrr+B8{(RrR zKhAZzE`L1Q=bU?=wf0);`E)Z1=BI-!fMOGpIwVf&Vf+sc-MUHUU1K1cUtfs#F5W1` z9Xu&+JD$ohA*xgLYk>KjBFJufZ$wWrElK|)CDNH2QDm0ub%E8SYrBT` zJt(mx{ccpyiu?14aO$Ygyy6VDcs-XZk+Y1T%iP{LXjC2#ZdpdK`A!aM$#oz@H&zH? z7xsvzFGrHI@juYTKgY$%zoYqTeBjImg4;U4oSD{6rgh>VO1x%CN=h|EpMC~pu02HB zgH)lq2gGh24Bq0m2jYm9)^zlDx~KS2FM&*Q`Ge=T_7cY&^5K|Qs^In$VA{;@TynWI z2bs1XK$7y+spbCu(oMB=-ZfO@H;kXEv)psglJDrx?|uB)uo}UlYi1->CzX6H4n>`` zH;Y<@iDcA^E@b?M2(fOupjivOl{J$xP*B7X?42Hg%b@I#@$C`5^zU5U z{Q5Y)?^MS-Qy#WjljjaWUwXuF%y`&3VKsVyxjrmU z{@OYSMTZO^m&3Hs_ndfT3Dc z`ejc;M|``{>cG)NUT#K&uXjYhyW2QsJydZ4V+@$?fj#7!KgS{e;sHdr<27_G?YPpt z{S@RIT*|v2*vKzy>N9CQ#`SENK{~TWZYu6XI%*h_f2w3?wslw9y{QWsd#N+gO#dhj z9y*s}WGaj~V0@l8IPL$YhXy_8$vs|%AFI|ny;n~0rZ3`Ih&b7|d zbFu}ZXGPM+spF>i7nGa4|3QYkZeoux_|8D|&oE73pVK(0f@5l*6yk@SeWZt-7fGe* zhXvnb*7Vd&L#h6Far;dleI)2mOZnxB9ktg;Gh8tJ4Q|pdIGeVJOA>?J zO8IKERG&2hn7$9=WXHO77PUrOk-BO3(eG7fl=e$xsOl3$Gy0#g!`xE7L%VEy%0*6D z36ISbey^)Qz4rejRWDeHj+z<>ch2idg*VTm(3)z5X5?YE8V}WH%?&WC_oT^=Oe+>E zr(2Q0fUAP+@WMoH~y z*Z^N?>Dlx2TJkyMVY*0qwsbYWX^EiA0g1&Ct-jmo`-Lvz>FjGOVTua=ff46{$DWN{dGR7 zp-1WOK|A2E#XE~G+J`FJz+Pk0nP;gvm7uE z_flos_kk^2tQD!Z)1_KN=P0A+2Z^&sR$%ReS8>C40aRcVxZ*b$Zk+^ovaRRvcaJZ~ zw?mv@a_ooVS(-JeeP)6;mPa_fI6XyZP0Yk)E9Y>`Ue#*+873@B7P)&H_1tAe)_2@Z z8#Fs9FGL%N*7;SqG>P)g`!u~X_`^&vt8KZ%GlEEMiWXRYQf_~c-WC}j$xTJtY!;fz8sn^yW2K`&Wp1mU92DRdfAYpnzZoS16 zZGT0qADWFO=B1Ktd-X}CT{N2iAx*UT+kyCs$*P;C3e^(;b0O2mDe=lysv85ZfLkqf znx{_IrctL&3WnVBK!eJm5n zHl~YO(=>^5*BFlRQ^n9}fLY!;O)kH?h;9kAB7fx)9lvx6(H=gFvZ)Bx&NE=}4BR-b z0vBRP+(Ap#KBEd7&vM4YE)An)S5nZ1V-cj~X-DE6k&gDhzad5$eaFN926D_56($=n zUC!3Y$INi1KoBEwZmhehsF*L(e%-F$yo~+NtdkP#H!w$Xv<4T;{W*A*x z7LVp+tbm=pE%|V87ka!*huRHzf)|jf9Fwm~Jn{kKP~0e=t=W;z_p~BzD@F-3J=00d zvs)a)>Nl;g_u*|%p5U^z`Mhx~(B~D_?h}u{FB?baZJL7?P8>#dje3CRr28SAzz#Iy za2ZYyvEZ1#s%LW^FvB_@kSjAzi344&i0!HEDE`Dr68<8MW3->-^Xb)ZXWsAzf0nJW zQiS2jW4NEbC-rgbgJyRUBzFDl_YW#tt3$`D_mIY`n@WYRR-rW2)>+0@6W3aLI{Ayj z(bUl+=s^LE~oY8-W@MZP7t(Ly29x zH4V}FPu-~H)R)xq?>)*e_NuM(24H%uF?DvxyeWG(1a4Xz9bA0=2$_=ERbF}@I)nxm z;UM_DdBgk@iUgG&FOZ-Jc+Z2|K{xx+CA|WL&UQX@&8Z#q^TJSJ&Lkt+C>^8yza1}S z72Br!BI$DwP7fyJpZWhV=`9kJ|!Ku9D9Co4bK?nlJ3&UdU|Fw>n zBG|BBN<*s{xwBH{b9SGock!I~eKZlF&RA3ijQ>_u=;iuzCe0xY{hxg95vd2x#_$3VWxM9^xU5(`Zy> zfVjQAv#1F=-bU#fcydy#sDJS_$1rhV_((Sa#y-ncCSNfW4F}Bh5&m??i+yCWPmI7U z_X>?*5OWCle8X|~%fE4a>tru9Gv2JqD3qM*cOsJyCSu&ZG2&gXTvX6>RN6aii?~9W z!!i3+iAM`yG@eb7MQ>eRd3CCPg#n68M^Xzn2na*KOP5QzeY`9{5)Xp8UvJAr)cc}G~O+$(+=?nRyyufwIil10r6tsFBzl|~r? zMon1l{H6a=m+#2xivq>XqFr+geJx?i7#`0oZ@0f;)y0Mo`ht;EXg1ajPDMQ-?> zl`^B;WwTH3;!_dXkF2=*D9Z?LcYcLJ9;EWsu#8~UWdl;FnM!#r-)VBddHYuR4ha(Oh5p;>3j zL`?%;iYVNxsuApZU_+u0r;rW)At>GUp!nl=G+BSon6&pU6ql6ly-5Td%ju;n27Mb-T$(rXxMN=%t996~8PJl5>>7pExjVo*K{iPkza-(ni6U1LV#chrej zH$-zxwF=`3m@w@h^8C#{=+aLs0tUk9?aKYi1GncRrZvRW;MklrD@fM1!h8n|FtboS zPd*Wq3;IC^U6*Uv z<=JySP{yae_ub~Z2I2NHYicVSBt=vWlFIeFQkRu&k#GC; z$VPS0?G;>6 zIqM#Dc}0$u-27xx!twQj^#EJC`(iiA6RuP7w)CdqM1f(Zt1y0mnI>7uTr>B|zlK_q zImT24OpB-m@|h^S^m4#-q{2q0;)I3$ldQ9q5G2 z@lu%Q9yIvVZnVHE8Z%5+)z>o+Fk^QvkzM$(LEN|3nm9J52S&h&+ zyx=6?Y@+KL`PRu2kE$a{cmipM>p)#(;r3Ac#P0?Y9=4N?`rSvbKZi?r)g#ICDW0w9Rgq^!!jOe>TrmQD-z@UMQnwg+;yTI?Iehe<2m5U}6@1{RYGx4BG89mfv zC$+5{jPj?nrJ29LSq4_4uZp2}1IG0G4%tPQiF8JdH3{<%7s{swDc5f+7fRvqv1!9C zeC^Ow?7#RT&Vo_6`=%ARf1-##Jv78!jya;jRIe@v-I71d3 z6H3b-SrZ$Vlk{Mp>(b?`*`iY&2$a0ndWscIHLuz83 zaevCDBG{2???eq8wDAn~odQRykP)zsu7)?INGlIa-PM z;*mO0|GArE_CuTo7zJQbhP886>W0y_@N6dbGn0Y~3vrM4?mY2un0N}0xC zXe!VBw2m&mZcVmyx<|F)wBy;em6Yk(xa|Ok%jOZ#26q{+$~uYj7ea8`_Xe)Z>WNcQ zy3tC%bfmXBkr+@gzJHU0ntMJLA1?TfKR52=m@cY};5J~|1y;z7LZ;C>Mb_kE#xd#= zu#$ML8b(`3soWKwZ}-M={crOF;)Pj~(Jj+nr5Bj<-We4bp}-(%tCs zD`PsdrV(eaTh1}d;X?p7trjqjZkmdB`>bdW_<1%B?I+~q#1ieVmqj+?;m{)wH)%(K zvC|`tVSP3pQycNF`fYe@uOW1FMHo6fYc?r*`3WBn0SU1A9cgLt4IGX~ag3X4HO~Pv zC*h-fj`k-pFWH)CEh0$!dNy(1cAkgoOgX9c!Xe!H^#yMnW0_%c=QvF7WXC7II6x+<`?ASbPd;SO2?huHEtB!^~0LENvpZwvq9il#Lo%2o}LT*U>AT;T^BHKTh2JgSX~ipw^|eTO}glP+7S|$rjQwK zP&Fs98bM0Y6Fl1FnUU<|lYfv)qBZ&D zC(){M5LsyW7a6+U!Tu)uu(_|qKWo0eVc7lRRj>=G!!DQ3L2)uwGCtA|-`I0iHnEQZ zctjwab~{`OprzuxPfz$w8>q?%tl6`dDZr^*N% z0rR)DgY2kxJlcEMn#|6Or5)53ledrN3bh~yYO!w-udVUsq@e?NDS|h^*q_Hg#&1V^ zss|A3$)&=y6H%gC%0Tie<~B0)IW2B9D(09ms)`2!%#=wv&Pin;Q=Dl{g8tb{4>g#Q zqGA8?sR-ta%QRD1DMD*|8?H6P5)bATp_3GjAI7a9p?=N6zv+46IQO;W4IFYEyBjAy zGjrh2CQ4QD7!R18v1Lxbl*iHNLil>#pwu}t5f9Ct1GWeIao7ecUW#B{Lv28|h0RGb z3~w0$v!`(bW67{r6H$(ZpJ*^AhHPv6jPI(*1Cw~1F zM_&EciDVr6D{!^o`{M&anVn%3Pv}W)a znr)qV0e$f|c{xV{#J67hl6D?`FQ&+ zd-8qmb~3JEA=*J(MHyX5CLZod{B{?LdVLc)=C>-1S_7CL|7a@I?+2qPy=@4-`WN}j z;*{I#cA(h{PhuDIOkD96vI20&t}=_};#ur>!^}?#O`$Jm%M{{N=8n`J>e6|uT}Y~d zDXHySEgl>d#WB9{^@P;~0p{12v+}sPQ;>nX4RK7lh_VJ9Q|g&mq9)4{kYrKtY>lZ} zm41hn3@YV`2UD_Gsc%G#x0?{n%Z{jEeka=TdKW@37?R1)e~Q;E7IDlP6($TY*7@t!n-?Bu^kDwHq`I+k?6QB)wdI9t~$~cDAq@#BK!4Xjs?)SGN zYFE;Yj>{^?k7#>hL3HVidP_8L<7V_1FtByT0mi6hh_i!vv0$~=h8$P4Mb?ilDBs!I zAr_|@&U(ic#~8-^L=DJMmvam&MVPz$Nap3<(!2h0;d#jbx(u5A`@uEfXdilG?s zs^QrHW-nj{P5IB+ci3Cm{URHZbyf`zv{EWRFVjZecPg+;{8!!s#W1WniS21DTVth& z>c1vZ^vnXwpGwreB z%;f>n(7w0Oii4HtReU~Xm^G@Sp*+CM-?&t^sWL~rQDZ~2K9!>PNm>C3kD27VV+*{m*J?fSQ`f zFnX{HKxA_cFf)IL%FG5rY3G#<33l5duHGB3RI9%un1gqu_Kzo+l_Hq!0V@-+Iq5$y zZr~e-=Hj2jzoU8E%V@zhjF;xO(2H*~XrGn@G6Yokhg&yT2b_yW9F(F{3`&XF07UvyfB9*7}%0wt+CW&s<*Q2nycvX z&sCmDvr+^)L9yXnkkZw^!5zwaula)>Px>yXy(<<&A6b$f54CY^l#W>OcdxLjOEg}# z+=H;2_J6Hb)qqKh@RE%$+(dKqY>8;Rh`QhJqFleejTjVLiL>5az*tBWIzd}RbgiC0}p+e^;;Rl4dLspVnAsf#>UM@WUF;k&4>L$LrCWK>tsBT(4U_S0M zmnp{Yq@(q1Nw+C!G_h!@H14VvHTS!ReL-4EIZz8nn}X~yK9B$CKfr}{XK?RhXV5&I z`Qk@iZ}jA!IAXo$3r2gVpvQMp#0QtZW8#{?F;7*P*MOPi8sh9!vXhPgOyBIb^l7<0 zzTd-|dRWxrv|BLG(V&Z+WalvJglw$@;nSQFoat4GCN;^$(@_Ud*Ot9xU};BEk{gAL zR$dT0TnA^(0m&TGN7V+`44Aevy-J^*-%3e)Tay3r1ns%D1?Mg8M_B;Hg4;C@`(y7> zN__ubKAxXghx_9zc%q<%?d-mZu4gk*&(C{^dKUw7M*S!nKKzuZ9Mg_?_{DO}8Tfg^ z3;hc)Ge*SA;}Qpq{Jccw5?nrKTIf8~qe-@v*wcu=VE5}r*I=VC>p^AI@o!nW5=$(2S@_tt+ zO=$@sEo(lDtm0w)76cnTH{sTrdt3yF_1Ul!sO*x(7#Ug82{Yo+ik@ppm>Re%2z!uX zgFfvTRgZ5>o6Ru`RY{>fV6sm?m2dk2|9#7bsOdH$rvYgs!{VIiAOmBqGkLhS{T_Vo zVZ;9t4_1nJnHG&Nri`GkGZ&-c7(||3xQ88PZbaqd4d}P2mmtlu=a_0$QfLC0mYcEi z_J$>*n+Q8}^=>qy<^(ae*u^sf=B~hO512p`t9bCl14nO3y z*moQVH5*e0-yV{KS5N8T_FyE3n+7|y1z=8>%`ZKy*-4xVJ9NRM0_4Br92s!hUBOBb zK^qHra69|!M{Jk~QsHpZvgWkl%9Ai0>*z$I|NAMtKk6W{>&Lwg$bV%Ys#DoU(h2

    ^yy%xORfgqVBzsyt`#{?e^!=C=~i7-&5PUw!LPHeONVW%?=b*+_afB(?P2= zXDUkDkxO+Qks*5TbWd7(tJI~xO{v9$QKZxF+KiN2HFg-0ORm&r$e%@rNT`V;EysAy z@RkR{66Q`ZsSZ4;^s3bwyH8>iiL@G$Ds=wDLOd{Zb;6=sv9!oqoH$}S}Q>X5g%T0~;^-kcZ?gJKiq_CJYI(N9$ zEqgKmj?%y{r4>n4CH5FA1dRFWRNH@NM#ZkTwgA973@ zYuG9!zjnX}mPZS%!#LIlO_p0hdxCTp7Sqpf&R=0*JXzW0NT51!WvY6RljZ`Ba1Nn6_tGB6 zTYGu9)QUV;>DNUrO|@(q@{5ahpDN;ZwuWUr5x6NMjbX~gKt77AkE|j(v@0FO-U!^%2NIa!SO+j)Npa3Aq8OI-rVz2d;wzs7h zd~2RO_l;JmK)LM}R}tl^;;JpU4o0`r$P#5j6xWobgdRRNRFv}9m~|%=vY=E=HO7`C z-uqY!pFh=f2V>kLe&Qxm(}w}0m_xO;_7<_^ySArCdqG6J?mFE9<$5)8&%3K^Qf-Ot zrTDRKExo%HD=A3Bu1GU z<)vE{d#3ldqLvTFSgp;Q8aeXAs6oKSsXR`lZCitVtm@SbG80VPjnQtoTb?6GW*l0T z+i~3{R7nmkpSqZo-Oi+>fRGX#&IcV-4adLj`FB3&ZDqvc5TR~WPM^6{`BMprDwkim zV$p5uv8NNuu!(e{zLmAiXWf#M!y4E@7AY){x~gF=d0Tc`;h+(*_-kdTudl-*q^fNt zJ6hP-=f@)jgNYV9fKM^1!PO?B}lD zc;x{KA4P-TLAW&(0FVI#}n z)nTT3#Jls#OVT##iky;G%VoN(#}Jhs$wIs~$pc%nj9_ES9ltGUo%R(D&$ zCRE+yv*{@%StdL?YN);icf#ycE$NizdYu8UZwX}Et0JF=d z_%XNA^{-bbOm0o%LYy73Hr@Mnu+>f2DXYR!6}tLlL}4lnbBNF`1-zxUq^A!a(7$e{ zTHer>?i(J$ZCxewxT(&m+8w=GlC8qr3Tv(S4nw|f=u(6Eb&IPp9u-;|C? zRuxlMjXW}`=;D%+ri#i)N<)4cQW7E#B!Er9 zMFnA+EsU8^sOd!OhD2Dfsuk>oDk38Xa}J&W!)Pjy=y7T6zA4Y))U>0(EkJj1T+~TC zl(lzS)K8j;&+*rN)Z`U#9F$6x#1y0~_g{vbpA89-{{yME?Lie3YmXFnfIth`OqLu;N=lSKefm zcEJ3z_19k3vFbb7y&G$?l*bY!-&cjXZa$^C;Gv3jQdbJZq`QORB{4YUp5TM7_l6Yc zD;!dW+;f@z-T<6_xYf;jEaOw_{e0OqO1cswTej`89Ja;y$?&rQZd*kYNu7n|%yQP8@Kf1x0fCV?Deq4?K-5zwt6GUX`AFoF51w)XKTUM1D~%C!y3C~lnk@F^K9rA)Mq5uX;*dD^ zJ|oQ&^aScY!$r0mYmNgrKo}?CDajvGt~X*frTB%0-5yJ6o-+hxfEIO z8K<=zyxl$dMYY6J#V#0)A!h^!ROtYD1q|vlGDEhMaH&a^S+=}%yoj+$T*`X+bIXnK zCFViM9mYJduEV#Tr&62tlsdFpQ%*){DP~JbQ^aIjK|EO_d_IP~;Qf#6V@2pXQdDd20z7LKe2vQbq_T;??E!x$OPwU#lpR zZ}>E-RRZ5}_hUo5FNvz5+cI8d^{}N=kjpQ-F>S3laJJb1f!`XLp6F1&-YVNzhNv*0 zMIaA%g&C4TB_&8<2~h-k6$AWr!%&qTn-R%UT}o1n@oaMD;)x}sx7*@U{RjQs^^uMD z_G$Gqu{PtEoXGaB;#qWAHtM4$wC%p!M$lc6HkTq3FF6pXlj5?M5RiT%k`x9s zD*hd6^RlQ7G~1pN&(&oqw*!qV#$P5vlAg~r5I%T1xmu&Ndp-L1y40>&5}0aFc$8Lt z?WqXHP-XYdc;o5cRS`BNwc(U8NQlW&N>n}Byp*f5k0NrPhdunpqKrvz$9d_JBgSQx z{An^>Pu<6k7vZHzY!A96cmQY1Ql-sxPl0f;Ol`)Hl`@1VsPREBkl7^h_)o!H+ZC4(C*BaM)Eg`LpY;ww5MV*nWppaiX}s`3@LI844|&q4Jl2D@iH=J+r8# zV_ecmxe7?0TIPUsBrWc`tlkZ^>%-Xtd)BCxnjHK3?AZ7_k0yxPomE1IxHc4cbE;uY zslU3O)cP$?2uaChE-TS`*K=X+N@nBJo1wn%yr+3OSg+dGBTgfik8#)rWh$KTN>3HK zDUQZbQ22;Xe)`Nmv1u0O>w7sjZjW23Qx$P-edoLOyc%FcB+Y)`uk7{4?J)~#OtSRm zmpbpMfz25%Q_!HWRmC_N=_*j5RyGbyQeDN}ytaqlo(dHA;V=@Frv*HcBQ`=XQx0P56 zO)jNSZ4+t9G1{2Zzk1qRK$jgrwtFb3zwu}HTTVQ+LoVt|PTt$q4Yq<2OS`U0gmeSh zEv~lm(#S~10F;Tqs!C9lM^-m&b@ZB>wzBYq0l2wn8itTnyh=oOdNfQBqI_ zN%;Y)5DwuN)u~Qh7TJs?mX#q(LQ6aK}wwbStqc@PNOZ#1uGsI!h(i8 z$8nD$JNoJxsfbboY6>VqLQpb(5Rrl8JN5%n1~?JRt*ysQo1XUMow_f?$OUjXb z*q0ST+^td8c*%n3Xh?!m*m9pUAwonYhFMC2ha{#tN(d@Z)^+GU*Y2}xR|Ok&dU5Jz zZrpBcNvnrQ4VGy=Pq# zDRM3@h3gDCPHAnpieBa*Axct-Dnew@5J2f5bJVbCzE^v#sF4IhJ3ZIXSHYA4P$#tcj_NdwvNNg*-Mez zXj*rSnYS^yWnQe(UvN-n%!14oqd;~%6(N8dQ>#_+iytSTCIL|)7RtFE*fsX7`)OKCOVYL6~j16fGSo(QZ z1B|}}kW}T)A7gLXQy#ST5;o@VT#DAg(yt2LsXmJmE3M15XRxSs81UBGlG0Gm6|lZc zl&J@Z#tF#REr-(o08j$fr@%#tP@~kTbhgt%nNxL`3J4EW6;XvKI^fJ#+LXxS^K9qS zS2HhkFW1;|JGW(NZ*>Hw?S<9MjauT&&0LxYNb zeD^sg$b=PENJd_+)N^Dq5kQ7>(L5Yad-N@mm*hZE>imsEV1O)NXDy1nH+E z`R1gp$LPY~+*&1)&GUBKmfcp{U2#=+5mRDf2IK+*#bfq0dYfNBh9<(+#~s53xstRs7?hQg_mdFkIP@M% zqi=0q!P*Qk1SCxsl091QF%&YND}nz=YC~Orp{$KM_+Y zr^Ie5Vvs>WXts=;0pC52rAMWQk`h8k%<(xO5P!_;s#Jgp!0q(M`fDhFK?h>6Cz0fV zdpFb3O^@6zO;g44h4`uqb;nAddBPL$^L@+`oaf;kho7Fh4pj@uC|PSG;rI}i&=Q`* zjt)ur=jEwk*$E9fkOl$4N#b%3%N_jx0G7He$w5j%^D0+ztorJ$y9QRB0>&;ULR9%o zQ%*{bl#oiKM?JfYwIP>?1Jkky{dK&bup#uPZ1*-WIpF25ET^!*dL*<2oSw=&0lCqw7#a9fqBhUWD zC-d{xGbD^CkCKS~1w&e_90NiwKg;wBIHutR6gsO!rAlFJzY02% z@d{b+z*i)=6XjL?f$k6je{?FtQcpCY3c8_*bB zhU6eR8}J@Kh17(Ug<#_bUVFoEckV_oGBM}s0q_3Whppu{r2&AEkWL4dKBu|ut#x%Q zH7xF`ArFn>*Vl9DZ{1{5VimY+n=K5+DMNwN;nXYYZ>>uv=A+W+o7vLsgK*BJE<=?2 zw!^430(4hub(m9Yl?sI-sSVLToguoTXkD0F3;J*MAY+Yr}N`z)`_P!QvJCNM2Xsj+)W=KJ+1GU<(xF?Fi#pwz zXT531rP389Q-X9WMhwX)oa|(~BBvHqYN%VM$=6GO1RQG~d*Hj5d3Q3+i%SY-Wy@8& zDehGjAq_VH-?tt`S(y^jLQ;WOgzZ$gPXMa(h)5g)QzJxaxQ;F8$V)Fcq^WPVl!p{S z1QCIN2NVv&$PZDSa;*{^jAHxLq($&tWi27)ptK|{E=nyeCz2NPpsB(RRHsx=o}$CM zKNx$&kWA@-B(~<~kk{v;-eMiJ$&4`5RM57JxMgu@4Q-9KumMpnvDkf$+qi189832F zNBcf51*5@QS6mkCB-Pw2Va_XX%w=aF;DzM(In|`KCG~`mdk~TWia{TkIraMbYWC|J zS7=vdxbqN`43#*yR!g4<83)v7Qd2uKZ8EhsgiKQ@BsQh30FleK za<4z>`D>ujMCx|1PHsRKzr&*974o*Cwx($HWR5N#g>0AmKR(;OjXjqAF>emr@AV^k zYuE1JZh|jrd_B3c>Gu^Y?23INEiN-ce5&L@8d{%rPly%Ex&TNW!N~sle%WoB`X$o3 zU+A*^xmNj9DqYdMH%%tmgo$K)Gv2ms6;z}@1u9Z-lP#`AJXExUk)}N}ZmoJqWkQn? z<+ce*q&6N`a7v1TyC{_squbBErqn=&%2Jrr__0D84W!3qw#aNAK|Htg06!+?EJmp$)oMCH09{b^( z`FiUZaVeB&GnZ4ICEazjJgE=Xt|z2Ql(`P9t;qx59aFMhQ_2caacWT~;v{4k!j`qA zDO-zkf=Upzt1C(f!AMZ_$LsaiRmK`W61jHr@0@q}pU+l1W9W;XbxNmKm}X6sUdmFG zAxJ`7WC7VNw3P8}KSAZ`u9L$E!162PM{^q^Tr?XCGX7{{T-detqZsCUqt`~u zO{gs`#;sT9+HRLz2|^`TSTUnGrIUoVUlIF$e?3v#A4OK~Jyu)#BfBXU?_0eIR4Yz< zoj#n^%W1yrA!TT)3AZIBr$R|3v^zNgAgeelB>c6PPudQ*>S*Yy*14ocYCCN2ZMjdL znCU`*msF2YTfxVIO3OHj6eE(n++K6=;{;U__QdrMw0C6nI8n9TS5)mP@?UGf%{HTY zv0Xw`71_An?Q%*eUtz{R2jSM$KHFWni@83_-Q%v)o@G((8s6P*OgStk#6gD!yG=uq z5EGthH0s2K6$9NM9N{|B%l`l~eLrQorvCti-lOzd27;n+;u00&`3&QagrW`!^Ugnp zzRE!*^QbE9`)XRxz0#t&$!c@5JTO+GlCpRaoZ&x~ zJvA3f)(#Ju1SiY6^T%(``D^Rm7>}1_zQlAO4sO2ZgwlC;PF0US+L2hgQ0O!W5@5%V zOoJLT)e3u4T`i!kROco$7IOh=N|x9x$wI=CLFFAjfP=ZU9=EraeVb{}Ew`=u9kFcM zHr+mf4hzh*!dMh&i;(O_mnA+dx8HHayx>nIte*Z_(*gUkiyy{qx1W%w5y>l!0!*gD zLWmAB`z??#Q~CTO>8ytI_1AS0+NDx$E!34drA(y9LljGaR^!z=q-I;~;mB@Z5hubJ z2tIi9^3`)Vb5tz{aJB}CebH2^lxa>)snTS{kj&Pqt(ItrhcTDimZhODw$z7<7o+cJPmg~z0f8FgO|vKHc3fJYJrHHw>_ zg9_)ROQ+3QTdm7-WO{?Z`_t7I0>h)l2O%nSsYGYGj&)q_>Zy^v6li|us+569**OsMQR@q%CnRRN6ha}eOk1kaC2b-$<=R>{+h*y+0 zo>>5PPoI{k?{uoSaq70M_7T!kOzA7HP0n&<0-r>)FWXw_n&n0-kJe=_iM03JmB51U zi-^%5RQUe&%_Y1|#Wi%($;fA}JXszr>U2s94sA4HVBO zDb-`CMY_J{@6wn;l^#V-<#C5Qcy2O^q?M(_5!;vDCqADM)F))zFGjc+UmUQ~UL1eI zr?Bec*huK~su4h3uM3Ox%(?@Krsy-VR><*bDQte};5Cpqpufca~MUT5<^=dK3j6T}1906PqJ1Glf2ZF3WnPt51| z=!@kl%EEYzXBqgj{B!iwb%bHQSv`*&dUnU~)CHlH>=v?!jVU{iZx3_9n zg-j{cC7_p^qcG!ekBqjGOYbL%Sjg|4MERP-lm4u)2MwOeuLTZq?MOH&SA{TT%k;3vx5gN0s4~ zs5JA1ZM%*65vp=h!&E0X1~su$khqO3C&NTptqc#t;1&7n zUtLoT8{-lHA2y)++f}&3u<7wQ>SLxQ^3t%#;nAYnd=*=fQgNVAr;3#6J|ATv1Z4gv zR8J4pAolXqA<2%Dg}k&c&>>+-zyt7+_=nfmIo3CAo9geQ%tXp{YNad}z;-;DZcJiW z$OQ$rRB)vcbiL(QTVEXIjg|t%t+*G0wWUCD*8~m0tx#xjm!iep3GR|Wa0{-*p+F14 z-AV~opg_^z@T_NM&Aga-aqk~+*S+VSv%hCtqrjV2*7T3Y7#{3OZ(e9b{s-iI3R18e?;B6No|F4=N`+h>ovPw0 z%|LPaAgsaO)pe63lZmqDvv7S;j+40gHq2tLjA!>}! zx6=!ha%vK~6Ngo(OVyhJ5wZb1V5?ED z!2d9AL&`m#&bKuL2x)db?f^{u*PM#j1;1I(|$p3*_%Y($WU6|HGK^8jn8{6&1UdT{ng@#-XWCcA!AK*(fvK{hKbD(h8l`bg4|!$skb?nQ2}t9 z8K6ltJ@}%dT^Gsy5aetH>cETkxf6SeaSmJ|@R5ahcS}Z+NWK`wI>#xa zQKnLZU%d=Z%-CKmLa9wHn(Y0pFgv7VH}}0T(0fh_Y+ON35;v=;K=X{UmJROnRABm~-G!PAwUqFC{g!g~iW8&n>PQaN%m5S`((&SDUCU8+8h}$Z zn-(cd5j|kXtHU_LkYKlwu(=ekHJD4SY(&jUg0WnrWH6PTim4VNx?qGG`3ot z>GtB=n=5A#Y0{y0b(L$-tkj!#y4kYN3tv=qgwGo@rV6Wmxr_9lB^}B#6BuOlbrj=^ z>15tHV@|>h(ENQobbC*gA-){j4;}^ls|RX|`Ea$LNF>P=v=M?h(!%mK&ouE0+(I_m zQA?dBfo&#l-SiK<{+e9#@hFJogY}$av!yYM%+23CAY=4+#F|WF_Du5gKc{MWs2Inafs`GawwEPX-@xP)R@XB<%^s|nM$b| zbqg)dtq}BeoJOZ-B7`R@8SS4EP;&5B6-O$82YZ=R7@CVZCLSo(Ao1Di2g zH-}nSlzwVxOBsH*WZC4*jh&=WxL~yN2Km>$&v@>OJ(JA`zqDkGn}T&S*hEw7OKUj>jpdhpOsoVr$#och8RpMXan&z%o@ z1e{Tp{+jvfX8&K(>%-d5Gvvh~@nsaN1^<|(Olu!K15t&*xocY~1xL-@;}eq}L_f+>O}FI~I{$gjx&aopCcldW^ zph#(H7P9WVrRcP80xw3y$VUr^n(ByN0Jc_=ZhRIPKsUl{hSmz|s6=}^VDc0D(!XUn z1B=;B?P)hYf!8*t196`*1?Omwa|qo9xGU>}mHnBP=BnPAA`A_}c{`x3M%6|%;k?R>tMA`o8<^DRoRwu8W;>0#Z2r zDahw#@)nvi;AZCdfI@rgjb zMTi_0&lZ%fQ2crmDk;qW=Aco&Em5v3Z+BmND$$4bc=f=&q0!yQIcVQ=!WGziRHkPG zXcq>(brk0nDS>RagQ6=^IaNTun^2Kpir{CB%tui4WA4u=y*fj^ocQQYyg80r({V<7 zt2o;x7cWjy+a_k+@b{SE=RxT@4j7z&Mb01DgyY!hy;FaF)l$lR@$Jp8{JeTjGo<~z zUcal++%MD+c(xXDJRYhKq^yh(43uY7i>NQdZN30+mecledx)a=Rpnh}`==zQNAIVa zHtu8@>BJh$G>6cdBc*IilU{=3hr)Duk^<>U>)v!Et5BP0#EU_D1i3hmt4;{C)>+W^ zGsbUT0?rYF`JO$Ng6F3zu>q0Fb)QD&RM-bbS&Tf?-Gx+ZCj#Z9u^rqn&Uw6kE)j8H zuU2d_!#kRRf|c>D+BMCyGi3-8<#Nmn_WCUu?^{Taa5AY1U&_XQZPx-$3^dlShokdN zjhrlL{e(>)RpHx|e9fPw#l(PX2zbE8WfcDiJg!XIaE@unT(@9Qfs%&9z=K~%Q(5nx z%+Jy56wl?KVMnuKSi5Nz76z^79BaZADmeVVdvg>u^%Hurj%3MUbCx&!sghP?c<^$e zsnPF>-Hwl~FCTWZhmfc9QD=kaNxSwN$1$d)gmt~of8D7$n}E^kC_QT4G?PGh-Yz~v zM)qs2Gvc+7^Pl7%=XT^QKN$kl%EqC3nwjhZ>NdN@1g3U^`UI)d0;WN)*`B!ylQ}&H z$|noDEmrMaj3n#aB;KMehzgJHk>y+55T9HFPJk+IpBC=xHoSWzY55<&7w@0^BJtyQ z*D@4#Qjgt#l`yMx?Jo7zeShc(_gH?xwKLSl@$pDDxEO}v9xG)7%vnS4&2cJN1z>hM z7)(67_<(zwE) zv!@JK!=QY08wU=NobD25V<3&9)(0+BNbh zYd|YOt~Y#B!My;Cxvd76a{E=HS@OAyvhErfZt{+(6?r+0TP=WO98NyW-mUoe+y!9Z zNH*O@D$YR98Kku8H_fa*h7(wwmGoRUe*(IiBMkH*>ZrPVM@RSe$`%#yp9 zg%*W3hs|m@!KxUAx)%$C3N1i+2tH$^WYUxMJ5$lD?YE|iiyS&g<*;IaC|TlboeQ7O zgD_rnfI`S(e87E_%fhrSn`jwFvgjt258!40l&Tp1$b^398h20X^c&T0vIHFI|Go@M zT(E?b)DlY@SKe{e=l(<`Zt8kZSbC2iuEn9@@QgU;mB`|g7pbcG78Rn{5ISYjl2&U( zW6_%pP6R+q^2+dz-e-Clzo?3wPB84K zZGUc>vs!LOpglg|gx!z9fmv-hwxC=5fW@!ut#akaO>ZfWJeBUa#x&3vGXXg_HPG9< z9d~Mf!TLP;jz(iGOt5mtQm!$}oC3rVQMF*yy);>~9F*@Q;{D|3_nx0!I+Uv;ngup- z|FlirlU~N6;(n@I&*u&L>oixuLvi~pcm9{DQV_V}X~X76g#E|TxE9>4U* z96S-tHU}Fh>+VYuiYl%4nRcr=*D?E)LQra0F$!e)X*bKO%Q*e;5}GwVopr`>1!Qet z{rn%s&#*cXsi{sLnqO#V;WLONeBEI3r`xD2H-ba}VU%&Jk1s>sB^Y0@&o!+pujMU_ zE~)*bd9uv(Ir}%FE0}FK`>o+Gl)=2-UB9V6W!^n|eIFyz@A3Oh?V6hay>K6@L-N-N zAzd$SUkU8T3GS;axCEyfOV@-Ry?tXi6}hioz1rrYQoPwryoonlyR2BV5w7AAO@oOM z@9XQpB0cJ76hHLf1_T2g^bVTEKd63dUlLJ7Pny}XkH*kM;BkDtjO@CmoN(j-3RuU2 z@I2_6iF{qg{57Z8J-ZZy`3jz+ttQ+aHCm=x*?(HO@3-h!o+Mm2esOACYxh{CRBS0b z+ny7z5@6?wVaEKkEH`?Z^bYNJHL2k_fiBdxnF|+VB??YY|13HV(Rz?e{Yvdt`9y7b z`S-Ep8eKFFC1~~Q#3gGArVm_TGLDsHaxmgLygaRZ>+r_fRAho^Yp7kg)|a7C^|WB^ zE@`hOHCj3vt-#IDap&o4&m zrcIN^HJ{^Qgsn)Mn-@K8kORGJdefU$6BT;5aUP!BT2WnE?^bU}bgPG-Mh!8YNqTGK zZ`|=8xo#a&1l3rc5;4pN6`ES#|HGiDE8{EMP5t`RG+0}%i-5)8d~QE^Bl8;U?~tcD zlENq7Hf|QJ& zD#R8fzJ|zTbW8^E`7wO{m*Cy^^dV#4IDEw9ETU-Z9g^+!oYl~bf#=x%&&z?8;(wJ5 zn%Y17hw&i3yFeE+9`)mE)?>L&_dFl-6?e1lLzRT)Zqez!X6q#9?t8WFmYLlmkV<&) zpK9YvI74W2=LoCxp$XKjP-JA(0hH~PGq{q`MC_%nFp)^!vf?ajCkc$fiVV9N z+~xGFbF_VLQE^NabH~754ckw!w+$;TsAX@l+B$12Q20{HRcBE$d0LSeJg1Xpof;`(^!JW!9diPUXl(xKnDlzf94RQF`VvLmV+dO;Yb+ zFTA;5!&WVY07L<<7AMneKe(p|DI~$hcwuayBmt9O>Opvm|7$x@^-jRb4Op4sxokfb zkmON(RjFng<5FCL?ZjD)0EzZJ4e`tukXT4hmscknff`2+e`9;qy_`!0;$~*L*iE5} zNWX6PbYPJVRnV*HTtH5|-@CbS>x_?+*X}DZfs!cY`m?q*DWQ7dCBl-xXvrh~x|Qvw zdfy1)Kq?btBCXL^^$nMjaUz=1n!--Lu}OW~fJYf#2&@d<9bae}s8Yl)eifWT%62+a6+)Z##9e}sTp zI<dcBo?e&T-^QRD#aYjl{Gs`f9+ z7Rr`6P6us_&la3>t}c{T9#d=?$_j>m?dDDYu3XW4plWIQ(Mouz^A+-b-n?F>~MUjW))fzK;A6-s3_08|(*UATo z#hB#h%YV`j#z#oTC$FZq2^z&z3LwiFa1GDcI(t(31hWv4`r+M?9uyFFTD;RAYvF6HU>lG$8?`VowTIE zR%MS314LIdFhOqxoTQX^8 zNET;6yx>lmD4Q|m-W?07?2~!eN*YYx$u^DJMmfRUAbL+w;U^W8U%lhDK+eFklS=fo zdfU@y-pt?KR?lG=sb4i#d89Z_bm0Z<%JwR}7wP@f-MRpi`!~~xdKsqU<5I=aOc{xl z&jY~cGU@u<#Pj_XfnSC5^{l<>(>wyvdak^CZfMBm@Xvq}rJ+SQuoD#jsxRe($jv>J zu*$HdGf;LJwVbQbztVlOGO?8#1Rv;;0O;I$5Ganh+L7cjDIW%GkS9TG3d{@R|xaOhbQvbe8%^@asMQt@BEb-{@%1; zCr%smAx4nVx8ChfrhY_(jZ}s{(Ea&>?a^}axuw&`6Q4kHLs7~b3q;{aptz$K|} z-xS4OL6n#?UVMuBCA&~H($raDZvhD;_MGg|W&+Ketksmv@|F)Oq|$cPR2(8}c|4(I zseKyqA^bDxmU4nWN-zwkmFS6_+vMJJTpH2A+cFnzj`oH`u+BY_z`|t4SgBxgyo~4A z4O9O1DoC{CsxC2UNPKz9u)E;fiRpInLSa26t@ngZ)n=1O`wZu8qrZgn^VNeXS`|M8 zc!UThMXc=-YBICkIZyymu&FkO8@t%9p_2QJ`=xcKLUD0{qag7GhGa z1)pPW&@R_2Rx6t-pOAHbs=LTGwR^K$^z`Tqy#~2Ijt!K&rfvO^oHwEppSI?liQzU! z2?OdTBn_OAL&=sjTEcf&^3@iw`PC_7g*u`Z-3~Ju$x}p1H+f{kfQ32<M%Ic(z3^OK0G;3a>5@Z&BVH9+ z#2AD=)yI?J(qgk4POYG+1ok>~)hgK7$9qJC{E5+Bo-OHX+1->W;#tmH^CWd~Q#q7h(UiZbir>BS!bmDC}EFd5PZ4 zmYY;m%+~c*zOh9(H5~^B6$UgdSa)E1mjv#AeSs9wyOg;kA+7|oDX9`c#_bx*9e_-yPa#a<%a+F8HvG#^ zlvq0_LPf6m2w+BJjwon))QJGB;+nDn8T;*4X`Aw_y8Eay)X@E%gj)bAd85}vFkfqM)%Q|)22J2Eg2V}?AyYE!MdoVM7*!u5 zmj}i}gy3A)aOi|;>hJCBW58~33yOq;+go3dxDq~ovRe~VGuM*jZX-~R%zX244PH8w zGsmXBM4&D_yK1f=2`)nnF!RV^T%la(4FN_CmnMpTBjz+Bjwu)YuA5q`ul7(rf|>T9 zR_}YHb}9H|$n@`f8?jH$3F#tRHM2#l1~6)?V#PxIvG|%>2)uhzaKp3$y^vHXkoi8h z^mwboTgA6#Q0FAqZNs;G?gK#gIJaZnhe%gILbLj}N)Ncu<~ffs_So6I{=M8*D5B-I z7?PhaTWcbm4e=k3JfxCpUH$F;Y0%8uOb8DE89&OP*M*{U$ksAfx1$K{oIuaPP(cf; zOOFPrfaL~1+pBoJ&raT_vnh1BEe|S_aDH@pjp-lyNJQ!@VD=VL+4t=ajzMEkY~`q@9p4b(vZ1^PuPjrsC&|)5=!_vq@o`GfEY(S{J((;*qv-=ZXJ?9NjS!Ra zL`|-u-sey|%{^04M(I3Zf)$qq8sa8#EREQE(=j9j9ekTkDK2 z1>ilTb`#oan)(fmDVY--MNp!`c@d0=_Dw6K^IE8T!mxdyx zmUaA-@X2m#h^@a{)79T*mCn|ns~|;x{VYnsJ+=*}7SO`nqCR2ary25#7yv%>ulJa% z=JWdbL&iYI#8HcGg%d^zNACxr#U>7+2YqyRRoxen#D%55b0o*a+ZO3>M1LOtb96Vv z05~J?o$xu0J5EYkOTP6u-n}oA&NHpj_G3HfU!vhW_Cc`58H)NlN?zIr&2h-?Wg+ZO4FhK&A`D-B~@@Y(UU|*Fx zRD_5;r9{T)zlLg~x^<_$L%Qc~>#7{l0kO_$7^YutNStx+%$ z5ozHGL%N%|Ws`6MK-S)X?K+wA+Dgtb14`Fg;ym;hJJF<$CV**-(SogZ3% zeS6&C4kpVxYi-dw!9Rk#*uU2(-$*{IA)4B>pR_jTo+4ccbc*~0iqcZh5Siskexf8$ zLb;Oq=JC1rCU63#%KV>2ut~Art_ra(&H2#72dqqZxt+!Y$rxL0EG1K(Px$uOtGGgU z?=e-(^UWt-Tly&6;m+zWu65QmioI*Mk3OYr4RG(AR{Q4T#B{v>=) zJEbX)n?r}w<(S{I#p@ZpSMFWnzAG#5KKtyu*Gj;jLgw{`Lb06vEmwQA2#U&dUh{XK zBs_W+jjZ@u9+r6BcpU-GSi+SIvgt5n05`7_FDM|!n6xatIUSeWH*zFszeCIYnHNJ| zisIHA%p;2UCxtP<5QilEW`{9p+62>|IxucQtC{Uy^Xybfy2jzJSL*@+8-&SQSQ!@- zBoO&e6=9qas8DZKPFI}=sl+IIvI|UBC#v$!72W})au;4Ve?^FYnrrSzcx`tqEZf;y zdleZIUmNE17EsEx5ykR;t7Nyb_T3p<1h?o4?h>msg_`yy=dxLG{gsUK(OSg{p*s=6 z(hy1)*y(73iau59x0I;qr-D{DR+Kt!PoQB*WUO5sFmYscH)f-Y(u(SHpD+8HVb=*t4L@ zkkTCxVhsE;9(p}YdN^jpWNIQ_DIk=*JjRm9)zFW#Ga4UYkO(8fuZH!1nwCbKm8xM~TP@L4|y5N$7%t^4kIp+lW_9lW7L0;Q( zBwc7!JFx$pP0jE&q(YnvSBP4WBxV2uLsL%rYvGMOt$-SMTy-2&D3#C?TN-;a}56?3Bb?i8_$CS|2FIY z^y0w7dPA|piXlx}{2zu6LnlZ4E|C^#6TREVx;6VsRsQum9<2_Fe_#zset_ zzS@Y3JpMd5Fndp^N_@zT<4tUH{zi4z7Bk^Yt;Wn^O~(h!cq|s3y)x!x(c^q8X3zb` zqcT+>iq`Qt41Y}W2ZZ2XlJ4loU%J&Lo{akLDNQ2jQzpsut!N-ze5YXzBrhf7%f2>8 z`Aa|(Udl^z%%~0+qlm7izA;Uv- zj%EA%fgs+qcPEAadQFTm@d%i1UcDW?*=xF2Mm&zs>KXLd9ZRaJgQ=fSVd7wT{Pri| zS9zb{zGb>nsx{E~NzaE)Ne_mYQHjz{JX}@N%IQA$k`n!^i{qQ1M_gF52%R}LTNjw{ zrt7liS9pt+maLn$p8~COPnlK}4ejy8@x52x)5PVhX4S8@C+Fx3v&H`7^8bI&*X(fi z3+g?n-H{rXz2L%Qt`(H>{3G2v{eWDI-JsEaw*;h>*}~x7pJ)xRr>#rVIFUyG^6%H1 zgcSp;)`k2W)p<04U^b!WxSRs-`0Kx3;MdKbp#|OQ^iQCCTrE5B?!-n89JpR*i+(t* zEClP@|G2w+3v^5L^%I1W4mQ!gB`nD1zOjfZ86(g z&AxFbA>P}w&)#+PG}LSNpo=VpuIhFoFWARJIIIUwiscY%^G_&E~-%PdaUt=H==W!Y* zwz&n|{nvsV0hd-YzsM^kl@E>jroBy#4@}i8f8%5tG2Fk2;Y(f@_#LxUH>*$@xF}$S zc=8hK^p9i%DI+k`si(wz6CZnP%M)5w2~f+rsKXN2E0}8Yv45yklG6fP7Aj*sO+71f zF@!@TJg=J{Jp6^k za~IK^=`ICj-gPc}&dzhDZ`m8yCPa#D#I8`wv_7elN}86LOWUwAGOq70QiO`jgljFo z_@rOy&!{SXV?XJ%0P)HEEpN+MHt;deOecE3>YzVT&4x?fNfevFKeYPxaooA=g2Jlj zyN}f%iP)Kloa?`=y|5}9bX*|)YG-lE#~DD26IOzz)k+zdzavmO9}{i*1j|Sfp4Eu& z%hnD8&rO0{+Fs)6N)IiZ0vW@;DkABdU%GF@rb<^yPYCS`&1;pzs7MsF%f~AENld`l zd*2b6&@w3HXB;&AI7(Snm>RZ5)mGQGruWp8EO;GzPg4UI5KYk~!ibOAq&ft>oE2 z#I&+CXFXIDPR|F^l&-ZKB>r`tms)vJ_+yV&vFs`CB|cYiIJ1)m6i5Pyg+94LCdxtfsu|Uis-f_&7O_sxJ*n~c9xF@k`h?o#baQ-b*6SQl@!;&9U z!|)dGc22))Twl5yCz^D6E6}SR1fy|zZ-#^o>NwE5v>o!=8pCzaoKcUsaOKHW2$FNg z7qM9Lnv<`J$+Ax(1_3cgJ=Zb+hk-8c7rb@vm!&G>- ziJ3u#6YvU+<0ln#z8IGp$!EN}K#nx?zF!vh+i2O=;N?-0pYFPv7uNroMfoLm7NR7o zP)RV4q=7XsJH3Y=H5#UEugrOGnd&pN(i@vs7++8xLMz@G8S;Fpq81MvmRH?B6}l`- zRK#w~53|Ub+wcMx|Aa3%TxoQAp#~Lt8SbKulpD;B)t2eZat&5$u1j@G##+(Bh|x4~ODK`J)Kj5kP|KL~NqB64@%EWc zbZR(U2$3$*2TBRmZ8+M9<{W59i-dIbh&O^f>~aew%)V%@{BzHx-a3nwzq-?8>SKhi zFUitS@BOF_DuSs2lQHBliikHkg2CiLavVg?t#`Z+pn*!K_u6Z$^S_>6x6zKD-P8r7 z@o`HOa6aN>jlJYCm-iTVyS1dTnj~B?KdIR=zj4CuF4_{C9_K^SbeK40D2j=gS%$9r zm#@7^sVi;f*rVpk6h3p{w^~8>z1~B2s~A@b;6#s;_`*0pe3q2MG}M(FBP%1E3t6Mj5ve;GA)FPdb{E-RyjIpm_0luZJFl@LT6X0l zI6~zFVAA&3Iwr5qgzQ^8rGH_+%i$zHAH87acUA3| zRXf*LN#S7PijBmxq6)iph$&yuIV0_{b;Gp$*v1m9LQxnUWWnz?4ITV4)pge&Y3wvo z;AX%5Bw_&^jG?t-m;jFb`jJ2?>KqGXskL?rO(}ohwdYq`g4Wo1KOk0snoy-fuA44g zCE4SQ6)}hYmMrxGma=-Nw$A~I(zaJuVX#s+vYEFQY)qXUg`uqC)q&#fv%+y}JWfaNv`&O>U^Vgg5J1AU1(Qfuf5jcI?rtAz< z8pGI>686i>1#T@Q)^)AMe8Zv%P@+UBT` zXp-rkHWNo76^77fGMft<)YI-% zX{*->z2jCdQGUO#+k^b1?VXDV+XH z7L-zPQZw+XpHv5SIA!g%r;Mk&|1?&UK495Ww*D05%P%d>Mz>497x4i-66$2><^P<~7-hO6MR`KR5c5Uay%5pW<*v6IZ#1F*` zVmKG93fuj7%%=9BLb`t|_}uvp8kwY-&bhUepkP zRiD$@<-+6DNT%n{^sUw)g}Bs8Nbg^QxG4OPH0(|1F|>eZ?9z^cq$De=6O{HEjV;qJgIh*j=>2* zsEsqBKt>sB?S{qDlngwux!hEkDEYgSQvnHQ*1}X^lB=e>S6_!zGNhcovz0u5G(eU3 zm3*u+hO9|C!zR~6%hT$TBp>VI{;h|7e*{@|mKJJix)>7~9;_;6nqK66{~+AAm-qe4 zcA)oJa}9NtnDH)(uF!;q9HbhdbY?C;l7c%t%Knlr`IYR-aGt7}-#wz49NbbaMvIZQ zpPrdN<#B$TFE{zo`FIeqtWmC&FKo1@-C>?0$tlL{8BG?(&&w?Ai;k}1#5!3S{~DXC zKS$N)=U4QHyxLQOmu>67YI5F;vTw+uEMFoyN)U0ilcb?{~`` zE>?&gl&~K!fBttuU_Ev=RFTe;M@lqW+b%vF*7(%y+CIWQbS_>@l|P$t|M_E1nCm7t zMvfPtd3Kw4Rd&#{g2NkwJV@~tojl%-7F^YRGjBY~K4LepO|G)V#5(0s!gJ_#!mIwW zGMAq?_9H=pR!Jk6RmI6r)usZ0A(HaDDc$>Yzml%Jl1546K#MB+B%S(cRr{h269Xr` z$Ro!bSumsKKAHX^B{Aqb<1dMB=jZDEI^Fgto@Iy+=P0g!_fI}i@LkA%7&2018gIBt zVlZ`n%mi4uLSX>xOmdIu>FK}6wcS{;djt9umA3w?Gxab|E@o;?46%DLY#F)QZl)0N zt(0pAFgq28sw=bzhny0esM67t^t!f6-8jJSBavc4@T@96HZytRGkw^{cG0=-*P+PA z13hLJUFG*??V#$&mvD)<6;^5(Z%NikB2nM#Hl60@!9_6a&_e#tGr4ziJ+scSSL-Q_ z5L)_oZCB~-N>PdpuR$mMRlv4`=230q1g-MPptbf74dza86JU-P3Mcgpm{H51TbuU# zY}tf>g>^nyCi*o?Xd%&4hZ4LiB2|ZUlz{^ z)zbb2@1w=$>X@#DYa>RyI||Y7Yimy1TCWj@=Yfa*6Q%D#(HGTkHA}SZ68Kx_N>+qK zqd}Av34=DxTatMe#F~=mF{9w0wp8Oa?h#JLP&*%@NjC$#jE6dBU3MPps@N^WRFY=V zY^l&94|p|O7~ddO9t`6S=LC|M3HvwV*j9j8=WuY`2Y^zs?c4=}H`kX^$fl^Hp}!i; z6^V5Y-P-05RB!7V_mG_kie^bSVXifHC%$>MlBN9*j}%+<(Pg+_udZX+h2w`fH!bUp zrunri56_fOjwqXlrgq^Cf{XRsez|g{b|2yinBB*t^@GvyiDR^6JTXcF(OW2qQj1dXwobJ;-ip*N`^NvGHqgA+OS z=Z;*bIac8L`8*lt90v>x>*ZhAe;PiCI80R_Ml4bfTtfr3lb>i0UOMk5{9c_>-3fNI z%+JxK{>{;ArE*Re`p&UOJmprq7`U63C`~|x<6Fhaq53Dg%|=@@Ar^A$p{CPR+Mrkdl~oo$vb@oFPgQkqZru#6!U$l+}jm> zG|rTs1=$%x>Vc0K;ockt>{~YlH}@gZ3i^O!T(mKsR^Yo0uixoho95S^_|#O1D1#M+ z%Ibw&Z-(p%;viP00vpk4QgF!E} z&O5)Af|}ljdpv~(3MXUDPM~7e9`8kpRCXQrraN)ihQ7#|qGu&A8b6Vd*K_Bku8nET zv}KZ6fKs3{g3xzi-OUmx&;^DZfZ`Mq`9JJw(afB(`Byb|rRS@fz)XV@oF}4ZNMcOo zKXCTBwor_6cZB>RDL<&5h2Qe)mN-On+^zUN=(U(3Bj(^^d=lI5XvZ{P$4ElTs&SrT zUeR9}KRH-&Q*~&m2m#pSca-eM;6RYh%3u_afsD>nCi?YjW>UST6aKJ`lN_z`3?{(e z4l5QJ>DnJ;J4G;f=(lw3JQH1~VN6;sc3!Rt0Ie9i(M@MwdaD_|kw|Gh1*k1=k+HX; zl5mpxGfm*34J)@O#1%obN+WEeNW580c<#pW&-qP|D&T` zgjoa4i}at0PJv>$v5#f{U!QVAD>(&k)H`<EZ^PVGe_B|7W!dOH#NpM1k#@;XGDs2mPD zPh5=*Z_e%4uJqA6)`#L_PE&)BdShQ6RvZ%LQB=WxZ%9}81X12yLXo+^m1$p|=lHsa zv48T=C#3O2PwS#&ZECdQDWNfL4~7ZYAYsQqknWuAi^r;F@L~4?>RVwFj-}WXvFqEU zw-syz@;6jmcrU+&On>}M4C`!l=LcCj#EE;je+Eo35%JxPCpT<_h14rJj2%%0tIdgg z46Hc~(j`9-UL>LcFMm>vA76H@>j19U;i_p$D~K;Q(n*TzN|%0jxYjl%@=Ng; z5(Y}5)DwfS;QhFSIJhF)&&R2y6-oG&k%F%}8(!+h^{Gwi4sKrIvE2CjITXQgcEnE4 zX;EV?A{=upZwNyKx)SB2!lHjcsZn?ZkZl>3)PN9_yQC1F=u%N!L2MDZF-CjaT}0!5 z7)QU4iaY(f625>E5pTR(#%j!9Kv@%hy+bzs24xSPBPL+^q#IN38Z=P2r_`Q6UX{Tg zOLwJ#g**QCT6})`%EMc!6I6cOw{AxU&b|xtlxqP@ya>;zp!RtElpxqnG_@N?e)8q; z)+uMF9i1P45nsBk`8Jq1pbr}l<7)mHeO*h+N%u8g$_0U6vSI?BhK$YMV2?cS{?pq8 z_rpIJ5=23Vj+4_RBN{@p;Qu?p=1DsHc*Rsv+-UszONFZql1UU4tA>Ak_JTy(==kr& zLQeVdE6>4`i96-fxC|+7l_tN;Mg)D0e8w2Q?W$XtcgyCmuPKJ}N2H%MEeM}?!ppM_ z$vOmRzBOqJ^~Vw{Jv>--fSfKD9TfX)fc$Mx-8^ioh^KNy|5)L^T~8Q@T4YCtDP6~8 zl6pMOY4ydALY-+QzSk24%89U~X)=D~YFXm`JK1(ub62R_m6?7Zrz|JmsIiG7xho}% z6iN|ap5%Bawmw)}w*B{Ro+yb8-a^}Y61!?FWrHB6Tp`xs;U%p+Oif$5O2OSmaw^2| zlLmdpyB_2M(5M@S20h~x+s6IF&G6<+DE`HE@uP8Nu7mevbL}$co|-3H;42f5B~a&2 zn1E$_49f>B_;`KbyXuvYH43=N`QJyq)zGWgj9Gc9lt~?e6$|sH)=ZV z$e*_U?it49z3eQX*LFO1rVq887oD>fDtgzik%((YODk}I?Nl?7pA)EYo9Dx5<>{M- z0F$mbfgMDUZ>zvN@aX`=w>$EylLq-rGFu&Ug$e$m=H&LMWvNd~`4G9^U#srmJ0;6+ zUq7b4?lixuoPtK^>6k8yDF+di%qOXCUh10p^^6tW4)QlTSdm)o<1Sg~;|K=B;;DF9T{qB4#Z> zE>1FfD1Y8<_4iS2wdwy7Kh0W^kdeQ(5?XcX{oNF$cCejdoN3|>;hNP6OlUwa!qp5SSOTC7&-0Mv+SV+mS`tRQ);4ZT!(!!d#KW>)f{DSh1E zjdnI(4e?6E`I|KumuuB%-M;|9?J}_e+^;nJD z$ByLq+iyNu4qCr$2v3WaBUedYcs2{!EGFpwwf!`>Xe%wwH}H1;(tTu=@YT)AU8A_Y z9=GQ&-Z!f*;l7?cfeRY#hbhjS{Ci(Ug(|H8zwHPNWSXVQO~>-gQi#**iSy70zzB7J=$D7$PZVIvQ>OECI5~aRseWi_ zb#f4#s-E%QZhiGcHH>np#E$(G;iqAvWp)*?bl@W#r{CCSv*dXl`%4$5^h^-)$A&j9 z9%1V$<~sJ~M&*+3eVF$ujd5Sz21!R#_^+Y11f+-6-%v^EFZXXGu~gY*1NtQA>uqCR ztyV1@WjC=*XWGqk{#>unHTSypGUuaVu<2+Pb2oPE7-+}=4FUjOz4YIF;k&qk1&7~Z zzryVG!DU}~Hk0+?a=TH+uF1x!G^x*zo-*pcz- zm8q}Z-Z;Nn+fH$d$;a?PKr7_p1Kgm;e>^#x^Ote+f!>#fr8DTJi8VKQ`p$Qs?LaB7 z4N(^|XV&lm$o?-Vvh~m%_p#N2)oq>Vfh4xUnCY;s{X0D@Os!LP&%q?;FW`#9YYT|3 zE9LcZ5#Xs-U1^`S+B(i(jfH7Mq7C#Kh`D$L_w5Ad3mIymqt0NI2{+`02m=lUv}5XU zNeF&#oG>jH!C3FB=2wINqNSOE5-`7^1HAEOY)BPUDd?)a@~Fz4Ew4JbYZ=KDl+fLj zP^z1?)Xb#n7?K(xM^l~#Z~Knf*{a&9h$smDkMqnMNBMW_z9^xqTSyKHauw!PP(yJ~^MrL05ZS#IFyKikT@I{z52Z4+t+ zxl$!nAe%b6u|srjavyeneC+-1^V76mHziriEm`Y(#ckDePsao>nfQOO^;SV`z2Uod zuwq3@ao5sdZ7EQ^xC9R#tQ08j1d11T3jvB0O$b4YI|YhUph%!tad)@2zn%a7_BXQ+ z_Q6VKa*)YP)>?UUzt4SLhIy;kN6EL7bR!;wUef<;_O9k;Reyv&sZRdi-GS2o{a7q? z{XehOL`g>8?c9Z;=k$5EL*wQwww@&a`*`s;v^2Ju;5wE|Vu*`jAkg35LaFOgbs>Z) z>V*gb-bE}Ag~$dMh;4iS)4)vbo;-9R7zWWCM*KDPOnn(<{bK32nXV zvO0!z26Eu`2a!qmp!B0DL{lR-t8@oED7qXsmrMpHTK}2S@P$opX-@*no*@bRj)Z^` zowhF0Y_D;8=S8F@n3lKcRApu6+-77^uY*3x>~$wYI~vMv#{@06yL*|Pu3@|Og0cxo z`~HrOWZ1os%t8{dXQFS?821tZmpP!8Z@k=xk;h_tkV1r@1mHnnQNJ!?0IN2=^(XK< z7Uk5cE&UF^NXKUJqRAm*k~^Sh zZNaH0{`~=Rz3@3asz96jU7iiL39SWMjw!ZxHx#T!`@i5G(c#3A0JZ0@U@=t`p1I-H zvR53=+%VP00QKRGmD3%@T+6JriqjXZ$9d%Q3>RFwbM^v)CK`pd8}SOAfsX?y4$4L? zyip?KzssrnX_OUzr--oLg2qDym~Hf#KlVK07ULjF5YZj41^nNuJBokfZLxn> z{=VI-UI?ZC6N4pafXm?OS@g*)xj=q%6RoNp-DIBrAaRX260kh*t=?9R>dJgl`Q;YY zdH%b}F;L!jN=UHVYq!-+>o$t!V~fL0URy=6fMlgeVT;Y*B*xEN&+UZHA!gi&gRu{1 zWkT65Ge{nD1IVjIzy>UDn8TurBk>wze(e+p@|&2inUQ%KDAt7JEOArIAb+;yS{di| z%H68zhu_Z_v@mSyG(N$l! zZ&d=*DzS9unNd2Zw&nc%Q)Xq{81`q|Yem$K3XUWBWI!SDTo z{sTCEM+(kH*t-sDi%OQHS08{fu;N|FrJuvsBf|1TRj=R}oxFS1PUCs~8jdRj4^W>Q zAj56KqUY*5Ocr-qz3|R;NkFnyb4^IVPCf%|6+o;IQ%-218WNM29`t>O) z4tlRzr>;-1C9P+U6AvbQahf}NyKf!1*Ck*wd%3;o+BNarHwGktrYbS2zC%d(%muwy zjoth5bAPzL%`YUV2YuZb0wJYaC_<9XZt*Dz3rT6``}#$7k%$1 ztU)d)OB&qD=Q&8nF^5#skKZ&pI3Ukbm-%DY)+!{aew%qG)A-tCTWwC~3!I`-(SP7{>YL{LE&E-JQnE4UQcm5=hS`@)HcCB7-B-4cNhI3=?EG zTio!5b%&o3X-hc%5z^Pa6Vzs!bUnkA24x9WtCT5%5 zSck12skLRRIpuZFx#Ffw4sm$F5@ZIFBzu>OFyc0<(mfHUKGWB_rL($-@19#woN?F6$w}osf3#EtayM@0sQJ^Re5ImlSmVYMqycn$+Lj6s* zCfBi&8Lm(aSN%OfweZiZ3G6knsQ zq0PJ?hF^4N*|Bddsik>;+OS6PvyrYr8Q5ChI_k{iu>p&UYJ4G3`Jv^)L1d@+`)6fP z*;7_hMASnI-Xjn-O$P7RO*ulDQz%39#h9)JhK}~{pqc)a(~o&|*~^U@G)n&C4yl}` z!>6Z9k0wIyo0yWTG1I{upIs}K-$~{Ksr{YJ%;ile=l0dbXSP zzqOiQI^zl#_50(ZZu!8kg_#_9BSwfOaQd8waK+Ofl1CsHahBHaf9G_&{L2jYPb2H8 z4KQoT{-J&hC|K33AYSA~DNJNU@ecYSwYWT6$9Wm9+fc>JA$4nny?^Nf* z<;q$z#Ax9e?Ynu2s}x*2f1q_EatqyprjCrMRg6qYn*zWR-9@oZIpFM;72H3rc^EUD>$yjg;^(!#K`KJ&G z^wsAZiwb=$1s(;UPKSZD>i2P_&xOLP&q;|-5?9~tFG5=8gRgFns-=#3gxW@6y3sS( z^cp86GTGAPBnhI%RQ~)9kV;YQ5n`2%(OKjZ$vGNTMNMy%8w@|S8Hk<&2uTRu%&4qiAN-6z_0$`u(B zYjh3aQjO#|8YPpnO`f0qlbK zt@1AEPnF@u={faw-o_(EO?97k;auIyB4wU_V}93Qv;jX*j?W|==qUY3LiOj<09X5D ziu}O4(9)t*Geu325p2eRxRrl?NC_Ev2~ZolRh_<^(fVdJ{TC`I;ucnE&ztZUH}2$w zG|!K%cM}^Ikwm#vq+lXPydHCwrth?nISZv_!o#VXRo47!6aXGma{VC6@)!1H5!x zC@HqJy`-FJeMKkL)XrX-2cS89jl(+(?^72?#!~b<1mZW}*qA>!`x?2DhQA&wQ-5D1 zSFVK|CzWSlHhxl!6{Rh6{fsE5`!E6CC}!i%CI( zI)=@VFp9oa2mUSXei+00XPa@)1biAvgf`_OuI+A!x6svOW6&oK8Bur{g8KOook#E_ zCl&l0mWgKt1^7I2!t3W$MQKql=;=>ZM(0dk(S3eTzG5|<(`597D_?8j!EEi8PSncR zPguSJVt7z&rvSeoYE12auNn9C=pL_8X*jjYJOzp=NkWzK8S~LE<6rVJVg-*7N4Z*UI9J=d01-#*37hM}jj1=U)|6*3hHy8SS z>26kTaw#zl?65+cXQ*S*?)_$qWt3h(fuQ>{pIDMoidIjrcO5tJF-GE7yH@fc$7f;KyBavH{VdVDF|s%vFq+PH#muJ_s$`*|OcuS?j+-5<(d=+I$u&>MxH&5LvjW<# z*P9`ZB5XB2f+PSpG4G$-cW>l{>c{mue%VHASrU~*MQK*XAe1xIB3}IjFLQQe zkF_28SJ8fux;8ys)<0wydJ5@uZmM|Y2dZ_N_*P{gs-~w8y5TWJk55}C*~U<)nOH~-Ju zBS6D}=kOlUB8F-06jJ(|z+b4>SIBVmNImezZTpg*ju z^Q~lcx~eJ2Oz#n$rdO&d4$?ZXPnnzgl3leim!0tSO>d73C}KH z4K+u0vnWbZ`04Q(AL--bKz!42>O)9^mPg~+Dn)*jm zd4`Y!l!{xaOiyv-46g_@Ap3B%^+lU0!W!bUW3S%)BFfmsxx7GTq!HJmR-zE~oTyBg z5|TFwiS^@ie20IlE^{^0g4F41c5 z@E;&uzHqd44r=>e0}+mAH_nXvMFBnusg3%Sd~lNdy%lrp)89fpBKZEem8Quj^9%gD z=k5)jYjm2bXIX#NMo;3oIB@XEI@LNwEXnZ3qGXBhv+*nzH*|}TP?n}$#&DQI@~)vm zc~h8Y_+|t51Kci^s)72p#khA}o2UZA2csVKEFOGcfRjZOozIY&edjBZECST07HbXYzM>~HYY*PD0cb8V?Y`tv#B*q>wy)7GgQ$%t}% z>;UVMz{!OTinSF$-We2WY~OW#+K>Y8{*Z`oY!jAxX$Q*&97{xl4PiP@Rse}GDPN49 zSN>)}!NY$53y%(BLckrx#du5S5zvZ;hXbEGi?mEZS50QdKq}=$R%VgcF@&26F^nFd z$6q5MHMTxiKUq<-NMuXaVPawXJ-{fl{T9&bBT zHJZfLk0@0PYc_#4mI!j6nG8+1K7j~P4E+bdt2W9+Jo%(zkUkoxr;hK31^A_8wx4|W z;yUTc_}uu+Fap=sZ|{OCnDP>mD@NIe3DBdsb$O69i7LR#6HW1 zSd19B+^0yZ{IQ|E3Cvt-7WI*?-I)X3Gp^I#gctP|Z}vy-C_5z70ogWg#AJ2VhdFH*Pv zyR0s5N{<6)s&<8d z-`Izl{Gb2P`3$6Z#;0TBNSc}(hK#=TBxn%(u08@YfEP;%iov5iR~O{*5l?X0aXtU& zc!j<`C@=o>&E@B2OEVpD=}gVP&+LhRV$WxIMp@&A&dy-odFOguvR|&=y!a7fwGZvn zCB}}-jNUuMYxsUIX$eIC2bf43z66z50htn@NB{Ct1-lyuNp zl7|{QCO&Zwd(-MW6c{FJi zsAw51ME}Gcguib_!(C*q(Xfy^_Rz51Gx1@G|BAR9!?U)?PHqu9@DfqLnauU=z39Hx z(cYq9O4r}KhYj#@uJ&^EvdDAzhwJhxSw5Dk$s61nE95lL?dLN|gH1mcjk>Ni?(h+F zar|?g%xU;Md>%t$zQjNs|3!hc8-X}a;utDFohlAF=~KA9yVl8%ZTtL|>koPU6VpM@ z#C!W0=gzQmwr=MmfbBJ_6~_f5=elEE&@i*--p-!~e==WOHHnGT!K`UEnc#O6?1XzY zh{V*lJDIWQrW198K+|Yl9p3%NErA8Sk#P7s|A-3vTW02#A{^W2$@mq0j;g&-ev(@Y zZJj>sqDIS{^;{C4&zt=p<-sN!I2@d+5=!xBylR*oKPByCWm{Y4AiencB9!=X%lD&> z)if56;1Iu6JZO+kS|N{MizSRJl@+nSCiZ~t9Bsh!%&Yl|xYQ9WC)V6-83F zI()_2)+FecP2fPxr>k}nnVOcr!ck#9@GS(i-O_ZuT_+o`-N8G(U_D32GE22!_E_@V z%)a-SmWi(yleQ=cM?s~0W{vil%)2*{G|#i<)>{nn0O3zzBxj4$Mgomzpp30g>OJgf z+bZgJ_Qnhivp!ilPJ0!PIY2~V#N9|BEbY@l`T6M(FH4M<)b4CFDS=BFk_gp22-=y&{RL4t=i=v*_xwZ}`>DH*h0?~%dh3gtO?j1N>8Gezz5f8y zNq)j1oG+2$UyI@4pcxOUU-aGd=YyjL$H%P>heo@;h+#`+5aL#?W>k)M37Fvhu&$`i z7J>zb{CcxkAb?9eUIhO%pAc7X=DA<-cyIx2a${Q8B69Bt)jLdrCA2iE-3+Y$u=w_F zI?v74k!tzF+ZZZEq|e=}A5jRBnam6;CJD6AB9hb<)AA7eXHak? z3an`~&5&85-f9*5GaHPWUWSt1e5_G~3X0uCn>w^9x+3NIbYAqSUNN7}wRgn4!jVr^?f^4P}!J`v|$kqKd$A91fYRj%oyiRy59O#*L#oOYP&i+HrElKY3p{ zoBYi6HN>55E_+-|R`o&OM$@zVkIxLN^^QStW5*e^zp};u8L^tAGSAb)zQcSK-sseu;?eBb&E8}dR2Ui3N4 zQ_oB`ZU&Cg@;bwCGfy7SKKlZ96*@Qbu}+UI*&kN|V3dIKb;8sujO5}zHkrGJm&Li6 zMQJ1ZQP{yc9;MCXk>jA`b|@mZYd=LZem?^@ilY(zE<6hq;?G7 zbICFZh^`jZjevU5S z%jVH4u5ge64#{&_&Ny{(d?fditC_zZuHEe$Z><`qo)|#Dhvj|=F+7nR${~2B0C5Ut z3N!}Kp(@H-P4DCv-ik~&7xq?Dp5<)ydQaGtXD339UhhmCO-!QWQ^U2lQ^q<)ul|$Z z3A-Emk4mYiOxX*uLq{#`5By`&q;3s2@lU#&x^6c^cmOIm7aKKlEAtt9*6pgcH(X_- z;fbZren<~fG23|;*uLvN71I|;nWASmMFd|3pOi%mRs1_+uA#8f{#LE|qYYrG^b?uy}2>9yX+T@_!E7|64L&`#@o! z>83cc54HDj%q3_iDE~B z@LBtqSr^W?ueW^&ULY*%-#m*T$vtkD>T;j)V{=|{l1L%X*)qH-XxZKMKD|xDDpP>& zyb0b?IHw!L8$61tx5LdDRZyVB!feXvU)Kl0pfce(qf+cy+O)7J*m^Sz&M^)zEQT#e zl>v#k@Fuc?UA%v07$qDL?Y;?-$)j7EHEzx9BrvO)=6PQOM8q0Lbxp(4jKD!DPyRr?+i^PlO8ZXSe!C5< z%$lLh;Uh=F7NQ~7Ws_8;Rtn2;5^Je5_NmMYBVho6YmAf0yyLj>#|^Q${FRZI4#AAC zsT$@lP{Z26Zm6q5sI^729 zz82la{LRPDpl2jwxgF5t^0LYNB9q14iue+B#B}EOI zg*3g6+>~ms#!3#r|5}dBp1ybcb-273G&AQwhj*x9&YxdmXJnqlu;8sv`;~SRND}qz ziT6KvESV=n|BF|M*jnqW=*gKTMK;fpE3u{=ikIz!wn6q9pJr#)GW6)gDqi>=P=soc zjop|ov^q3Zg}E5Hk=`F7>S?(d);#ugI5qr~+H7k)3pB%CHRqZ8mBaU*GD7L0kH@Mz z;J~I0URt0*rF;I`q~9BlCeBui64yt+u|7MT(fk#sB>i^R9+S)$5(mf*+8>=iOGcB_ ze5o^#tsK}=Cieh6R#Q|s!&FCYT65XK&Y*DSg_QVQ~o&2Jdb=Yk2aBJ_MIW_Z|b zWK}ULsW40AKY-^PAnEdQ&KX#}TX(Hv?Gh-q+chS9(TW^F8S@#&xG{XSSI=PF$_2Xx z{v;W(nW~_kPa#Qn1uW7$7yGNOM#cy3FF1}dYaDAYn(=LRubvlO(4cwam?>(g;iY(9 zB>^*(g4!+>5I^kZh1aDjC)P3r-gqer%vK0*ES{0PoBlBK$38nvgAhi? zpu>N{^=N8J`fKSFWtSSjsR;7mZ$B^Sjef(qUo9MCYL23d{TT;&5Du?|d$3KOr|GIcg&#VN}H8+QCvcTyOQOW8}ZXFNKmW$DWBLF%sAN(y|?SbXX-E)W#)Q zxb*!{DZJQM+c#d?`5io%=V`?p4y()Krpg~)eJOi4Ux!6LF^@}ok z^wT+{Qr>#=6{nKPlE1QDE2$lC|N7oeKC_p~^rE99lDhr}7aAI^5M(UIxZm+d1VfW5 zS)7@vUJS^RC{YP(eY5#S3T+Bzh|PE>e%GT-kK?Qo=moe-O9JP{K$#=$rV8~D4HxX& zO4nexxEGEf4evzD`6Z#@r)fs(-ps|-W&mXQjO1taJf90ekoXnh+f0PuaJ`;oIG@OX zdby$ldjp}P7Lt!gjzZLy*VMGbh;x(x`yIR-o6c!2&zQF?6R!z?HE{IYns^|dY^}u7 zGsZNne__rvQaj2hL#y)2qIRkqT253_BZnP_s++{67p5c6*@!pN^00FygIF!I7p*}C zrHT|l_A|@XM>=+>5f!75F;gXtKp8>)cV6Bp+*n60{++$vqYd>39a8dyec>%J%BAFd8g#7BV539<-Zn z3xu+KXG|Z2Q`UH8YhCn!Y3MVwfPV2CjRZz%@rKp!peROeBUsf_m3woId^ZpN1CGVdS6 zC5Lwz+x~Ke`sTN~>#~`p6&?4(mkvrCkGVGy(qqdS$+DwCMT)tGMkSKT9|du4hQF$U zrA3CFd-+apvwj)JW~GMiwPoPVlQ4hvm&|$zGRUJ0E_%VwiRn7ZsVea|yL8TE|00gNO`WKV`6_gX-NFRwn&~`m7$7K|N%DKI87JOPDzX?ZBQKg67 zrK-O*FW9N33diB5R3W;&!hpVAub(X(bnSfgqnd7U3EUn%kO$ z<HI6x8gTV^){&For&I;D=AzQqDKut!}lu za=GpCQ(kbTa>AK=7no_X>Ia_}98O)(%7Izr4KJ3YUO(K(=)~?h3MrhjD zvV1a~)lRH1ve~#;3#3m{&hXX;CC*K`9=N8?{%4qR*Ub(zv=m==a4LAYcy8qi%qGq* z*44z8w1H7Y4QJ}St>+ArwC{ooyOy=iu0OlUG}1l1!EzE=-X4v0SLFO$$Z<7n!x(iM z#4lD(9o+o&efy~Vd{JSl>6cAkV(-N%LEZrw%}$17jTqv5I9*bsrVUnyv~yPr%6R(F z?`6Tev$**Rwoa<-{i>6ByCLU1uxWjT$ZJ5OztivBiVOxQ} zB|c8*eSr~@jI;^}@@IZ)*?m29w^wK)KYT@xowmcm%FBxnk&UUc>{5?+SjMFv4t99R z@zH$|iTD1@NuCdbGuQV8d)1S^*q&0WRhQc?*_l#DSnZ< zFoe&&ddH?%Hu{8GZsRr(*GrqwC2jGW^`FMY51&zT#A<9r6HwoyyM3gouNlVFrCMQT zS+w9EPp|A*|0i*duH`8mn@dSf*R4-NB%jj_K%Wt+VA}9i6V2i%0_OWOc7K1rlZt8$ zJrjplG}dLBUo$CnQzQS-6Zfj-8;0HQ=*H@rpawojG3!Quk|P4Fy^Tx}`rD}uJu@o* zUNV&z;uD>tfGrYnfQYT$JR*&oSO?;lQ9Q^(L?p&X2>DlFSfMy0>9|q4^Ie(NhIe1% zbN4ax%*FCZ?3yRp7%sgI2k4hiEH}Wnl#(}+t7hkrv&WFc+#E=r8O8X=K~RT1YZ*n9 zU@KWQ!|4nXNLFCD@h!iUQBY=iymG9?`B*K^Q8yFO)iSy4zyAaAyqR^mc<^m<5FD4f zKJ}MJS=cY<=j|4aM%xn*isRBlIn+YsYZ4x9GS0v=n4`;RN<0f=3fWcJ56{oq4fOQ< zA+{)HZ(_Amj6H`k0t~5_C?~}6RlBbRcWJ=$hl-ybo?X*>K z(V|WryaJr0+tsY%5}+t{RBPF_r9>vEtyubV9at{N(VTTkw>^gf7vpXlwW>pj9-7*r zt|&j_^7f`ApQST~64#{CUqq3UPG4N)QTq9xrt=R;bhG(Fs>CwW`&hN&aI7v*Ih%vO zhd|#-JqRi$F4r_;T8Ar)EXv-JMdvgeJwmiun@sl*n zqFU4QY6XG|YLU}LQVdiwSCmGkDT9NlEiRhSf+!4Oo|jono#K?@$Ms)$BmK-7U&YiJ zoQ98yH<#sTSzMiS&7l@=>B@?Wj#;RaQOF|e$Ie9LpD(EPaa_kbsYyL@i}>!n(%gO| z2+c2!*g9#(y=-X(wYhyTaDujF2o!D{8auyc^J4GTX}^63NClL<8JpnCRtH|**>m*Eu{#|xQ<4Ra@dacT95qQNVSks&96qHW>KdbeFphhVRPBTP|#m{SlO zzmfKH4-_bzO(yutcfH#awiHg>8bkWLUVwdW8Og@>w3#N|m@0z%kebXZ@z0g2q6p^mCM z(0Dv-=OEMLx24^C!AYj&o4gkXeXGpNDG8D|17cA3HW8 zjvdQmreIg_j97BIzkhe|+FOk3u*7`P-*4_HrxK`H^E9!8Ze3)P0Ftj#$F_M7f#{!A7HEek!a~!6Nlxr z!>E73#HGF9HE%bnofBiq!>eewH?OQl+O{WA+(Xn z*2InE16j!j1V-xTbDg3axw+HQO2RmMAf2xnA#hoC`5t^`f5e73Ys`;e@>XcFyZwa4 zspP=|2>Bm?b|U?qv1@srr1Ezq-$qc2W0ycnLRmAo)UfP8*NbtrNJ(rJwCKGm(JeVt zp|L&fJR}XHN%hAi8sbp=VZ-tls?reQm5`1dzS+%jERFp?N8SG)|NPIh$={fAY%Elk z7Q!!$Rjl%|<%>qLxmnepSwMZPp|3ya+8Dk$`Cv1?r1b^*SR^|`GD8-a=3%<)9TU4@ z2r@SXIwqSxh6{J`sH-!4<6=+wJkY|TporyN!;3)7(efO;46G&h`@qj^Owr?;0sJ|K z%~J>8Pd-)|b5t$~_WDvII-fD`k_*FyUZ-tV2{U+Ld)bCmln4G7-#?yXzKMDR@p`R= zIJCrLNCtGG*Qu$~R&Kl(&AdV;-_-l~#Lax^?=%Z`Zl^%~D`7^P>qQBPIW~pt3KASt zXDZZj#ixH7$6u4>EC3ODh@upzh4+Z^t-eQeWB)vkX;GR zH+*K74y2;QI&>OPCO*Iy=x4|yRh=yIr6sZDD_<+!=T9BrUjXxUiJ2l|6} zbEqh|5qBREiS`=tXH~`u`i6NH?x}JK4E8-h-b~sIoNkJ&YHg?xT8q`3)PDe=x<(A} zB-z=n+__D1UX0Z3J3N!4Uv&?@BAqh!jFyV6Z>y*jil1dScL1;kQ_q>Tmy4>H*%i*1 z)c$0$j=gn_h7bdanig>cH^U7-32W;FgS2IlMf|29xUfH)roFgq#HfYguwWrKoW}NA zr&PV?=yHy*gN{m_UQJg{mmUYiOT@b!Vj0}->`02|;==rBN51@=YLwcvz>CL|TkJ+? z@#IhSsC$fo{INRw{U)v_EChAuZkBwN4R(gih^NuvXR*5zY+ z>XqnjH-1)4dHV5UK~Cj%qvTqqK9qPQZ}(X!b2B~)`iMTb=Ba0kvv%>H%dXLS-@tiG z-u|b9aT_l~wR(cMht51y@){Zka|R>>-lk2b`?~G?7S-_fa^rU^!zirPXRz8je^6#1 zR&buIYE6J}t1OW?3p+LjaBu&16rR=zM)Z5mZgTkJ?%UX-&EnjqtFaEiNwQ(dr3{tM z!iH8RGY^C1*l7{S6$aOXuSM*jtxo<{LobTg?Cs6P=RNqew~OlDaE+=x>wEO&ZH5!mmqwXyO#@(UIBmb>r+w7~R##cYA3!961}CiC^F-sJE-Ir6ks34| z#o8||4XcqZcq`+g*R?EV!nDyOwq@B1ull(F+G6l(8YhqdrF)x_y~TeoG;4|J&xyB; zZb^7yCVFF@@uaQ{SMxh7_vUJ-r*Ba%!SMLshQ42~_+T3^M}KI<$(Bz&8<&GG#iWuR z6Pkh8ls?V0r116xHxe?XaUo6%7*#EpKL)#H{B&5in9zBFTK15gk`ni2c)pYn(UJH36St-Ufuu(`B|e}&7_b47)^sV zh)+~yES*g~E7fw1@#d87?*`if`CZV@fx3#$9KFQjZO*K{HXN(l_{sTB%pI39Wn-Hl8w`u9wy;u+YGkQyxau#CyY4>Jm2* z;_Id=R@SA|OQvXBGzmnV$5p(LBw83u(MKi6)zkibi$$WpDA*RF{sY80JX+S49!bly=N$@a{2gXwYOOptPt2nX)MdV<0{I7F zQr?!$2>5(j%J_Wy-XBl2YHPQqt?z))_wd?ACEMh~9_l5oLBD6?@JCoERXH&q4EfF% zJma}j(bXV%_SMOyp7k`$u=!aTyO5^%K3ZOnn;TARxX!`cX*jqKjgIE~w3^jLrQjtM zaltU?y;U|U>afuqPc+mm(~*)kba8^t*(o^xN=jwIFTY%s_7`ef}y<@6Sh=sYa~6&dYrR37(%#Gm`}Uc76Fo zj^?*Fomuu>@=|~diUpKIX3nnPlpQ)@E}H^unrmR&b%yav8fp1?JB@0$GsMYJFZv<0Am&U8EtfTm5MzQIV*@$x#+2hF|&Q0 z7g)-g`yOH6yjM-GW=mzM7*E^{$^^pzLkgK{>&drwIMpL&o|uMdXHPdZ=;N1D(_`)( z>+wu>k%-`pauYB(4LcJiT5B(tKUN_-+PvG2nK2|tDE?a}O7iW4iJ?(qxpMNboiGrS zkpCQDRNXHe{YSj-R&U`mqKt-DSK~GPo6ecq*HY0lYq1KHi^@pY+8rn`c zDSlSup&!ap&ee@?<+=y;*W!bxT&l6pw7i+gQP#P)E1ctl{;y6WSgBU!& zSc4SPRzMz6Kp_HhIopk{W|7u|YSmIhRJ9k^cNF_ru(QX@;%U|JTo5K){!F?PTBc)4 zJrYbBcmQpqMoNyRmrlr0&@uAo-6LPr1+pIF+}nWl)pk1QSZD=~oN)kFr$7LH6p)@l z1?TAUPgl-{)%si19huxwMKVutD$0^fgPYKdUK+DPPk8<>;PVn$ksS%kU=|ctHRN`1 zLUO)R6i}`56zEl4M(`26nOaDskeYt>IC=2k3R4e?Wq_^Y$^lLB5jZf4YQj)0i&n=M z!n%2YZLs&s-crEbex7#SJ5HCjk`thI!-2CKIg#shszx@J!pT%U@%c#E zbyy|jr(cL*RpV_@C*Y>2t{4-e2KlHRe(m)KXoFNg^L}$Lnm8!KCrR}vf!!7%kPS`n zYaC)?H2{SiV8%aN7zIkvMAnr@fi;qeYIW)LG^(164&lUvJ*EAtvb-$ZkDo>)Iz|3^ zI%zpTmrL-g%xHBIIDw_X5|yd)px7yxIrxkte_rYhx&&RhpK_VEpS1WadL@6aRLmAt z16lelbLtl>ThAMkEN!99&8*{n{B;DK4ylIuj=pGTH9jIxumBf$t%%G+v0?v(OoFy*WX2Y(D!*o!?`#0si8GkHqpoFs0Sa7P;ULE^QH0 zzY{6BB=5E(TWEgdlN=4EjY~H!z(!&DzQIOVy3sQb8+4NjPx~4qhxZe4HaG`ibfM_5 z*{sZ3;Ps9p=bU}C00@!%m$3Z4!;wbmWj}uKn2d<4vk7_e?Cknn=k>W^T}?}Iu%!Mg zfEJROt5}@d5RTo$rmlco9(;lkn0K8nnnR;fOrmGkvtl2sp1vfA8#z@w4!0 za4anZlFrlUEk_UXK1KS|i_^1JH(iPw`1DVBk`uZLx{tn~FitU?d(Hn_>!j+=MdZ>b zrk##o>!OLhgYsePnKsQ}x1+L&J>c3zSMTjz`$3G`bM+YFIr!+iHjp~_=};sMH&6-1 z%Z_)S1bQJd2Dxpcd&NHdp-Qx9@vCbqDOg4-gzG+7)EMnflm_d4qySG%ALL~XEgWd7 za2Yk_b~9L^!D=>E?eOsaE%}F?&v_P-w0{bHNl|pS&p7=bfPo8-ErI>9@6{dK zgx)i1VRE@4d_Oj>iZsLEuBG+_w>8YVp0zHDukz9~t)Q~o;6K3EonF!>TT>-fnGjHEk&<7YuKeht= z*b7!$Cv*klg_FMwe7d)jaxrJR)iUWgKzkunh;;Ck9Ca6KxB;cEhmzD0Vmsy4;QIQ8 zeq(2!gWi25vwt1A(Vd_sM|C%+z0pV~QJ|~2FbnT8Qv4~MKt){(`zjno+s4r~Jt6k_ zq^nF>J@b!>!G&O32IaoF)v6jxyUnzIXRhyPv%8blyq-p*$4G$}Vl(^GNCvIun?lJ2 z+I=;RU8V2_TS|i|6_ibB3XS@gk> z1T=f8(@tXM?KnLQ%U0xtotsH}Jc8;N99Ev{Yp75+;2y{~p1VZ0MBzNFqGdXTeUy7? zr!|BmtI3c&ZqM)V!?tBLZgoOsH26E1v>?)rA{RbG$*5d)sHMo)h;6;m4Mz|jb}cjw zPF}Svu$Lf7VW@0-i1)Sm_2)7BbLwPSD=Ol@Q2J&&z2h89E&;VnCK59~U3K@k0q`So zuh7ic`pHAA0I(NIFm+L>fBpM1LZ@jC7_-k5YK-j9aGsT>WCATEtrhm>m?-FPh}As( zx3*RFT~h7(!6oEGUvNR?229sPXCY6yu2H3L8(i-gcifQ22M*E+L~^*5ifgK5eZ2F0VO4c0S5u;5^07WQc94HK?WEaL^`B~lCBwG=p2Stq@=q+Qo5z% z_s;*ho`dJQ-h;gl_SrgFYklv1-=7;mJEE=k1ifkeiQZ!QLe)$uxe*thDA)jLxlEv1 zi{#_sY89Gy^Oq%fPdg;xm;iA(gA|=C?3+nC_%5Vn(`^YHO-htH0xX^AC^tnKA^@ik z&K2*-pZuFLl1GAYt{Lyz2m+1SwkAG)RW`2@FoBDD2RhU~1Hw_tnOYow-@&s{GO?Srekj;{M<^6|Zk^EWzX)q&KD^Yati@rEt`_{_ z*H~1=))f~$MWW0pQ6Sf*KFAGgGr0{fRz&)kWBV z1fD?llw43d$rf4jB-G?e6)HBBzH0zC`!Zt0mPjD(N&hm=w@ z;)Q;c=`89G(6?!abM#j%vN@UW!9+HYSQbltBO{3Ba95$kh2tqn52L&==evL9z;JbN z=`{}CUa{7&Q{{#Jk7Ti~21d2`{%MO@hq|8w?oQ@E9{LZDAmg*ku@^mx#kJ5OzQw%p z@v_=Z6z1O8`La|y^V|81Qd3BY=Sibo6P+NUocmDEpXj^7t6Gp=;#M%tDgXV!F1xGOtAn%;Wz!%^;p@89 z4Bc9z@b$M$3H?YVN4e;XH`FMF@)U1Pd~WY1dURN~n}6ytNnCSL1ce;-_Z#l`wh9ZX zHtSA)mH0}PWM6oZ^=JIA_dU=B1A{(3wS9Sa9F-Yl|K*+gd>9{>{BuHAD8C%@wD~*l zAX&(PRih#nJKw#aOD=h&%cINu$c00A*sApB3GEnRw_iInB-ZoyW*5|8&CQ~F5#tjs7i)E4y)B>mSk2tRl z5V8f}LkXZ9vExbcTl%(FR;p&2{A5{S+QG4^Kz%>NbVi8TPokgF@Lo$ILQ zbgj}d2hVjq^*fsVM87DPkCjo`4&^T;|C0}q!8hymH$rdzp|5_S;1k>bd2vXvoC(V= z61rKB2S!^|qT^NfYJmO1%pP;D#YXnWfVG@F2S`W z+bYWG&O7Z5JG0u@q0-Ksz&f)IG`vhTf4a1eee$yjD@yZ=b!8KbAlDPd3~4=umry$n zbe6F#qY&_c8f>JoQUM!`V~ozE2%)Na{3QECzvqDC^K~{BVPbYvfi|0XcDPRlv&o3EQ*p#KIOR$5P#a+DpK2`1KFwG99LK5@#k?DWYd#(%OiqPpi}ih z?j&I7dB+mJnZZAmctaQZwqG`KR92&+;>~h=bkl_@aP8)RvkQu+hTKCc+Rj?v(o%!G z-;qU774^h$qRn=osPX>*#7MTw|#niw09R9YtGRmpaBZ;jEnTVi( z4}@^W`+W;5yg({`<*V=~eJp#$W7Fd^Z>8P}&pfA($xa(d!FaNV_3t`1TRn2P%py0F z+86%Ym|NWl>RcwVC7VGvrgZqtpRJ=Y=cTWE5JCf+c@13|eXdPf-@mQ)FcU#*pMd=w zr4|kmG|!*^;(2663^6(bXp6DLrxn$Q&R5JX0h2K%%@+li6-KaBgM3zxv=DwrGRCw| z(+>SuVT=4xn9!bef?w5#sJV~M{^$vn#+&du>QLSga3i71T3+o05XnuDZ&&`*OG??D zX3C2z8t2EfS^>Eg(Q)(E=its~GIOD^ep>flSEnYAL=8)-@2E=(muA6}H;?)wwL488 z%b4B1G*d`4i9Z3Xp~s8gtA70Pgo_S8(CWoh0i;83fvZJ_DYH>@i1-*p|HPE|_3REx zC*}(k*2wY~h|*S35kE=C>JNIe*g**&85ysfCNSt4Ia!qJ!?Cqy>X~Z5@E=Y~oJ@0M z^;;{y{FGjpX+~-v*2a2^{Fbw_H5qsrc(bR1`P6MhqJ~rmdg5H}b&hSFR>{Q>Q2#bL z5DOxSjH{;_?c3MZ&;5?=QUS_^*$b_@Nkg`aIcWbPIhA?1s>Kf$?uBIE?t0XgznPwg zb(PRiNQR;qaqw1>a-c)Lqi}y22XJD<;(d6sIQsaXG zNx0mGVk(?Jm!b1l*r@Y!!uo?u&bDduA9^aCDFl5;^cpgx7 z&m&@4GZh=Fr3N9YF1Z~c&gkq^PbblHq`6yE0=uo(X4ynp2N5}?i|cxnbU*cdJ1gPA zXES+I`8qr$3(+NZsO0f)X{n~{fbXw)3&hC5KHbUC?&miHLVV=*fWgttoHcA`=CyV5;uU+3g*gY%-1mWQLkOe0GAicn%04@(xa1bwxKS}z0 zTiH9NsCu0{`acvC*$-(0$wrwn*7m{s$f!0ZmGQl)T@Qx~gJD_CwQ0KKc%Lwl%5l>u zyKzqCpDJooN=xu#F&QQx=dd2 za*i^yjHiAfBGOE{KDnHm+mmI(`sRAiP?t3QE8e!}hvcPM);aXd=0nQ)Bwr*q(KAoF=W|f>hr=uzr5S`B+e&blN0aMez;)aaT!Mt(Y@pzb7LC#G_|%{ zyl7SFgmxoJU;J@y*y1V?Pam_n_k%<&uzwdnYOJX2V8kDs>k+FlfpBxGo%yFQT z39{3%_G{%t6HeJmv|`nI2A{J0U6WG4>CTx&n_)30dG)%+PvijLtRDIOSbvoU-sYUGg2NuniOl18h_ z3IKyaZvMAafiHnN0_v5EZz?EOftUdULxDTi`Y@_Ta(a2H2iwxZNm`V#2NQ~AaNSoc z_=@WWwxgxTo64WzRxLx5oZcj|#&Su&-qE*QOpQ(K3he28KnXHKv^Y7ZKSI>SCKkci z5>?Vbf?c zkb2D_l3dIQ%(M35Il>l5S-3kSo1S(kQUIARWwH$gX%QtCQeV15x~}co+s)$AH~0yu z^wyEe)g0_NmuH9XQVU6I2O}%m`}MoMRr+a(+%ejZGd$*4CXJ>a5`uU{wU4AW3!s}DFCNy+C% zDv=pQD~7t1{FY*@f@lTDkec`q!Ot`_obDTs(~h+)hLsE2U>`+AdTwp!^;ezyUON3^ zbP~CHVLHAq(!-Rqwn#(*6Jrb}(h*-HFGuNG4?yjGM%U(9Q0VczzXUk9tu`M`$>+qU z;yFlQx{3mkQa0oxHq3g+KFHt6wehr5^LOoM2g%1XaoB{6R4r zhrZHv#xY2KybYHcmR9ofZ+U3m)VCaFG=^bz4H*H-I61P=7t)hTvOTICPK^8{XU(z0 ze4-L46q(=;A}>xOoy`p#W;L#{mz$*v4Y#)UgSRv{YtQMwGWoc?!RLe#CLmBGAZo(s zUW&?fwCv<#C(qh|9;-z|+?*I?`QN7YZWQ&>;*bPz^?WZ!^%L<89F~jWDwY=q{FB~8 zjZ8%psTmH*$s);|Vst7mQ6 z&ot$^w<{!JuXq0OhUdey>D)U}V*61$a(eZRtg_F=L7&y( z!QeR}{BHmpmSC;KeyyCUsA=%YM-GuaM`arHnW{0h$VqRa(u4O9d{ z`&Ko%;YxahzpkL)d>@q-6ijCiP7SZP(1_&CkA;S;H1F$ke~CKI;W^kVg-5#28gK{+ zWKo7}``vh+PbmZq@LN3@D{P?4tEO1=T(IGm{ilU@!PIVNS{Apk)#BfJcQ>*NmT6{# zo3KiK-FNk4?j5*~>rlbN^-uZsQhrzRAtN^v5mo9aMy8-!271OOC$FBbhOhcYVw=d` zs-sKUvZVWW-DOIR24a!MkyA;SV8xj)5t`vYQtcRuDN13+*8$QpWxe){h{95^3 z;zv9jg<|Z4H9rqFOWfw=l9f5Aa5!0I%Lr$p^%LIS3H$O@2-?VnUZ<(0^HIZ*Z+b&_ zGrjSHiRB18w-4P?E|>#-chsRXi2igyXCrf0M7GW&O#sWLOXyQF5~*SDyY@F4ic%bm zmm@D_dK=FsQ!q4y+!qaU9hw>zemR|BXXZB#$)l=K=I(U%$T;65!7(5QGV%z_hK zK*TGhd-AO7;e>tU5+*s^=s-goUC8>zJ8~l|A5yl;&Mu_~z1fb=(7qIQT~Kf;po7O* z5UE!YTida^Fa}&&y0Fca+oeyVaREf;nNLe<2=0Bv1)rti*NK3rCM~E`JxSu8 z6N!aR`#25Lo7FFVrc&ojEGJ3%u}khmG+l z&G&?GB`h0BDY6aW8Si&d?8lv08C%(YaN83jP({<|ApGJ;W;`{yyn*L&w0eerXlPZE zCR*TI$XPk-bYGvbN*^7b6<42~IcSN?PuI)D&V?SL^woQ6|EAunI{kRpr3=zc6?&za z4+Io{;zn}XLy3uj#jAZAB4^us7m)`h1)PG*yHx4KC2LfJ9}I`Giegp>w37#N-}`@Z z`su*w1nK$Bk=(db0IaN^(D?rc5QQdm{!b|JPP>oA(Hz4~JrJI#TWFBig#wq3T2Jii zT@SHdCFKn`IRB2}OnXEwh)%6fP(E_}H1n*3ieF&yD;BY&1A0puVRfcY(8U}xl(`VH z-%|STeOrc>+D4u5UPayvM@=xO*5 zC!hnr8=sUHJ__9~n(B5q+eegB1S&Yqa+R8ATnv;RB(-@edqTDwZZ%KB&+v;WQU(eq z2VB^)UBMjOZV_0RL0A_6&l*2(lZV~h+MD$(W(hcS!<1U8BhUu-%VD;gMr>;i} zddlaVCtEuT0O9J+N#+ejP$N~L1(iG6I@3K5YwnuL7qO9Cs6YCKVwlClnu~(@mXh_y zed}B!eNK6IDQsqZq_igK`W2eCX)2Ltk#P%2NU8-H-eHPx{$P_3=KC( z3!z9F_(=k9s4%-lb@N8McR9Ztf2zkI-`-;Pw(y~>`~=hX*6@RaS3sEvic>Ua&^%7C zB>8@0&T)Z9ZPY?ZH_}&MoI^N*HkWKvJWK3WDIiNSaTIomE1Qwsw}XvHsx?Tb{gH$w zS5CIu$M7c6rURz6UOe~k-bCAU8_*UTo1hr=yw@d33R5e2wti(43D~yevEK)y6RgBi zqjk9lhN`bN=dt0MN zzfnp9uDVD8R&@{WKcb%jdNjE$ zBPz;!sLntV9G5%qXwJO#*zN2vt`M0*zUzf*@$9QEnlZ}wcTLK_$T3{fDO9{Uf=ptX zhb?Iozb4i@jj$6Mz+OlC(`eKz1(IVwNTlwDRs3k-)T&1`N1Hju%HRinKh{-`j{3gQ zvm8)g9@ek69k>1l5k{!Jc2$^8PZ&t2vevZc802*8-6sBB{tH|4?TuS_`GJ#l+ zS6jJ%(|#>r46s~^KVO#Vuo%LJsUL}D6C5MwxJf30+;$tJX_WttYv`3P_Xe2SJq^AY zB?&4E7qN?QGhPU@k*|0kVZ1Pqp{6${O4FpL$5U5_d>=XKGpK6QGuaJ(Tfy3s#{5a2 zwc7ia57F9aca?@Dw*DRYv%LttXHc4?ff`N}kt_>wHe@s|XrV2?BQ4Ec=OjyAmiww= zbk#|HO5;DMmF{6+ImIfeRq|HQJ<(7BK6|q3EVRO}M#UnNtbQyD%Jk$haK-)7!V8ZN zTibWKiQ{}r&+y{wv{QP1WBTmfbJNvwB8)jr1Q>LwzLPOCFYmhe<2j+jR#7RL-@m`j zLiAHE0}Uk%*_MmPp~dK&ty0ZcswxG@=XX5WjfM=h6EYzNj`HKl(LUeTCZ^SHMd z&jS`~jFchTg@)dtc2#U~J91Ockm< z!vQ&5n}UVU4kh$JvG@#zBSWOSFJkK3Uhk5yom zQ8CtXRIrHcI+G!2eCs`=mmj#%;BWQQ9~et1AE`{rbbJ{^289Jxzj{EQ8qb;EdSNnc zbOU2C2Kc{i2cvh>18C;;`k=JC&wo*F0ShMoH+1t+DZ5JU8bjJu!Pf+R02Q)ksuZ9s zMS`B2=~cL&&z@!Tpl|FnVot6_v&Gr*9~Wz70IlK0^s<^uLVubML~(Rx;bL$)ljZgR z0A8?>y)&yTBU(PP4Ltska}GT)P|w)RQKpWB)CY7?wiWIAqGbX-E4l7avJ}_lRes!N^jEjK)kFl{18ZR2$VGblV`M7 z*q;PSp+{*Zp9|IzISJi#b8b%TRx`+GDCbh=JJ`uMXuGpmNi^*}FU#Jkr49vE)cACP zz^R6?e6ZsfHTnBbb#y8o!tpF_N)_XK^;qq%R1;iv-_Zgj`Uc?k5pJg5jwM%)TxF>@ z@xUe#4D-$>IjJ%@3Gr3I?@zH!3RXirz1L0!@==ykmQ}@7HuB7mAoUFg?ah@;y2?>w zYD;S`Jd%|*aQJp;;HVO*!d(yfP$UsFju%<0t6jVadV&v-J)sI#c}dA( z*O55oROlyfpG1M^PtwfV^TyYza8{)wk`9S_B;SEW$FvHE(Fsb)JpK-v^e&5r!{0MS za6bMKU-EAZaH2#@QIBBcG-oK4ihFNpefjfjq_Q@wqbpb{Su>e`E~u4h$qC2TpVoUF zc4X5$pRl1Qvlp9;W}kePn(Tg(&pHx$6WF}{ZmObr9aqgu`cuy7G?GA0sItc3Eq$0E;@|8cBT%z;{P{l|M1n92Eslo{9Z3}Xr^2H=Zg;?%!Q<%1 zzj+P2)}H-`<7n9Tc$aX%j3A*Bv?gi2J}{H|wj|^iDZ=W7T)5;7_ucu7C0^FWe>h*| zH_OBKrKueo52nwu(P&2@LV)&PwlV`n4JwZ2&`ODgxRUqp8Qb3;4rpWZ6=UTvpkcyV zI9=b;y-)fgq~iozX6YS$<_^Q zGpt}csrs59%SGaC4o*!v&icZ*3;FgD;=qy@RJlSh4+2$Z0mKgll`T*2!VAdUWZtkP zMkFu9eB@xw{}xtWj+1O%Hi8*e=_w(7#ig=!sU+~_dD?GNm%j})J=V#IevUGr$K;Cz z6WY{~xbhJ-Zt`V*@N4U2blp`8^M5$HJ0?2hyg;rkV_G6$C5?ElD0TjweS1Q}6T2L#_i)1GPnmU@#cuCj2@@~* zCUJ&m@PROo1rR@yZ@|W;k^QdUOLVk})D{gIEV<>9p%oBK;Cp3e-;8O68AnElh0ta| z{~vAFzg$t@!)PS`CQf5PxS0!9{eNtruMPQuuUS5M8ELxK$t!oB?(sDAjq*WjZ6D=pGvpuu-0YQdc<<6 zA>vBUfZ20$g2gdS&Fk$;_bQ^T&1;TSVY57LdH2N6qR}hEu*uZfg2~4*!jFE+HXqA< zz~{NTCTG)Cm+2>x57Q_M9?v5QVQN*Rv4WEeKJAOOS@PhEbY?KdQciJqk#h~0DwAmY zHti^jezz<#{jc~yB)MxpBR=}M zh(s)(bJ_emTYXa*_AYy?w>tJrm7kU#HL=Zq{;lg#sz%!PiM`ZrnNF7+Ge$JvLdv_^ z>z}lR()_(6*taOUSOi)!4v2@g@yRDXcT>_eSXX(%3n?yo8&=Ti*@Bv4#KCpAL;_G0_#O?R@FbcJuCoGSX zdQ)8={Up4yd-qE{1f_4*Xh0Pz^z|66^8N=1{D*=nd|u182b)upnmT)szj69kBKghp zVB-tRJM3QvGJh1O*svsA@@2yB|1sWhaDQ3Lfm(0ZPY*U9=67VaRS7XKu5qy-|2yM@ z6etJf&fjr=R+WcG3PH!AbTF8JPEvsEOd$^9Z`x*`Ed1 zKkC6shq?q{s(kYBQmZnuLz}_SnR!-Imbv5m%@?2-bwmOKh=C3)s|AG%EJ(L!+{N|j zh`;#Bgh}cnzkZ>WTB%&DncK)-(l%U=o^XLQiE<9PPg#Od^;f^O*ESlZ1o*)HQ0AOj zaoD;4lcN+TnscTFAlF^7<>t;^*;?%Bv+J9bkN4S2q=zp}{I={4hEOWWLrgA8NifqY zq0=4D%?2WSh3nd7BfzcvFLG9RAloUN>S<0JYlTesjceh*9T$&Ay?H09!+8?7)Gk&R zQ}m`_A$_s54tPpwEoEI`=sEjoOq`?uuNp#(>Io4JxWn#E-Ij|l!JK12tgJ(H+pVj& zuvt&rqUu{0;t|qUxpX#&@Bf}e^|Kd7Q*XVb+`vzG2B&7_exX@_jFtzKq^`+{%(|g- zIX}=(!x>;DGp1i^uNy_nXv($wSgtqBP?3(}I8PF0(| zZ^eqKy%~8MkE<~MjGw(;4<$Id3rC>v*kr)vrz#`&=CdO^Rq_vQUu^9xMQv%!ueT5D z+oBio0XxG+FhY(Qk^bh(uHA(wdgH7V7a62AS0{8jNXk3UYr0gp%IfJyU9ZZry4TpN zn2)6Eyhrr8XCdGK8>A$;5%k4O1Iz;6ML{9_AzdhQa&c9n zL%o7=RUMq1E#_v#IsFI1D9E-JQc8Odgbm&NR_j}X6WaLSoonw0bj3jW!w8}KBBByw z5Wecg4F6tW+s}NVD>?Of{0TgS3Y0|*q5Qpb{w1-$I&Og?S&GeDK=nFVC{j_u4ktnU zWkknwX-QnILC0*B#xmMF!EVB zRDcXn|LQHUEIoBfJqIgshdrZP!wav@N?y5Man#PW?#^oBCAxHYv0{_{P;-g6m z7dShc486}bECTkT;7i|%QU=93i49u4#94f({2qMSPz`FbB234RRJj14pfxQPWh%eN zUn?6ryv;?Zi4I}JL)=1k(22QuJ0Bli#A~luS-fqQx z)X=-4;x?p)^?yt4PyYHl#Tv+wbDu2mS0*rn?P48k?@Rc9kobvcV+xcU3P9b7n`>14+*}m1&cVOp>mxRXRUZb^_+f8i zbNMJPx*r$X7YTl1B6jmMwZa7=59@`pASGt1`xX@b!y(BmvO3;HIw^i-*SEg4YSvf7a_Gt@cCi3;{MSh8 z(pL9XpoVn#-(SfptXGHCQo{Jb1a1Uqz;;y`Sy@ zZX=ZUm~^Y=Xh9+uST?O3zWB~BFio0i=iKw9iD2QIOb}}^y*2=^KG%FsY+BcR1!v@Y zoUha0!v9$mYhjO+a>u;%GkdE=mjB8wNsy1bC>ku)U9x=@ctm5Y;NVlFZzZkfU+Y91 zzHWXx?l%8XK1)RtXYi%!z23pao_f9lW&?Zx+;G4Qy+;Amii}&ng(_06j!$um;nN>} z{<^uwozJ7~#$K}szTQi8)8P^|^6FKqY!Oi#Ur0b=uHk2UoWEVvT~h#;xWUn>K7q~c z+-+1aCrc9=roQ@e!%HU@V82a=c{7hEzEZkJWv*6=nug7J8}V}KKmcXFJeV|1R@G+k z^atKkfo{_`T3z*;PUZ6nLZWPcm-AfOa`8`6>nhBfs@ywbjo%Z@-a@8s@c85zm z>DFza=FJv4hY33BfhZTecg|A`%DswBW*}<7=l(BGVgRWhi#0dM-aom2P6LeKTFK--k zf4eFpfjW{Rhw-??Ir0*}F7)kXxO&;VdaVh{k`3y6;%@ATnRJ`6SrQBR52wqbtD03l z3@i~>X|U_OF2!kdA@1Gw^ht%n_cDH7<5J1_%+cC^hHu-B^Pi+ZIq7D3;b< zT}*pd|4H?>A>JCYInDk#r)nWVlkn(TNAoZMl}{wc058HdRRrx4`aZAWUvSZQrJt#7 z2DsoU%df@!>N<}8)gWnZ+8|&016Fv#+nvqy1C+_b{81_$nPW+6C6$D6YidHbe+`fb z`28wz_3ICUKeD4D>}e}TJr`kz)fqwP;2Iz~#1e(iOyT z^_7zdhxAhTW7%>6tBb~rNzsBxcdmxjvYDHi@t*?aLUCy=pv_bpGx7K@UM{@Q`kal8 zN3ka6{R?M2mkmrM|F+NAr2zs=F|YX3Xmu@Ex2&%4?Fm$MV^}TyNBO}?SbiGF^)vaz zO4d7Fv*?}~wbzD^Rw(FYC9p$DSljd80R>Q)Ar&--rt^w4F7e-Kz3OZ0S(PXB3;mZH zJ{1iT%1hD3Mv@-|w>rut9ZV9PIVur5VTunUrmh@N@)-c>Z}{MXL4B0sqe(tp0h{M4 z){UE`6PgQ4BaSO>WGOr(I=kxaLz*+9K!cH7Q0gG8nNI&HbVW0CuM&kLgh`M{639@c3o-I$aplpy+7>7EXcp-_LZbuZ`U(q zMFN#g3F%ScMMV{Z-vnR(S*WfiSi3+E?0$Rq6hZ^!l!|{lg!lT0$uD@1WYN5*KlqT~ zc>Lg6SfgptIHjAZ->s#z!!oldUN-J8I6BsmjL#aSvl9eIs#u1FvT~YgO3tTjj$;e8 z(?!kT7sDUX*>YO(%zKSh$(@KnzJ?+6Acx7Jw7h?-Uf5gFr4Va>m#3=#;gk~}u1Ysx36+CBfKM?+3)Yo_dc$e-SNXM5nX3#u}2B#F`Uo+zxaYK8$jCd*OD~U((W*j&mPIlM!S> zmi{XAjWls?v1#~uE3nUbs-vW+o`7i>t{#nfTz$28ZhRBikCCS< zjH~4ydM*5oieOi8dEV#FfTi&nVi<98Y7qm4AW&L`%z}{cvIc!l1?%9&1z)yF{vM? z!}EFA!G`#>m@_6bl1TYMsjWaRe3D1RbgXYeIc0OP37Ll_XG=e`0G@-1FLMFQ3mR<= zpCh45wq^R+>di|{j!)Zu<2#QXmMIWs_pxv`DbR4_m<^W)9#`GU{AInSM5@?Ydr#r^ zzBoDXP0uKrUI*z*N6YV+%C6vq_2I=YDYcnDpC{Ag@}$vn{E|T_0F7O(wf@bH5;@ zJ9)&a-01xHu7M7PY9cRHcl#N7qi0bm`jQMvixg+_R_SFM(^NTQ$+F%n8Pu+>F27%W zFZ~t3eeHFW4ST_C6AfS-3|ESv{f8m=gWu`MMxm!h;NQtb`xkvNesNQ>VdB|nl&qtS z&_ua9)YgzoEP|hRb9OaH;8Opgct89^{2nHtIKQ+AUu;}Cz{+C$qc34@47Rw>Xyg;% z<_YaM7LR}Om}FNc1B_H#bJD%o5Z#YrL}urC3%wox0d#k1BwhZXcge@UoA!*;+*emg zV$F5k4ve&OS$Tq$y#t2D_UF9L-TIK0J!j|GnzjXqhFW=B>vZ;*o+G#Fsz!uTv9z>@ zNc<`*nNadp2j!yMqE{@`Uj$v5ks2p%MiQ=}Ea}$Px9hp&B}278@~HbbgMN2V&Q{`! z@6b%@yo-2%0dIwQlJEC6Qlgi$rJl>WTZLWG_Xon1SQEc>m|kW<>jdA=LOiTiWZkX! zzV8@(I$&=$2O(4uG0PeBOd2R;v?k5CqzUdC#tI@<0a6CO|1n`a83vqn}62vTNyOQGvO)A*)8<&6B>>MAm z=*f&V6~fQAX7p$<%t0DlHhOzjSsnO6(`-mI`Bsc47i!pa{r~9yl6XDCu|R!7gRIXm zqh;G{TH^$HWBFD94Z9NNjD4}s+GxJ0H{Nf=&sBuxAA6p+z~t-KD{PM_dFt}ymbVA-?|Kjv1!Pa z>5wBGfT^W?aW;xTZi_`z=>{~=mkrn!htvUbXnc~k5k;Dhqf{|_Iv|o0lLqvSS}+Ql z4&;53sDDZCMue|3nUE(1GzVxcPy8}50a`efk1H84kXw_qRCUgu?uor41I>QarC}8M zG@tqv`kkzP!tb@oXOR(@a{J}$(w@J|)X@Zgi1z^b?+cYtrHhuAsi95kb>+>xnthl< zmOf+e@^li{5I$WJR%49Q%c9IT4pdX<1C&AYQ9q*p?IbU5p-FgV_zG0!b+}{N8MW#m z+aNL@zkx6NY0viwHJx-Fi;7`GVTh4m>U}qBj7yu@T&UhSra`T}*m1Hk_siZ6yz1x# z#ZwP}J2040N`bzAdYcIEGa}I;g9ETe9{+zG6Dbn=MIT#QOg_b(g7!>cP9qv>UmC#; zLtRNWCW=kA0GuVWjUH~m28ez@u61$Mn z(e~G(VMV2=Qt#Nq=WpCAVT-t)9VyA4Jqy{xOH4h*69+G7mDUd-()tn*Pf$Kz`h=aj zhuB@)`Mmr$K=RV_NtK;`_aFPNyCD+B{q0P|S>h5S@vXdjb_iW(x9_DXG~Stf2ZH{XdAY0pPbsmJpRG5$Qhvi>w_IfbEtF)6BdKD9|uSs5h^`kK$O zpixe6Z_pE68XsFNaRXA0O6Mgp32-^6Z!es5sZLWZYXEKUq}6i`1k2s*T(80sh*%$r4zG?M^_ zMEVL%)9O1I@Wb(PGM$@&zZOvgZ%}dk(^yV`4lhgIquF8^>-gfnz3p;_=MgXRgNx`S zds2f$c4jiJ;-fL1W#K0otujS#UpU2?{Ml|w2SvVn4$aM-X#c`q5=>Pvch#mm=!>mL zu8fx1XTH8kJnJ1WOI^Ntnzr?4>-26IT{g^}gqMfUz2W0~ogkB&)1JDlX(u!tuJx#(=-QAPfsIA9hJ0q&NaE&?Qg9NG+-&v2;w$E)Fex7YTD$y%l{tsuFAIt97vuBg1O_5N8c+*x8 zod+|xe<#pIX%FQ4Ycc75v^uJlnAo14E&5EpJ)Upa992H9jaEmie{XS6E$@-9Evbh| z%t2a$UZ-ySR?z3eZ(LgnWHVXp9Ls-+t{*q1RBevQ~Q`!BmwARQ+iF>W@cfHqpo)_pD z^uP;D3)rRUytAY0i`FUq-Qo1nLm$%guq4LdYib#fQY8@$?DK)(Bdvp%e4l6|RTa*jg3S z7W>JnEGBmCvmMjj;d)_vT;o^=DLWh~ox7wF?bZOrm?Qg(^en^%`W>ci6*DHB941j5 z8~CiMtPUUKf@4Wg^IDx>dK?a&0h*z#^++oKI7o@=!J^Tz2H0J(STH`-4*e%oxrziVH9 zfXWrBhu5QcPS|CBsw%{(sGdlcL-%3+nQsqhcNv_wPhRsr;73g5^f%B^pF_C7|DZnL zwTbwpHs-Hx&AX1%p~Dj%ls4D5k2W}#2?(!9t+TFt8Tsjyj|0Uc9|-`P%5rLyN{q1ox%|2& zg>62warx?U3%F?~()ijk^QX?x-?3y%tGcnFNwRI+#@w;}`KM7Y`m71q05e09VCtA~ z6PYq730^JCasGH8vsYYnYb&xkgDyyF%aj+9D3bp}o>s~2w}h_L1ywK39nNpUh#7e8 z5!gejxE74vT2gC(g4sMgFCAvLenC0OkzMW^DU95>d5`Vab7t9RMhs~t(mrH^J))pJ zP0c>bx9cu5OivUtsEL1_0woY4;DSh+7;~qX2)#HTMx-;mbzR1o4L&}_R+%E0{79S^ zI9SwYbLF1@tdG;3K7~nUAO8NzbY+F>*n+!=`n(Vrr&c^*YC+UV5C1JLe&+Tzj#c&S z$7Y`|!iitwR=?SNH!K{LGp-r7FZ~OX4be&JFcZD4?031*XMs}L$`v8xs#H~U<0$rU zP!M*K$1D%>7lHqBCzD(z?{gnU?`s3AS9n4uyo@xNGM1hQs&3dP9{E&6E9!T}e|?Hk zj`_iOIrhAKI>VtnR6}S&;r~7c?<{w*TDc>~|MN}L>u*dkYjQKC9}jNebvwy0^}JU@@8@6ZaW!6Z&-1D>p&l)^ulM8D z5q}ns&140Lm3R#X|CFGq37d9f*93q}96oRZCUC3PwO ze0XQ0tukBn^2pw>Zr$&ObD6$<`18^u?c7yCvzS2nxO(G-B*jm%3dXTidHJia3W})X zeL@=|X0?rf7(XjlF*s8S^;&!@%WQC#6v` zebP4i|%Ph9+&RrQi!xuK?hkkP(z0g{X*@_++Iq!UMMEwrM%!(1iOTw z$&1)%BiT2icC4HKA7gJB*W~-ge~%CZB?S~DB{xDvKpJTnJw}5l&0zHC5(()}X&Bq+ z-Y7xoP>@b(kd#Ic_}=^7_y58D@c-bvt|xo2*K2W}*KvG~_j~xe8q+vQED_Wxk>WKu zatLZ5jeP%O(~lPflIfD;z^i>Syi%u@zE0e_a1Fa`SDDE^`ooiLUZRomn^HDBV2XCX zP;x!F+;Cw)fqKstDEovnnWZUyuf}!jr={j6f^93H^3V08;2QocsO1_5B5h_jYR zmr41j*sr8vLEsacM0)a#G#oVGROQ9mO&^qOTGvS{4-S2of#nl(RjwC0KC7ExYxK_p zw;qVXvFa@5Q$?928lih`lAgQ5RRYNO4(V$Q-b3g9j*buRYdFiI5=8*oO{>3tFT9@mJKNpr z^UwU+n%gUylC)|$6n|;n>0PEY_*-iZKF~gvuHNEok|xjonn}ML=vCkFSM9Ye@g}iI z9)Wc0qYe5IO3yB*k8clzyzzxOjo)?uK)q#MMPn{!0S5}j-vW8lsrJ<&i?%}YRpS+> zA6%w!v#AMiO_&nd+h)(f*v8zes{+{knQOh1O#Ru&J6uee-m>SmQ%F z_qR_^)uzp^EiMw4#QaM2_L_!zJ|)d1Yb#B^E!M`pQ_7%K0yf4hn$Z2bTR3VF!5P?D znyCdGvc2P#TnlvV@~!3-nG&&+$T_fZ^*x=)x#q3Eo7$+^51D&Njv$p9gu>rc&btuzS@*ikwJw*Sk#dWs zif|79mC4r@^i^Y+@b3zjMw4oTy@Z->G4fTbp3T8$%VNN@Za@ z)n?zn+t7th9H5c#(+w~rotN>gI(yuelW6{Tcz!Gtw<>-Ev+zh1&GE!qJnID8S%4^H zH7Ib|1|X-s*PNbUiXL|i`5S`uyr;6=EVK}o^XbcM_C1#p0k$u`rF zq_tP`IT__OZDq;LLcZ9Zc-h$9^7$;s+^ejy*?BTICPHV?bK@6#_P+DzUyjXhHGvPy z9(*6w-%T|@%bUR86bqV~Z|9@LJpTizM=>S5#Lp)%k}?{~v_E&+rJ%=<0Lt5~Rnt7K z`(HnRyOZ~+%LbizZi)J2o_DA(@pF1yensUJb}Cl9QZ3Sbf+)I}X9E4xwjRf&OKykl z@kWJ(UvvQnM-qQ-epFwi7%$S_hO&<<)^j$nAb3ju6&H9bC>Y}to=E5VVkB=4T{;(< z)sc~NHxNYPwoN*$`*d+qm8LBeutjmR6zG$n{`|3bV$|xEA~&aPvqB(8OJv5G$;E<9 z{!&NctcJ%j%G_=yRWz9=Rm($h>N8IRA$ph$Eea_SrD&P%FzMyy_GApKF9ilmX*U`c z(Uwm+xta-#`4qs*MYa?knsN_ogvIvFBvXQi75DMKd%18f28(-54C_PA8$1dgh2>X) zEhOKX1gbil7X*5WRDzbhstkm{4UM4gUKCpdEqcMFIF$)ZIAk8H?Mv6TDq)Cdl87Pm zMDF$sdm~lx8fc4Py1zd+uqtK$HcZFC^h3}1KU?_f@;_?fD1Dw5xs;Yjl!X92G5Vp< za^6Iu&XTXbAtbcrqN?>DAmTjFg^}bjGhMB?&kL35B$Cishbp2~(@xr~PD~D#rj`2W)ClT9<74J5?WjVEKbePp@v}`b)|y?8Ws89N*z- z&Y~Nv($?ZB0-`dYoPE%2%@5MK43k)D2Dhh%o)tA0nJ$k!d0%N|>ej&wxOyVTURGSf zzxuy1yHAk;ORp%)=~V*DZ-n*CAs#2kF=`MQ7c5*iY16N2Spc`6N!}!qX4$q7SJ`68 zjqXiPPDFrhN%<8bpAIs9W!a9Z&E{SmissJxkd_hqTi`YGA)+Jm`;AF2)b};Zs++vZ zOtbJ$zKxp|nyjGCbext@{{l!f`;nbdr%yaquT0)uWWgTei(m=@x{9ZBXVFPcZK|fz zPq(|gWz^V7Xso#JIkLz68SlTGI@Jl?XPnmV(|q|WRWCMR!JGRfJtGZAueS!;!euB9 zUHw&`tUqQ)Ap?2uF=f5wgy>%Tzo-cVly0Sk*=tK>1`zO+&n&{pvUcYY@E&0K5}(=hHGbhPJ@7*pokyzQ6Y1LtG&q6SXREcoMgtz0R; znCvLOg00}ief5iu*8=uMXSi{5N?=bVUo+ihLdF7!gF>vm-~$-}8KX2LGT8GPf4F4ESb(WnoFxV}$vkr)1Z!!f-0WNc8fdi*(Z9cE zGgFP&3y0@lRBpp=Zpyu3bBini?VrzQ&P|@pQrtBORuy?VyD(lvkkbocpt#cE4$IG` z(FS&9V~)5w1Hm+4G*v!@~U zs#%4FkMZyyU!Cc9>C{B;wVNAL((gskj}ZW4*SP_NX<{XL=3mBUvC40AI~$y^+^SY)@NW3{e72)V3(+r`@M#L+@Hb;+yI*l;~7-^%#(?-}d52ZHb_r)4MK$O6%e z8GAS;GYaQ5NbN=C(nA3sDKEkOtE$iA(a$Zk{3puMpOV4TTVj?lk?PopTjf_A(FH!2 zkITkCW|N!aV$zVj1u^c!#Rb#I-PfQ=e{W<84fGWvyy9gB|V$XzBh5`q>DFH9YY8>%!6GVe-WD(qH>jF*UvNL+U8m<5*( zbJX9_=+Go3rKB~}Y72YHFU8M&(IPQBH;w)b#SdOZ{&sD!Q?{UdAqE#PehQ>r#-ylJl?d3fs3V`IHgT?Nv>({updT zS$casGqiyMMR%IWW%?03g;Ss*|b8d)FOYzj{EfX_>NDL z)n+jde}ehb62f?5Re3Tcdxz;X?+pX$bb1dv`K0*-Rg$kisw#@}#+zF|?fj@26T38c z-&OlItNd_&$rBnrCBQNi^$dbZmsAWV4$47-P0Q;t2L|FAufo}RNSmh9r^erIPF*;8 zpf6ZDUJT3bg-oHAFYghq7Dg0V)u=?kmy(nIWFdI^^6^l7n^-)9Q6lWc zZWQ*{)8sF=-W#}4TWQ@NY?wn>xu(eEC|8(wUEQt0H3Ic+LGvIlxInk`;L&RvQ_pA= zM z8BN2|)J8eC(E+cDdyW=m8mHpC@K#@5&FQAQSjz=%sqUpI={heM zT*pTpVYAISaC38mx3#WzUfZAj2RL8}uHCh*k1|^;%hmamNn085I$`DA)w*22IlgkT z`X@}aX69tZBre4=xMctFJql0L2l1ycnaA@XJBcG97l^BBWiD=ZDuMq1MKfJ@!3FuM z|8@-whQ5I_7e@T?f$c5P$C~!Il%ie&iS0zrJ7()IxOXZNl$7%3fr@DuM|~iE5LkEq zK4e))%|4WvvOkH_1hDg-}TtW-58^Y8REfXv$E zsW}!yP2?}rtC)3brJNXw?RrS`b9AoHc1|H;yyApnpk;41E7yag&V$dSt_LxB6JF+1 zPtL9_7&2KPC^f{1Z`*2-xYd(>-nVYZ=A;PPVmGQHs(Sl5dh4^-jy+2hz0u${|EQK{ zf^(wYCCJ&QA(TpP1$BaMyL3kSg5l4gW7JJ=FQ?F* zgI9isxwH3=7eitcC;z?AmQGhHAVLjsR!*HW6eNrBvs zUs<#NEDxlJ#?wnTp+pruR1gGU?!&Hki>~;o;rW~QX(Txussu!20{~j8XTh*T`9WFJ z{ZP`AEB}XqUrf0<@cTL7AoPW7M~Bq5W$Sz|_!&S2?qXdq1-YClzxjGquz4$bEqq@> zCLu_!EXPUkJEL~YV*KwmCdV>-v$rhA;eR>M*o`7y-Y2}1-jb^?b98k%CAR-zx{m3f z)j;5Siuz!mc0iuD$WMASLhz@L=B}1|=9IA~lqeb19KzcE7JL1mylfOwU2a6<)w1 z=xcLwLZ-(ln{(0CdC~9sT5>th*@ZjZ`R(+%JhDM7-t*_mG;sW>ubaEjOEIZXTi%g} zVFbj~_h+^%3g)VRCkD=9jGFZjceyo2$%1{Kv717x3n*Jj=(tNbsvi1nXGD%(|+T}ODth+7bkT>5jex3;PILsFV$of97fn7on*EOg6UG+y4y9~MSnMJ62)I7s zJ!Kn#JvkpB0R74D&(IM-agZiS3=H-U%QO+4b3JlHxqNjnIdHzsgZJ&MJ{J3XW(}_R z!|<)>5$sZXPN`SJ0(- zvutC<50qSD7>ZI{(T5MqBZ=WuvR%9X{JVZz21x2GlIPDOSg?qWFEv<@&V_&VjemHB z!lCm$lJbnEap3PnH+ip>#*CprA;li?A9a7s8(|kmLXp#_{3e39bm}*}jOwh4q$Xn{ zGmXt%nUtBjS(+5X@74}#@YK)(+sBG^my)9`TMJN&Zq$U6T0Z<=I!pu<8}oj4zrO+x zG$>&PZlG@**&C_YRq8QtctOLz08XAvTw9RO*|x_Iw?XZb{aY7g(1I6+mSIh!sg1HV z6M(9QFzX>=ViP#Og7uz8^Q%y>8*J(`u+T!k9VvX?D%5r_cy5_dF4}~PEdx8wo@~Bx z=U~pWbtRcLH8JBe(-OE>D!Dd5OidnrDrr+jF!#$k?KgmDW+HQEqYweDatJf-&Mtgi zw=+;#d5D!?vUD~mGGF|jR{m`_6_u^K`SO9Ucl781Ax0!)jPR$AX^kX^p~>Rm7innq ztN0s!ii*Rj-1qzKyWFq*_Xjgi3Q!Az7SPSNI$+cY`u>^1`T$1k;DuO(_VIc^x6rHA zFrxCasg-?Kv$pI8gzpSRJYum~%MsOXLT?5s;z%>dHaTLL@?K6liiU=lS$g3Xz6;=_ zDA$errt<#-oMlfIfG_Q~ESuw#VTeSSLFE~|{{cMUUfXrk!-9XJw-{`Pi2Nx(D$BRNtG}?)KD9(h zVS3FzJ9#dO<{Zv-+dYhYuM-**lZ%9yWlfgy#Ok`ds>`Hrah+HX3;+1?9Xi6$ahOzIxs^s8|+2pvQe6QJ@M*seTU;wT}U0TZLw|nT_Uj^@}+lt&UDEIPthfAcV zZw)xV562YXy!p)ujmYIbMLa}~&C4H>X0+%$bu$Q-&;Yg>f6l&?)y)G3;F;D?sq}vv42sl4+-m zxa}Q0QI%8!x@av+P9hr5=Ag1`lJ+r39{DTP0%Mr`EaL`bZfXJHLLzG-^z0ivrJ?yI zK)r--pAJnNRl9Y3V7KUrUSR9PzhWbOJiSmy^anRVYGz?-h>cLzWHil^=Nj)(Q^IXz zWn$nV+3UMK2ukCHo!)ly`my78Fi#dU8Ux*a5d9KNyY8&+_~sI*OU!2BJ3Zd4vGW}{5TL}S~BUF^Bi{w&{3&}`;U;Xrh|$k zJB{O_t+-;+Hkz}OvXf37H&=4J8nnb>TYd22Y1j7lj$_XuLIYo}iiXNIq zil0#Cp0?eJX>(3%#E8CFDBO>gQ`O*6bwY;s#rNMKcF$$v3%MCOBK)V}9UIBU6}nr? z)UTN~f?hpSs^B3iI{O)C8A*%e2-{Qa0dm(15RNs{lG(LE_A8FR zMYhmyHqY;R8GmPr7mWbq3#TkhZa+Gfye4UV?eMBq=qWln^6Lc?3mopfceObh@Wi@~ zQVeeUo-$Xo=i@+%pwqr{{nL)eYcP+Fx!aCM92nf$*fZ?dr)o&GE=3V04PpAIz! z$IB19kG31%r{b#xW2`zZa*>BIWTrH ziX34Wpi^Bqr3`;V?jKlQY63HN_(5+ARw8AMp<3~}U~1^dE>WwnoV-xX-+RWqvdj7v zz}-mucr9(!iBfW!CV3R#0dN9!@GU?;Z=5CB_%kR19-T<}e&Ay)_ zU9NS*8Oz9w?`D!Q2CEa5k_H`Xi!+*%qTHD8_n$=$8}Qv%N9aiQu3EhB4+GPg`6se~ zA3R|9Al|$D;&q+g(jnCWs{RybFr^qp%LNMfA-%>u4U7KJ>sp-%;P}cSM4P5cflB;_ zq!JkEZ2KwJ@5E12^6M<;9`ze7!c6%J7s?3 zNI&pAMZ)$0h_nUbn|igk#rX-un^=>4&O54G+BtaN2tb$=!Q~EchbSbyA$_weTYtc}UI@5SL5!8zgZsz%b@zI^MjYQwFO^4n;f*a104HA=^ypO)*j z+hoW5A~c%XQh#4NL4f~5Dbh|FQdw2`ZxFPeKVFsY^;Y<`qR0MT&VK;p)bBJfQWR%3 zxcGpuz_}>nm!k7{)$jAq7JA&_T*rFvi;fB`6#PjsZJtY_7A1L>72^(>OZ1z4W&P0x zWGtn5bUf-;zPsI*!xXq?N);p6mjcqc0N;j{+9oO}? zXhR6FFGTB1LKdXFGv(}GYs>6CYY3Xispry0jyq+t^a;#Mrqj%%KeH8zcZDqHT*wm) znTd+`_Ht#%^8%+k7G7#%vo6BVT3!2RH0wDIk$E1nJq%-$c6_z?TqDcFFNbXU7_<8u zwyRwq3S^u=H>CO)h{1PEl7q+57n7#1&^eY-Iwi(J5%>abXk4Y)k`{6zqEr1 z7nm5s8wFut?dpJ`o?%OjyG6TMs%9pmf%?nM*W^L0_ny@*W(&Q@dab09JqFVe=O1Ss!fb|#~t2&Gkx0Z->3NPYrUzeJ-`woi+x(T_b0%SyVvpd3;|=4mM4lIjy_3;6v$!j7S?TwZ%WFr>DX2^>W6)nUkv%&s zTX(kVM-%UD)Jw_GiKc-uOn?X84!5SF?ji#T{Cv$h`5G^;;_cHH;wMh$*UvvV%p8Uyc} zjOK9k{;b-(_VQ43f@y77TN8>&R5ugiUuJQ5)i-cSHE-(?wX4>Ig78hcuf^z#@)~(S zcfxB}IR(WURb%Q?yt{>@JG>Q{k@aaT6Y%> z-eL`siP?Goyi9e&RiQ_Zc}}O^vzJTe8Jt333P9l{H6yVVu|ahsz;B59jA!su6M>hG z*;Tb}o7fo_|C-N^duwq}Np)tf?B3~?=JqtPkNd0Drb$_gmJYI~`mHvNUH0 zK3xtu{4FHL24mrc!FROfTs8gD*^%=TwZ=nr>lLGhmXn@A!c|^>^P~>$HcXFx*DofN z-~I={iL|9u_%?*m=vA5>^CjuqwH16@co4!1z*r0>9o}|*d7cxYvi7B73N~d`{jVN1 z?ZT9L4w}4VbMH^vh;CSN-%l5)h&CYu^eO8eCx_(r1L*pm5l_7u&p?ZKT?iJ_8dWDH=7U5qp+0|70^WP$Y>w zjjF7?x)KFHMEv|CUZ3yoqLgn$X>2-K+KkPhCWn;FhBn0cS>v1GrF1Pl-0zMxxI)#B z&G<<>llu_-wuik{tquCywo}Y$Zoy0`^6>rHgn4cCTr zKO76bp>T=b|8|>~Lm!i)a)9WdrSRV%%r+=;J{QwZ0g6mDK24hNS=<0D85T$B7NV1< z4!bVg!Mcp<#>_wV2|TO%t`~BW0DWBz=FtxDv z+D%FunIG|H))*=?&N!Pa8j6q~C63TcA{L)hNEBWn3eisWmz({S*t{mRxIguoFp8q| zMQev+PlM2U%Qi_$CM^BBGm<6yWp4yfo%fr(o`(8;BBOiGy1$z@g;;1msH1)Y>2P(c zZ%QYgsYDPGI}8fe_c$aiP^f?*FTWD6*NOko9D0%aj!JsP`+O35ydiV?!^(dT)yu}= z&PB@<@_sPTS52q8=OOco{m6ALOVG`i0-@#2YG_hX?!!CFy(_0Zq7Avw>8bkKMh_Md zJs}Fw(GMqVU5@{|zz+Y0%-;M5NH@zzx;dT8TA#9QS36TB-4SX2?*jc}GP95F^qSC8 z`Cq~A|G#37LJQ>?Nk^Pk8s{VFLRDVKAKveKA%DuWF`;DPW2}%usGGY{AU|7JxV_;(XE3>1GAG;9C;vk6Ji(HHrD~x+r(v3kDo&v#<@*sA9f{Lt}Rlrqf z$jdyM;GMFZ0VOUfVbblIk;JS!PD}n1wt{OGx0KQq)To@mH4BY5;;4x?`cOtjb=1O$ z)mVLVHdx8e=k!*T(gWP*d&!7b@8I9jw^jA7+rTd!?O$5g5O+%hY?_Iqe_@aQ=mg?j zP2YaGt8;xUcy7MF{XaL2QG@62HaioYZ1&)HR1+3HWw+W=Hk)$&l9AGD$IB8|1a}49 zf1OG=PIQwOk^pR1iTTA4bQp?YtKEJWq;_XADY2WX|<2Y$((B)Bwubsbo@ z^|E07=KLoV`EVty`nGNvU#?=IQOUzlYlBl{tw-fDk0pQKmU`4gD+NxzOt{Nyi+_`! zu@$1XcQ&KG6H9g&9AY_oD;N2xBw^~seXfTIbGlc4tEQ1HhCpJ!t1C90J&fa3EEjdK z-x+I8WT%88-g0+zm!I=2%f?{TGf^&cg5~%s8ErO&AlT4x&CJY~5q;h!YAgHh&hI}! z!RZcKB<5pb^6dH(nWK<`kzG=kAU#dtJ@PdG<6Tgs)RkYzXntWT|LEVAAvb^=?a_-@ z`Cu~XfW+jR#0=!jt_z`hmt3{fmH)1JGSqYJ59 ztDK|HvWsB+U~TyWzg10~<1yC|a>x(a2+LT~YYwmQuAFrTCqCnkzg>f%o<5l_>_7zn z_^~?s-Oz`$M6$7CsV=MxYU_MEvMD3=0j{VDr0g%&@KcZX`lj(F@`_7~%oTvXkc#+T zE@00xN$MsO9O~~qdUF!iA+r)!bd*xf{iaYHVx|j$QX^3yazN>ZJ3IfE7l?0U1fx1D z6m>I0zhbuHemF?c5}pKgUR2k;!EulAH}AJut(R2|G{t&1kZ3)t(DZ9cyFXF*!?CIH z#4!CG@yfOL6m7-alq6*7+c!uGZRx{R=6VR#K(6-;deoqU>g?;Z!NYOvudij`Y8A%~ z$R)`nTW z1BM30yf>9fV8zDyI0m3|}d1a&QK6H?=eJUAw- zEkXK)+I|ostzYEJ*RBFfZUU62w25Mo~-^ zI#Gt7R-pDsNLhp^H*;EuS3v>X=5T5+zo&(E-{NAYAC&0Rv=8eCu5-sU`A5>hrDZ1dqSHA_%f@TZeNc8n~5oKY$o z_k%JY>%x(I>pch*U6QQO^;+uw!7h)j@J6ec&{~~;3HE?o`E7%c_UvNg#o?^sEjbNZ z&iJ$4q;60D_~JWrpoS8@S&&46h!XcH%?f68v94vPOKB8GispX2{KSiO#*>STs&Kom z-eUD7JWbflk7s6)LF6b`IVkdb9$|5gmOoKr%x4XKDv~m>O_>vML0$s!vuS}et2YEv zAuNXGq686#KTG2!JU7Z&NGsbm&EB`P8Tm|=ny1B{oHtY>r3}+75w8S!*gm})piXhz zBA4ZeYnCS^hT%+>f)^Q(4DnV|dQ6BGC!J*B8Cassuw9#zlwcb0t17z7q4Cq9xW@^X zNGYyHgc=cZ{$hiTW|IT#B}m1I_a-yz{r$4z$T8xVmLz||e&xi|XtDbn<~{EmQDm?~ zQQk3SXRKRwJJc3(%v1H|GwyXjDo-b*h1sq^$;#R=Yo{1k{3ba- z?qunDSc7|WyUe7&+9NRH$HMo2RNSkZPSo)z{bM#&Zu?VgVi8AU=9AVv7YG*Vs5 z4i}$VyK_LzO=|Ri|FNK~(h<(l(hhC>`7{W%It=fV25SlD7wdvk%znsnW<55N(&D#s z37|*+%WVFKWcrO|#;8=oTT#UY;B10P`3hZ-J4~q+<2>xn`Y`STM>_qw%=ziWk5Sic z-Hf~S?s-YLaB1I^ncM=t;9`i?DgIWxz?YV#{RM@ROk~nXEs>nQEA(lnN zM0-p~NpL_9hg%ruKX|39QKW9%l>;~kKN%Dktue2yKrl{`2k}tQMuWVN<9ugZMoiLA zxNTmHy&p_G(pCEtC4Tjep!^9AYv$uDDR2P<`)Ri>79bwd3p%J%@&Usj#e{C^hrZhe z^czi2zrN?!S>lZel9OzHJ%JU)|S1lOb3dt8ePf{Jje|%a2 zD*}MuEnRpzqmjANS*F%^F*@vX9)e<`p?e>6m$N?Ie?#mZHa@VER)zJ z;no#?q*Q!h$1^u8()tMWX|2ocr9m6ru1#xX%#bQk3h6h`c;6evD7T&RCF!GV7M={k z%ML7OX8DD<9R2#N;gfl=WkwXgP9z^Nz9`UujY+9oCrb9_fMK_*}+aP9?eiG0tST8?KzHIVL>BRk#%^lr4^r zkENt){4GQajs7F7`nLHo)?-&+jzCLU7lP4HELYSZsZg% zOPi~KW?uX}i;C_HjaOkSU3z~iWcGyq?3}t|^MiwJkWT@6-LG$lOy?{4qd+m^)K5af_uZVqF9rkyLw*~;a%z2I{oz? z5At_rn*Y-5a|6-O`!fI=ui{v&yPYp9ye_H-I=wGOTZNc{Ff9c(#rq}tyVY+{hRG@+ zxgrLS9>pfUp#IlM$`w{xnjR=FOb=eEkTw_Q78!rbZ@PeRp>NDrBEiQ;FdPKz)Zoe0 z(cY@GC)R9`om_yNK9-xs?&UIMV!R{bdmJF}VyoVV^6bKIU!O;8d0*5L&0qiY@P205 z&7uzE!0>MbNuE}ev+PQ4s1AG71~=y?9XIW&8gv3?>rY3r)t2F^kSl$ECkYOJ3MNnMf3}QMD>5;XZIFC1GOzqu zEIi(E>}Z2jHwveH3h*Z`tl%9Txs>fVKf47B7(qU{TZbinyG~7S*&E))r%WOXANWIZ zK}kFA{16BMDMxqmZ0fR1lZd{+=g9JnkV7FJsXyF=ibZfF1wZ))vI5|je>H`?dec@Z z{XOM{x}@b1-^00~j1}Kw{wsXT{!|(w-7l~!s?xOQLtNt%Mb=O7#7Gzdq2C^$NqTu_ z+RDe{rJeAj*3;?SIeXFzMURL0p|6 z8nk|IErI!V^Oqu*z{kxNtP1N$LcBjCw(zI-BL_#3oCz)71HoRLncey#_$Nd%-jNV{dYZ~$S|`A zM!^?j_?mUptKh0au8@~k-u+i0GC=?d)?XHHsh<jjA@KgTnFb$Yj#NBr+{R=o2YOGB&YSUU#$ zbWp+FSG#syvhUa?%(X@6qzG=@uebjt|*u4W*`0s7!_11#qH94I#Z^mqjJ^B479$2 zF`pR_4JVHdlLEHKuJPNJAT$#gZS;8o|!{DVq zaFCHJ*PA_Y8z0TcFRF+utas1#2GDG&1}5*^A|P*znJ-L?3S3qyIy0^DFR3na`6-?o zS{HZ8C^7neOT>VfB?jfH$}5vVz#4_M3igj2u%QN!*6PY6PVAM(Y%(e(4_dQ-JX#mO z#vhawOLfih#t`=H0UwqxmiaN|8H0(bacQ~uY2-gwRD$w0J-P!R!x#7WLr@b}yJ)#L zUg&o4E;je>eDvcv-ERRc~$)_md(XqKK2+ zlgLOrN6)4psjknHbm+qZ!c^HfPWnee1U1GTgs=Fxn~ur5_5-Xt3%2Ak3ca_d==rnK zDJ{wVzTw3d4&Ea8zL@`6Xklr)y67J@@P`vDCvy7%zXDi?Sp7yb-7$8`Exg=h_MkPl zB#+8#n>+uHoUPAF8iuR#cVuyZdyi(Xh;s{`3(6N9(`CL;@V$5oO)9;<)b`wvHD-!m z7R@pEd~a@QypawA=i%o7rS0MN!+Ddwf(A%sTk8%+mYlY>paWu)mixDi;}BaBFiLV< z)vD>}ACfkSl5F4oe1fwT^wEk+*|4T#sovS4J{LW0lBo-(%fKW-Q5%x=_X)tZAPq-i zpAFUgy685kCLb4igeX0`5=upu?*2FZI7~A{=bpsM$3bJ+2;R=Ms}axrL6Cm^E-gwc z?aFj|Z&!%6SiMheUz8h)rUJZquY}}~BZt2Es!jIfpn~<=R+93^3`Kj-Po&nnmHz>J z#N=SuqHLN=h3`mnSHY(6Nk!mCDdCv zT*c&MuAbTP!PCViTGzJHB+i%S3B?no1mS-ZxNiCy7R-v(6=Q(*-&u~x`d!TvF;l#i z) zY}c?!Y-F?h5zvLYn7|H2pk3c+3u3Q&Z!FVA4EqIRxUXxLlnZynZx?A*T$`Na0Q;j2 z{?3UnSOQ$tHb^k5p@_%X;FMA|XTp=CCh1#!PxCZ&v8*xP2RHuvpS{ZrGbY4#4htKA zO!JK8zo0fO`=$~3%p;}pDh^PRx**v;%Bei8#u`h1h7IakJ{@#Y*2CH>uPE8uxNEB` z(3OUgF@n_CeV8&^z;KwZ;z(8d$25WW?CYB!7d9*VEIJ;TH~t5}>sE1A(@)9Vu;k@G z6N-Ns^a@GO(?Q#W^07R>QqKH)lV47T6LO6+zOt%hUXK||Ltpu$Bx4ue zi1GfeOo`MWO1cX)$a)RQ_(jzYe3Kly^5FdTC@vTFEM{-LzNCIF#7}EeoK3b{VoIg_ z;KrLx-{VOpICVH?UDMVb>Up%veFx;)-jWlPXRRl?Z=BH73dv0h%Y?@HS9EjvC7+&7 zYe^quN%aUZyeb~7T|f}Pww+SI>3VTADM3qbN;lrU6L0rR{tqAp6aW4@4I@hrDfx$i zuxdEy(2Iu_mwbJ9tPbjv`Ww`?@`ShzQp3U?PzPb%pI2X7`=%ohPV<{q{hCTpQL9r= zXFamro|IghK-OeUSO$?|x+0_!L&&`Dy$7dTcC$FG{z$PqB|oUG>hS3|LJh)^jz(TA z+;^0jS#7LWQPHLf+yy!xTDXiB8==!AV~>HCih65{?wqn4u1!{714kk!qfFdE=3eSx zsNN!95>yJ7-l3DuV*WO6jh2$ub2gptq5b48r&6JuIi{zqzVn`TXH)<^pV&`z&upR< zXQc7y$<+6NH%sPA_Y$H`FAa9bJuKuOE>UsNr2P}>jf_YKZu=H;&&g}B)Ptj3m9Dlq z^^#K;SM7O0dJ+;`+pWR&mh}spY#)7Sn$i-`Tr(O0B~JA zIU&6{=Q{?d^lHzkIlWmp9rS7Wut17+y~2-wKwCor5_e2dqzfl{66gD}o&C+7GMnw| zYd1$PZ~S13-AD9xMzmVkn_DQJ$E(wiR@I@kKuMmyqozZB<^l)@FcWMq7_JL{S#UCQ z$`tKq;s!n7R|o%0QGvX0FJG1S;%U-$1O5#+m$&Hr$++7jUvqXbI%-NP1+ z=^It*8hSYn`~!*ciofY|iIy#ajeAspM}%MqUQO{Ad}o@q(`FAz(Y4Gq z=Asu<1PfvSw!Rz^YGjNO04fXX_D=(}%%$fhj4VIZt0(PR0U9x616^vsuhO+T?#aui zGmPd_B{9Y+7jlpCpO$m62_zK=e7r@N{Wg2AmV5e8`Bg>g^r~tbB*(w3wv?LAuvdms zkSG}(LScIkgG0?6 z;r9-W8SU4B96#1qPY)@jF6Tbl$V6ee_5MPzqrQ$JF|J)0!^2<72HK^D!q6d*XD)@R zYMG)xlD)VYS2R-6jEiE1tZ+~%9P0ecW&`@D zHBNxaPAL^vW2njB?@6~gIZ`J52e55c+Jf&TR^?s7q^M+A&A%7Vo|P45%sJXx<(V$3 zyZ;l05SqgTY#*XSe-lZ5ud2-&nJAgSykK8AD#U%Dyhl#wuc>zM`UuGf<5wrsabBUa z95o`fc43)v9HL;1MNcg0@Rs0^ffT7p8Pk<1ZaV10nv7bm1TZQxH97wEvU}5)@(a{%xsBCa092FWh-x~!YF2s>efiBv?&fJ7AzFwMhi4sv4aIlCL;*W;nc@T$gB zz4Z?jQ}MvwbXr;@GkqorEotTwx7-KgzK|KH&}b*$`Cq+_20r1n9Q!oYPgG*73gEHi zfz!3hxa;FVrivskQUWpwF2CG$+`;wbbfDLmXcYyc#mGWXdOfwkb0^>((W)=|hJB~4 zpWpSal{zydIM`Bl8-fs|yclJZw&oQd-TV*m64OGOLQ8s>T=2ZQ-a5XLSY%PaCkbwi z_>LzGC|fy}<@~?yvH#2afYOAP$p2ZQ))%bkFZfo|`G0`C#0kp}cx)(AavDX;z%oH0EqM3LVIjpobA?^JK)fTC#X z!zHxA32Ls4XFmcHM}qzLBs3fnZrj+pPY>cQSX;A1|Gts6R`w0iMUpz8Pj#M={*^x{ z;JEXTlFeE1e{ zj}V%o6EXm!KBx8pJp8zkmTTW~6@)OHp(yoNFMqbZxUr2wQlNkAgje%0S zKhynWQn{MzGyextE6jt7f1JJU8^lNn6UapPO75M2_4bXZ@^jb?9~cqC?4ACSy=e4t zO5}ZZ47bb&rV1Ym7nCVvRnhd>S2s7ol66ng+F_i|qmL)&Qy{UDa(IuRmbjtkTGE5i zU|SQJx*Ji=gx}>=Z=0+dEd2%%qEbNDnjS$(jd*VJHoAz?m5p8Xf<~`R?yg8kINf@8 zzx6Tz@6BLpzpN5YJ3d&D!G#yp)L3t#p|NtQFmcl1Rd(utgnn}T$?jQg%fDCJI;?tQ zMT^vKq#>E3!&kc+7-yt_$0mI}gPZirfy7tKWG7wI%4`iE-T>i^K=Hq6^KNcZ2^*LF zS1=;6QQkF(u`X%tTJp!ug8!$r>x^om-PVDi0aQX00U-eiQUn1J4+tcHV1Q406O|?) z()refrCBbK*m@2!LY-5!Frucekwe>y%#^ zv5mI2C$db0<=d$Ql&1f6Jf)^gK}v_1b^>6k19>yM9f$9qDmb*`&MkF;$x*;D&H-Mv zJ-z{dx@bk`xaPUSXScO2qIalXB<@w+tqS`IvPVtnnO{0g%8O>W$=DnzmMeS27qpl` zyasH~Rr_3#nWgC98)X-}2iGYxiEOd4TKZyzv38RhvO*;m$wjuV+G5$f=NEh$Fnyn# zns3`go`zLi33fP>X>_`B7kV$h=m269u_C{Yo--En@UhMIM?0Ejo(|2C9CXUcg=pXI z?jh_6aZw4KFcOL`k+X(+?>Cb~_f$eu9shIX(&q>^YMUwvBw= z)z|Mn)Ln3Ij;Cun=~$%yW;f++_#gQG6%l~#Wi2wibnuUS$n>Lz;@ywzw6j$CvC1mR zt&4_0bZYH_%+YWUvd;@TkzO1obhypOJ3#J-R2m_Qae6*hZT|`HtBdazuo6{2%HA6r z+E5>~^seUI4nEg|$REmjn@Ge&-q$?rH~BEPenedzRaLMsR4@MQLy~K-%qy2;?jMYI z?q?KgP*RW8j$6;)+v!4?Eoy^6P)Fq`JVLkq*r$VZvh~AY{71*jHpdQVhyMgk+eUa@ zYI~sAI8d5X%6js3w|kmXDU-a~6ExH?>|nQXsRp~@H9+pN++I4kEkd~dzZz42tPt<`cPIcOJ=l=U> zJ6xLB{XeC_@I?I1QopU9?3z>z@?HBVf_~agRbx7ULbzuElDhpPv0GE{A`#Q9HHu= ze!7M=Sa@b_!&+X1tD`hoDR&uqO(eFZ-R0oHPWwBdsur5kX2RHf(E=803y-Ts1`S=% zTnYah%!|51Uvm80A$bG17VTbNY}v0fv!V;?z1o`4r>+MlZfz+WU2JYwl5ZCpKP|Wx~wo%H5d~c zQmR$@na23Y*05bb+tP!DB`u{c(A~42Y3w*QI87H0hk}X~y>ANp*oJRG+MI3CIc1Hr zk;7jP9~*KkCwrO=cip1pID$ImARtld;a5bHmw$ZGf?w&zu*K$1eFGy-_Fz9w+jvo18DLmqtiR`E@>PR~T;fK1m)(hij# zxoE;3=a`7Qj(kGSrkUl&^df3v>@=j?ZI@lGr(dz!1p`n3pMf+o;0gWh*Sen|-Q-7p z6Ak)oXilh;(*DJ{t-bRZanGk1Fud6VIyN#yJSsGbuJ8-aU}9|POSj<-Af z70tzly(gZqme%`S5pTr>xdW~#XYOIHe+vx694<{)+x}?6_0rvrfCnrC`K!DAn)R?4 ziEpxbZqEyh90$p_)#$G7I)6Sp?0FLNVNGU-1hkMXvSPSPB~c@`Wl6-U}@J z4?q7WZt4MCxU2sB3U%*cs%A^cl z@9=LnMap6)ec=bNgx%9A)Wf-%(QyTnmyvf_#}jN4b8%``2qIT)wVj~2+J7QL1_4hL z8J+Z#i)ONZRl~$}r;-$J=SCSfk-B*VdHXn1$oZ7qt`Zq_fdYZiBo$C3DC(7LjWey%vq1A`FB$+xGn4vYO2cT5Ir>Qtw<|tLeRkycdEl`(m6l%Uz?G|?K5tVFzP8f)o(v46p4Bl5DpaOk}~9f$h%rNkekhGoQvfq)3KZw+)8z# zgH%zL)D3StKOVuZmhbXEi4Ay;(#3`8sRd<7}xR-^YGGK|cUjXK{97 zpSfQqQy=_AHLoC zZPoS_CK?=ZlCsvdc&=iWmdeMlu{B0SrL{Kr>wv$_#_P{l%Y1=sqms+rCht0O{!lAe zh7YtGN`14=So)#~^grd&wyx<{Zjnmv`pU*#N+BQYy$r$~s396I*v4MmRy0QKVt)jg3Rw`LY5UkP&@*7QScM>>h zq`;5mOZ(bH(u{Zz6)sIXAKNHlahx{~UcnkBMfVTLoej-d*@I=K_q z6q8V>=F$}sNd`gQB1V%`Ct%S6++_NZQ%8~DpdEqeJC4?tt}Y47l&`gh$w4ZIOr;lv zaV#A7dhNz=C%fv91ZW)1XqaS<3oN8JP;IiCy8j~HQ0|N({PDcuPx&G}0W8DO;Z@Ycc`EoNT|(El3|6GW??$h#nH?uY!EK;&I_VM8n0rl{l^?xPtV6s+){sm zO6x{GZ_v)T^5OVig{sWQC+$gENJLB?F6E+~zk=W9LJvPm0oN2%jIy@1a&&e!Y9J{X z1hg$IwLH(IIG(`OcyxC*hRC)nVM zqz&};O&)xqn)*!A@T!ojVLE7zy%i!J9eRI85R?6*ggcJnE{fpRrkh zyzuQr1?adJ;|XdC&}oy*Onc`U8~AF8q!EO%P%|=12_Na}fo(0!8U{c9s)L{=`SHz= z`qut_=}bidHV9=AJl}@!IgtbCL>R(t2dP3y+iq6;_Qj-sk-%0$9U3=E@~SGiSfv)A+yYgQ!;xlV6V7>#$)y+O z#4k*mw6hqvqxrfW6EK2_F?J?>UAWy)uV%o)N3}c-+*dZTFiI0zvU zxXvl%P$$ZkRg@Z6VWrHH6ZAuF$LN@8<>f0VoA4_t5Ha%N5qi~qFV6McMgnqhC4CF z6RioL8OXG=r*FOdS9AP7TGzj7xEGT*_Rqr zqTwqS%WUF}B@N0Zz(SUs(HPQ9m0c7{kqcR;+r0wNVAMw6@6{*wZ_%oTJuoFu3>zfK zS}Ke7eH!0R(Z;ZSTNqB30iaD<2%#tK>q^!AC&C{t<61NbTI|%lCl*74RS~Y*MlbEU zjpGbx%fPTSoX9r!1}86afb^!mhe<;wY>5mm?Tlx+5tb(dwtOwZ(;ToKrZ0!NHu36GlWu{b>gWy zU!Zm+C3fIBVAdHj`@m2+{uq3-u zE_*G#RjJvC+X4B$PX9db>8}EBA{j*rOq}y%0(39SwH6ZF6CVOvKdWnW(>w2EI^pGzhV|BMz2OsZ(WTXO4!orC1+;n<7+x$Q0VT93)B&S* zHy4neR!e}p!7wzP9mS&KH3gW6&Gu@*u5{h)R6)^Z*cVgyuM5eqFlQlsb5&i6SqRa~ zBG||^M3CAjoxsT%Lr3*~{9n~0RXgIG!-`3VJ7r*JDo^?b5A0Kv zr?paexEJdjL6FEB*j@Qr#%sb`=1)*X1jpz`SZu}Wc7)Q|%x{|(w0DpeNoo}zW4yte z2UlXTgJ+N@Sn%&v4@tUgI7{~BzFspcc`}w{f{*BU9LL9})O-X4yHOYM`FBvw_#5mr zoXVCLi}k~`ugG!_h4@l2BhsMU4c-~fU(a{V@1@0;{{{H* zN}Iy9=Bi)Ds``l@b=mnAcB?E4WJvX@&I!dU`1_lP8%BXyJZiU>W#}uaHic)djP7g3 z&Slh;E1!EDhQ`D}|4e6na&E{t->A3RiqiV!rPX{o^B?tahh3fOFV4(oi zSrc>Ft(#4ns~l)tv*5UfVTdu2044rS0}zmiF#h|_DrX`{q}bdIXo6q|$0=IF#V?<< zt0r`Nq#m_+&DSxHYcF8W-3JgBhD3$q)fF0!Nt+>Q;vc5}t`Tx>(U@dUJO)VjpZurB z_g|0umoA=va*h8#wg+uo!vAu)t$&T1Y$^ZY`Qmf3K9RM$#z~lCRx{2iNXCyaDPKw7 z*XTOIif@>4mhIVC-{$1TTr60|m=ybFZp6c)6C&TyhI<`L^@#AeN`APpFwC5piV%qy UCmVGj*m9Bbtk{=p7C#663zoKFwEzGB literal 0 HcmV?d00001 diff --git a/data/quadruped/tmotor.blend b/data/quadruped/tmotor.blend new file mode 100644 index 0000000000000000000000000000000000000000..ba06c0075ec9ba8da473eb1cd3e0b7c82df8e98c GIT binary patch literal 475716 zcmeF43t$~po&P6~wgJ%=0S)L%5QVG?A_WPrCTUX$FGWDfy2Yl@&=lLIlp+z4W)XKI zK2Si6>AT}L0+aE^Q08oB9z8mGSA=5DI+k7wNc+>1Jv zb=ZqrIh{B6-1BN&jlIiy9;~lKC02irf4EtD@hJMB7z4!^D8@iB28uCIjDcbd6l0(m z1H~99#y~L!iZM`(fnp34W1tuV#TY2YKrsf2F;I+wVhj{xpcn(i7%0X-F$Rh;P>g|M z3>0Ia7z4!^D8@iB28uCIjDcbd6l0(m1H~99#y~L!iZM`(fnp34W1tuV#TY2YKrsf2 zF;I+wVhj{xpcn&_ZVb4TL|g11Hx={eM?bW?x5)={j(1-CyQlYn<-0xg*wf!{@%~2l zK)ZX1k7D~D-9LNsE5-J|Cug_3_tx%;@lkC5<@MQ~QmWYg_moU-{rhNlp?nnE|JL{8 z?ig8Y|GQ(>wr`u;U3GjE+yD0M+sR&AvHef>4DI;#wYydDQEdM^zP~5a8j9_IGG$}e zw58pxmXBil-!(bdRckG_|6SGdlV`o{t|@#J+yCUr%g$&?vHkCiUY^|RXm`!yquBl@ zcdoW~>x%7vd-v$>S6{npG9ShEzx(BHTUuOf|J%}gdq!-#dmDTd+y9=C({kTMvHh3Z zQ+sZ?cK6o!D7ODSH_v(Rtl0kZdgb}`TDyC@d=%UN^DFno_W%6Kciy|@wr}%d`_Jp4 zJ@>U@``>eOTkbn+cLn*_qqqN8yyB3igAYEW$-UoVLJt(%e=!o;T^I1NM{oZ{sz>!e zvHg$glIPtE?d~1(QEdOuuk;t&|MM%~dGD6nzRip6Kd*=O+}Dcjf6vWrx$msq738DX z{>$yPJ)>N){qGrh+?IFI?t=L!w*PJE$=xru*#39FoNezGx4R1YD7OFY-Mf>!zGC~I z-1*rVt!sBH;iK68cSes-o^=%4|K!QVu4+lUTQMKS_P?vLuxr*^Z2!Ba-zU>r+g)S$ zD7OE}l$jmhmSX$g@qIkm*U;`7$VajLPxfqW-}V*T|Mug|M3>0Ia7z4!^D8@iB28uCIjDcbd6l0(m1H~99 z#y~L!iZM`(fnp34W1tuV#TY2YKrsf2F;I+wVhj{xpcn(i7%0X-F$Rh;P>g|M3>0Ia z7z4X>44iuAn`bvwM^W@dizt7A#m@_83tzGO+q%9-;PE?Bu> z-ldl>Sh(Wytz6o*vTMbW7cS{owvbW9yy$_V2lj*>IR7jsb|;eVeV>kf@s#(< zc<=4}v(8_NOY?cnb?%Mu{cd*8 z?R|w)`&&^jz0T#AU9_U3V;g$ECORtGJY`?&PPg7E(Qm4z#Lrki+tT~dyW{@j>)|}E zz`Z#1r{1`~Ij_BGVay|ckNKtxE{VBj9_HPTy?VX%Fm5QE^qx- z;}(+t$vtOVE#}-eMbTzAADnVhyuN4s^1;WjU$ioL)4Au&Y^i(O;*KloPI0@zyb|NT zmOGwTygqJs-=&zhU5#;B+l_hsoHxeHM^3^#TuZVaPZn@bpS+O!BpzRGNv~i3pWSoo zr=ewNM{baNk#Q`?xZz6>$NCh1oE?=UaV*EUhIb;4^)YVMv}_#9F|MW)ajZ{qc*b_J z9OKx}tdDU~^cU`ssUm47%Q24SSRZ-SG{x1s7n#5RbI+|mYp*~aS)T0;->Y zZ9bm$vfW`nGoIxcKkVaKFWX-#p5+-|dnMY>dKq7`{k}Zo+j>;Gcz|Ef5i06I%ocmZV z_b+p1IceJ46{?7)MK5+R)zx^r%h2r%WXUn+!)}?4<8Z2o=DJ#@L{&a7w?#*XMJ5$9 zFU$k;GVnd*h53pbZFz~_zJYI`vH5SB4tfPRotMXafl_(la@OPLxp^6O=i=7a6Pfbr zuZU}z8oe^9Xri?yfji|1^TIqZFZ3Yu6*nf{UcQjpUYeSs_FEnQ?|K{3`}-EZ+mF}V zJ#%}h43>N340(w?%I#(U=*sFU_h6CIb8{FymcPB2$Ew|bHjkq9@xPPzALfO5U|!f_ z=8HU;=VRr?_Ri_HgOQ{3>%02-rp?DD=Q+J@u#+Ej4MS@`6z_x6?L2+%mQk;LWNOcv zD6$8p7ku~3)%L9Asqf61`7hsEJ$UO|;+RveSloF1>8H#(^mX^e%WpsLufG1-LpmB? zbMjAS`OtWF$alNex%wI{-eT@{xKU=JL0%YTSI^H)h>>?0wdTSs%N1>DNDS?!dGrzI? z^7Z#TI^6uDTc@o5`LnmJef*6pX8*+>f3WWO$E#)^Sl#d1P)w7d2Y!3x2jcOPZcDkZ z**Kav>$t{-uRgi@*ALyay6RWITy0~6bsh8hcb~xLoL2;!diofhWiZDvZuYg&WZoQb zb@I6WAy*_=#pobkX6DS9qu#r{r))r7^S2&8a~AhyR<|ABZTijf`1~PTma&{?mu^o& zJ0f>HXzi(rYHDwC&-R&Z?f=%p51$-GSGJU1-wb!oFwG9~ciL3xSLXWi9al;{(LY#m$M4VLFEB*e_G!8U{t+#WbfG?+bvmE0_{Q6j*;_xhKr!U92`XyK&>tkGaotfnr*Xr}c z^)fDfow?4v$a0Kp>%#h2ALHiuj|13FmSbFl&jagIoUUuz`dE%}-F_UgKE(~kLyzlY zImXrc&k0x`<5o?}#<3jZ>KEhvu|CE{(TC!vTp!CZuGY7c^)YVF)NCBfF>ct$u|CG# zU73wzImUJS_s9Aam+eoMV_d6WAM0aW6kVI?PnKg`C$|T`UdG*BnT=yP#?b?;k8yLR zo)I4cu|HXkaV*FB$g8F)&OXPWUw9q9&3~T7^4t!??aJ00e~#kIGk(}J>t%enoiLu| z8DINu|2YQh@%*j#`paV;#n`Z-;(S1iduN`1Nx;3gcNm ziT81=m!2%u|9!qZ<7@xkzkjx)gm07g@5?iOnDM?|_B%Zuwx8u0-`4Nnzpsb=7y6g$ zXZa-l9}v%a8CPokZN7XGe;eXiFSnb} z{$u%M{XUNE;P%gYM#Ts1A7;F72jloY!g!YF`gxq(=j&m=mm0q;&v@3)dYM0tV=lM; z?{~oCab9<*Z^#~(bG_UT_LbP5S-t7==u+1mYF>cr4#|8Yt~d1k)5NYj)c81_-{!{e z)awrW6xSWx5hU}#yx6#~iTR2l_qs!Sa}+Ia&b#hlui3=U)h5?<2V9jx3n$;dww*V* zW^sGlUe_Jy5Bh@s=sOYqpjUX@!TkVz%HuNjSc^M< zI((1C&j)(pjgdFgt9zVCwKbo#_mlOT>SgNPG8dq1m);)rf zImo=&qP+U8rgT`y>1C7Qx#eYsYcaRGZ@Wfi-av^)y34k^^`!5AW#7h@BciB3`%+Bw zA^n&5@F@6@p5%ETkL!6}LrVobuj;Sw1~yKhcNA_I9*_Y8kdt5;IjU;`Ynexj>9ReDde#Hu4c>2ldcim-oEdim*d0f zySm|9x&BrD{Uv_$KBM0{o8UKkkH>jD-{tu)kNemR?kE4lb>8V!?sNRAlPXr^9PbS` zJ`nqj^O1jm*J^H~kY zU|#sXm@n|nt}mZn&t*|$$Kn69!T3lwej44w{MF_+#3THie&ccY`Tlj)W6$t8^)2ok z(~iU4cSz#ny|#*zDp+5(e3sJV_$U`0PGKz}hvj!Q+jf4o>nCn+kGclsc3aTUoVOm7 z*gdfAW4L~}BU+p8N9*SqZY5mbtK33c{v!Wq_wC^RhJ2_iWMwc_B)_lT&%I!0d;Fc2 zeK$GH2gKx#mCZTc7YH4!@w`LKJA-^tui z^-+_Ko6^VAtv|)@WH_(C2>Y47D<`(UVH~~Id2dd9&!ySp=bnXGj$2pypO5*C4%Zhf z*7i4kp1Z%fq3WQ>9^+5x{`zcAanz#Y>GEpLsc0v?WaFvFrJH$RUfMp4yf9yA&h$A^ z(xuyD@j8;22pD{1Y1M{-!a^!{iLhEPDiK0i=^PT+sVsSbzSNH;@ z^1|h;$Io-~(j8qNT^tn5L+0gkZs9ASl}xdUsM~S+cQVG4cVb?c2j+zyWWMkY4t2jP zYfo)2;yYY{d)>pfha3I)z8yiy_F|k~?iX{Glb3s=o2u@Jt|?=CG3VRE@{+&3ShDmx z8Lo7)&Y2hHfq7wjnJ@BWopb+EDla!wy(^R5kSELg8mh(dh~>q8Cqo|VcQSV_`KXQQ z%=GdXW`8Gh`eWPnJDGp~9)2e?H~5{*vE%$s=Faw(=B{_&wRYq?`kl;g4%oE%sC)H0 znIpeGf7U^b`kl;cTK=Z-y7RKXliBOOCC#o4%@_IK$(-$fC-dx?|GN5t`(HonCoew3 z^+Dg4<}A5<{Z}3yZtnbtDeJ%g$J^Hazga70pZMGl)_v-~s%9To)8CZoqylzX4@~*( z^ijDe_cc4m4u2o0uiXxBNvsm;1$j zhU<^lP2=^)$X$Q@kLdCEku6z@tbRL=vT+n`M>*d z%h!#$yz9m9JHa0D=aFa6Io0BAT8x?fTW#Nfu~A;mWZUXkc?oL@xtw+E%rdsU)VTiQ z{^>hz<-R+|Y=#?}yXDkyFeOxdbSURIk0y0 zyQ+D-!s8eI4vxn)JZ|ClZioH#Z63#@TW90={cc5eU1Ohp?yl^!O5Kz`e(8G=?*GU6 zz^Ac)>%JoI_#<6Ap3}#S<90vt<(&AYOWZMsP5k_H@*Tfef881;$F+EOJ$_*xn3usX zA}`EWoQ~)?=il`4ORM9TZN#$C|9;cI#Ov9{=HvI~Y+rV6XO9}U9G{<7y5pCj=<3R$ zXi08)UwLX~_21^laq8vxsnwJ|egTK2CJ%FaVIG(lZg0%jS|Y`jq-9PJKr$xm)c&!nnEsT9Xqp(Z7=pc3+|uZ;hwwy$DQ^Wx5VTwu%nMZ?7Ic& z$!@@46OTi9+`;1zEYitU2aRe(*&FNLfar@1Wzc@G!`Hb!Vnsi)}syOHAX?_5{)Ry(!>0<43bw3|{ z9mU;C=Jbl%_>ogt@KUap-pkimy=xlY@bxzy+tGORAO9!5Z`<1syKD7xkFQ^SiW7k`|KS?kJK`SV>}KXLI5F2;D8tM_JC7vq<8Jk|7xS&yzgYs)`2S^Uut ztZ!^TrFYHK&m6wSwPDTLJ0EHM_-p^R@!mUM-ssxU_}`!0`1KDR-_%sI^JS_|Nsa_Vyk9 zT=xO%|8+{`>{EMxu51((JM_G5q_ic;xc@&O~caP7blKU?C`z$5* zUGjhTrqq4@&pl^O*V5%(mn~koc-f+8(N^7h>DsvO(xb^;&+_-J+2rp()b>UHJNR{& z*S;2?leNvlJR6;NJTt@{PCiDnmaL$9 z63a2J)BimI*2lQ;zDq2}xK@8Z8`h^dJYzdqj&Xy&zgZvS!uu|<9OGJ-XF;lzZr)($7F|M2I^K-_nnwE`YImQk8^|3z29Wyn1e<7A*T!a7n z60DDL?h0FcK+ATr9OHU@-dP{xj+vT`V>!mP`Tk&ijN7Lw8^>~t<95RO6o+SQC(AL8 z?I~P8%QJrX zUl7lF+5T{xa{VmN__iBSp<&*e_5YKuU zUuyg5^W_;|`)wcZ>t#I0VYq&lXMEeEKHk^McC#PDc$QD%c^u-~!S$Ew|2AKq@vNWq zvfnulxZL``-vN(zczvs3ZuYo`-EkrBYqQL)c>44+D!Ss9R%AY>AMV0^9FqAWe|>z( z#QZVr<2X)xbK~EWy*}O(Umtg^mPOv#A?ueZO(9a zqp`>MQ@X$6`hyVEqVE}&S8GtoPDJ{Hd0<}H1m?>rVr}|94oA;CecdhJd7tZBo80{v zawg`1pVJ%L=aT2eWi1Ee-N)gKinr#}oA(m)VmY*N98O_PA&2F6HCtYubdBKl_I>xf z9DhvT)eYau^{?{pkA9=i=(pB4;P{B%qt|$xU+R2=Hv@-c~Zd3SJw0@5KC8@8h@~<;Ms2?b;^4ea`#M&$pA`+@D3u{XH7}#<94&_>FmB zUg81Z{$akrwvW(#ySA+Q%$(=eEZk_zX1O=~X8)%7yXG@Ir~PJSZ>X|=M@_cRX}ZSk z;C0`wGb(PZvd5^hqh3glW4p;sIEA%@9G2hJY}@$^*MHpJzU><1yK~H@<-GMV%TKn2 z`rJI*vhnWQMgP%<-LHcW>B;bXm*=fK4&>Ti=*HSicg$zg7hQ)}R2=TEM55=@K5YG+ z|2~AD*WL#Y)-Icv4;jbpZs4mq@!@?2)}Gda7M6FscbMOPaJ*-+cD(23xjsDH-DAKW z<4@`S$~)deEjr#Suh#L`yQ50*c#nBtUOKPw`Sp3m`X}#w1}rc3xWP5l#&I}R#J_Ui z{q8fsJTNZ}cOWm!7v87tD_}gC?lZu=*tYdCG&b|^?s}gA=7D*k2bnLtNq1j?wM#bY z4LgnoHyGdH9=y-M-}v!*yD!M&2V*-w;&Q*3v-tQSdtZ)wqiZVeh?eJ!e+F@G&bNo< zC4YOdN_M~R%Q6ql3*RsEMV_p4+g`@X%i&cwXR;geWO-kmTe9ElBJ+D)7j*p0#&2di z@|lHAnHL;P*6($_X6mhtXP^JEe6Q>9RkwZpqN=l!?{!uG;ALx$ zzUH5j?{yt`;D%Xu|LKugJ-^xLzSp((OI=_1^8H6Xe$UA@hxEAbb?r0rd+vK(A9dgB zn&!UOwa$I7>qm#}H+$nw#rL|xVY18k+OOR-Y8;pQnq7Aczt@$%&%p1m zxc7wY8|%;gURQXp0tjM)-|OLm<+AY?d4|1M+K6s3~hqFD(o7i6uX72AwT3%57s3-5F0 zoG6;Jf$w?CmYME;fctMWzQaB2yu+rq_zz;g1WfM#K<0A4n6vP@rMpYqz0o<9_F$3H z^B(ti3T%5Rl^4`v=N*{JtF`p{cJvZ%FU$k;!u2v=QT#i-$hpUUpBJ_K;i@lhc+cv$ zw?x0WZS|k_i(0x|zgXYc`5yaynPZ!HK4`4v{M_=HQ=;gZQ-1Z9!ISrXY`-QuAH-jo zwl3_Ma!zH}l%_KBVo|GH{iX6^HCY)>A@lXgGPk_+xow~Or=Plp<>+}-bHm@EjViDM zU$FdbZS~>r^X&JAGY(h~9Gmtue*RCdZu#45Hq0JxJ^a>p*NQiFE$ldNMMuYY5!vPC z^mRJI^40HN;BgC&V_1gAH{tiF_yKl8dV6wTVAPWTFSmcjar^K4bx!=+D!2XH#Ov5|0>;u(|MLCB$1!VXyI6M| z!+Gv;%s%d#wmr(5GW7=`s71#y<<}Ziw3Co|VIG*5&L1N$%vao;o_pN>@}XpZ8AWF# zZ0AEi_HF)ni9v1GG;AudJly^GUidzlFL00BK5Vl2`_@D~6-`le^J@2{0gML5tq+4Yf+Hl9@Zko|#|Bjj#re4W@ z{v00tY;Lxqw|w%G@o!@-&Yq{^Q&kmDiykO?py+|32Z|mjdZ6fmq6dl|D0-mifuaYB z9w>UC=z*dKiXJF>;Ca>qcCE6wUidsqdhvFP9w>UC=z*dKiXJF>py+|32Z|mjdZ6fm zq6dl|D0-mifuaYB9@vH+nAr71+}ls9%m4Oda({e(Km6qW`2Txi{5ya_f8Tu7gJQp*uXSa^R&Db4bsh5eC-39^Y~P9d+SVU|`~3_YoxM*iR~!Bwq$2)C zXm%}gqGlG4);@Rf+&`|u-+8EWuX6pok9cixKlUWhKe6wr*16{_$GA=YKDDgR7k9H6 z@wb2($8wD8^zWPXG481;**KPC+=#!gKI>B)o^gFF$GCx|xX(T7V_X#dA^zPH<5-Sy zoBaKFSs&w`nv#uUImXqz6YFDrj2m*jV!ut~`dE%}1OER1tWR-&a6g$*9LptfK7XuF zaaUyHd^yI|`hH=3jC*Rz6`6ivImQh$Zq&GGjjQ1MV>!n4`TVgyu5YNSHPbIF$2e{$ ztdDW-&q!w4$#RTiIo3x$Y>MLS{`lPfcz@@%_1F$sp5rYXul7FU`|JDijIVvr-=ErV z*Bn2k;#r>YZQnvX+re?fcCcN^`h9uE5BvLKvtGut9br7nGrrB=7o6?j_8pGPWc|K8 z~5b`J#G8~cyt8DHCh@xyudb!?G@hqRLpYd#m_g$&+ z*XPSKp8dmmnfJW)_q)Q}-}85oBmVxUtcUBRKj;CD3zoC_Q|@=Ze{@!~J?XS*o2MM) z%sJ>^<9~yeZvZ zVT9Gv?D{X>$+(5=O_tkq8Txbh=*QxItSA)2j+$G%oljG z&%?m%n4kQb=i^$QaDBen_xq3d=2?lK|L2&?@%wcPb@yNK_lMs+<;RszxJOXY7`U$+ z!#E<$7Q+1<>@`$oHK&h$Yr2q^Y}B^Xz%P)GfhQ)OmnOG*Zg;#tJh#76Ei32#@U|V+ z?DficyfELjKRqPoY`qr*+ub&7hfm&*?U3{Bv>n>m_ORDq zqm>m;xJRmzF`hod8zWu3-iFdZ2A?p7v>A`mWO>dsxIR-E-!blOXp=#iGE~W zN-WRKOQ*|=^>sOu<;AAF`Zve5OpRWNB5n+I`nx0Gg_^7K^D^`SU3){hbfgg9<$E#D@i{<68n4hY4C0xJQ z{cS$){mwk_{x`F0y%`s4ElyIY)1 zHa_;>%l*AgU*BWC9do;vcdb}i_vYEBN6Qv=tf)I>@sf^oJ=^-c<%D?)JKoi?q-*)S z3ol=?q+{jGc?%b;Trls_%NHzMaryF&h4Z2_7O%Xhvt!x(*-JXC3G=%yyky?CuC|CT zdZ6fmJ){R#F6~;`wPNOxP7KAD*!Pf}7H^~c9(aw7{1abuqGrxXEytd10y)}*ajF;Ddd96FV<{nd(elEiEo@JP`o#RO7ED_Wr+#UsLRH z>1H07m+l|noSFHWc#C#!gq<(j!*XcjIGk|RFZ;JDY?N~vx*2&P@9H_vnVARXh1(nR zwX54X-ui8OvB%hX$=(AmotK(hCTCul2j+$Szm0o3o7TP>M%}WH1fqAlb8C(;jj9iPuyd64?OOt zo^*}1an#$1ztNa(d-^%=f!F)C9Z-@Y20eJTH2n z=z*dKiXJF>py+|32Z|mjdZ6fmq6dl|D0-mifuaYB9w>UC=z(kx*tN!m*_R3`dZ6fm zq6dl|D0-mifuaYB9w>UC=z*dKiXJF>py+|32Z|mjdZ6fmq6bR$z{IX6mUj<4elNM< zA>8AI-+vu>Jnx<_>)dzmZHm9ge_RxumS!v(p-J!o>ebi2I7yf6>UOW!c^#C&08&%b-n)Le;sowUBc#64&(z__n}Yk6L& z+2?;_KXP6wiOdW0z`P94!1ls?A%3~@{Xec(UB>rr5Rd(Atb4?`Nci5}WGa1cpw0^1 zJ!b5hv2?8ZxAq=1y;mb2oR`y%?NNq#VIG*5&L^?GFke_#c+Z)T$8HhteNxsmYGn`W^G0GrR{)@A0?? z4ew18-mjhaE$6*yQdLIZtOA|tX49wRFFDvN)}q0gxTaS>@0;`fujXBQ zc5(jRGsBCs_n=`M&jE7ddu|D?F|7y~?Je~$-%ot)y8Q+h>#kjMo_p-x%NXfb*c531jO|anFXKUrqep4LxoEG7roP8^C-; zQPbKey4qd4u&H%++YcA5ufOrb3FGzbzw9SoyEeA_gSyL*ZnDoj-2Gp#y20ILsde_Z z9)9@bD5`7rw_K{Mj-u)smy;vovgQ3_^;-^Y9EX$Dlzu&|dD9nm%sn+af9><~y@}`L zN%tnWy?x(3PhZmw-yeB8pX_GyRj$4E{^&RQjDF+aQKI*FZ!P{^2L2s|@b6pjUMt;h zgS7jSS5+Ned3C%d`+Ev*iS+fjFezsHuJZ|iWZ z_uEhFzfXKS>Tv^$d0<}H9_9;tv+K*Jb*;8%itRgMeu*19yeH5_KKKZ~LDFvrxH2|z zIf(xvFSodhCwBj1cVBXM|Kr0e7e+5}kMXDUIL^B-wbgW5sv6_;G%x_a4P1!4aGox+ zHP45ChkP_t-dfiEhq(^h&d+xJ$L;M=x4?HNi{#E-$L*F=+iP&|KF){#4u4-Kx~!w_ z+>0(>vV2?qKwVCc)c*XQ*k{(yGu(2n?^Ujot)HjtjmML|9dSPT-5s(#ALg9Oc;A3u9PoYt?;o&bJl$U}3HYS}*9LrG!1%6* z`uAnQ@|Oqv7XiN_;DZCM3;2+LUm5VB0lzBXR|kApz=sE1AMjrW{F;DY8}RD_J|f^F z1AcwLM`gI!K8o!lyZuhC?Std9`#tMozmsdO&GO*>S?>E#mOHv)p$|mTNzl z<-zl_JaA){yH{s<=*}$Hzd6e_-^_CFHDK;_P1i}Z^hW(im|^HV}C1#PsG^Yim|^HV}C2g{#K0rtr+`TG4{7&>~F=` z--@xn6=Q!Z#{O1}{jC`LTQT;xV(f3l@QE1vTQT;xV(f3l*x!n=zZGMDE5`m-jQy<` z`&%*gw_@yX#n|79vA-2#e=ElRR*e0v_zl7M$KMaq@|nT%V*)-l;5P<*T)+(hA0O}u z0iPJ~Ndcc6@T`Cv18xeqIpEm=&k49C;JF#5FM0e==J^7d=Nra$4$1QeF6a3MdGIm( zUGaqd-xp8V{~hv#{of%^_=zBX#z~p|*Wiz{%X$98`0jo2_t3~Zf1*#h|D#XE@TnL+ z6~m`u_*4v^is4f+d@6=d#qg;ZJ{7~KV)#@HpNipAF?=e9PsQ-57(Nxlr(*b244;bO zQ!#uhhEK)tsTe*L!>3~SR1BYr;ZreuDuz$R@TnL+6~m`u_*4v^is4f+d@6=d#qg;Z zJ{7~KV)#@HpNipAF?=e9PsQ-57(Nxlr(*b244;bOQ!#uhhEK)tsTe*L!>3~SR1BYr z;ZreuDuz$R@TnL+6~m`u_*5Lle&z8r{UU~6#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc> z7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)%vU z=k$vhei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH z_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%Uhkt{#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH z_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zwq+|`b7-Ch~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PAD0kECD3@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2 zzlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJ5yLNH_(crA@cRw)ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TL{iihdEpFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu<8?_bg{V)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU-*4) z`b7-Ch~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLd zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PAD$A40!~;TJLdB8FeY@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2 zzlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJY4yK1qhG}Eix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLOy7slU57Q-)M_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@Qe6}Aph`-mcuV%_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix__4?^o#;G5jKiU&Qc> z7=97MFJkyb48Mrs7cu-IhF`?+i};1{_!7e}V)#W2zlh-%G5jKiU&Qc>7=97MFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEywh#>#)i7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ;qT$;7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!NwQ z2K^$2U&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkzG_v@iw#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH z_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zwrKF^otmN5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc> z7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XFBPmq2Q!!Kg^MGU`);TJLd zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97M zFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLd!uylbFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF^HUWBNr5zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&QbW@1IV;h~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH z_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4e&OF^ zpkKuBix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLd zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97M zFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU|2@4L`1V)#W2zlh-%G5jKiU&Qc>7=97M zFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU-5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLP1`*ZY*7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc> z7=97MFJkyb48Mrs7ydm<`b7-Ch~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc> z7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEy$K5j+)`%^Le zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97M zFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLP1d$>0G?C))h;TJLdB8FeY@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48MqxAO3w}=0}YD zh>;&L@*_rm#K?~r`4J;OV&q4R{D_esG4dlue#FR+82J$+KVsxZjQog^A2ISHMt;P| zj~Mw8BR^u~M-2aq;eRpwFNXic@V^-O=HH)YzQxG582J_>-(uujjC_lcZ!z*MM!vzZW+K z`DqFm`+Jq29W0*{a7(~*13o3-Qv+@d__Tme5BQ9L&kXpifZr7Gn*%;O;I{;PPQd2| z41aF=&GHB9E2D`16vLll_)`pjis4T&{3(V%#qg&X{uINXV)#=Ge~RHxG5jfpKgIB; z82%K)pJMn^41bE@Pci%{hCjvdrx^Ye!=GaKQw)EK;ZHIADTY7A@TVC56vLll_)`pj zis4T&{3(V%#qg&X{uINXV)#=Ge~RHxG5jfpKgIB;82%K)pJMn^41bE@Pci%{hCjvd zrx^Ye!=GaKQw)EK;ZHIADTY7A@TVC56vLll_)`pjis4T&{3(V%#qg&X{uINXV)#=G ze~RHxG5jfpKgIB;82%K)pJMn^d|vER@mm9aTfpZB+!pX(1^o7a|2p7#0bdaCI|7~` zaC^Ym9}FCGX=Z;Q#{NKz{ec+!12OgoV(bsZ*dK_oKM-SoAjbYcjQxQa`vWod2V(3G z#MmE*u|E)Fe;~&GK#cu?82bY;_6K6@55(9Xh_OEqV}BsV{y>cVff)M(G4=;y><`4) zABeF(5MzHJ#{NKz{ec+!12OgoV(bsZ*dK_oKM-SoAjbYcjQxQa`vWod2V(3G#MmE* zu|E)Fe;~&GK#cu?82bY;_6K6@55(9Xh_OEqV}BsV{y>cVff)M(G4=;y><`4)ABeF( z5MzHJ#{NKz{ec+!12OgoV(bsZ*dK_oKM-SoAjbYcjQxQa`vWod2V(3G#MmE*u|E)F ze;~&GK#cu?82bY;_6K6@55(9Xh_OEqV}BsV{y>cVff)M(G4=;y><`4)ABeF(5MzHZ z_}Gb={ec+!12OgoV(bsZ*dK_oKM-SoAjbYcjQxSwx9{noeF^*aCG6Xmuy0?&zI_S% z_9g7wm#}YN!oGb8`}X}JXkWs`x5r;OW3zBVc))leftvj?Mv9VFJa%lCxZ4R?Aw>HZ(qW`eF^*aCG6Xmuy0?& zzI_S%_9g7wH{+!2_K~n}U&6k93H$aX?Aw>HZ(qW`eF^*aCG6Xmuy5awgZ@j{w=ZGe zzJz`I687y&*taiX-@b%>`x5r;OBn5|J>%X?|B2B)G1@0a`^0FU80{0IePXmvjP{9f zyeY=`4uC-V&qqh z{ECrZG4d-$e#OYI80QmWoKKM5rEhn>RuR?y0@v%v1I-_f$3si=dCmRq#et*W825Lj zyI5}5%Q^KPkJoFLzCK<)vJCT@cVa&5UuSunf3qrzPIL3$yX%7$6+=~bS*1};RPFv9 zIOaR+EU&FE*$}TknSbu~n7ePo+!f7Co0j&*%lkSpw|4iqYFm9=m2Y?3&vW8?-qnK2 z9&N^aMZlR=jRJc=HXUgHwBO)jhnkal)YBNnk0`2)s;a7^eX944hN=#V9~LnF#QwT4 zr>NCrN3gET;>kEYb@n|P_vfaj$Kw2Oo-VUB&qsdyskpwuEtr>E2lK)_FfTQqMqZdN z)OYZlDEjCI)$O?F@t8m2UcAjO_^J&bH{FU^w6C9&x!k|ZnafMmbj>sy&(oq8M^W`u zSL4?z?7<>q&#nFwU0EB);bgU(5lxBw&~P>1m?^dCR^(-PKJwCezR%A)kBR%W=0n$E zyx(+BoWE{A57!fN_tVJ7$g`NY{_eK8zP3ML9+oFtUS_!WvdORiIk&*Np=K%C!*XqN zo{Q@vzwNZS=g(}JfA)FvS9WzRxorN*6$_SKc5&B=r7SScd|Ttso8bDw=IrlYc;A*S zTR!OK9e!bTbXfe1x$`f_Gxihvh5b~&4E@CZ+w|74`>E@~OFAxEnXY;4=V3ohG=A>F z#S>WD=(botjXZ~b8cr5Zjh~sf!-@UGeqlegUWIYZ{_DPP?0)K8eA&vb74HtKFUes) zO*FoBg6j(#V*T`_?9bat0>*iT#rFllLV1uc2$~ezM-_n83CW_R~b;&vNUlJI~Zu zA`#=fY~$%&|A&71S+HLUFs>=-C*LpZC$5J5x9Nl9_tO;}ix+j4lN?uhUO!DF{``1d zTi;XGPw(*k#P>=sWp=!Nq4m?*?m73XTio-!{@jMt#cQ(l^tg(7e8c0NO`CAM!{Z<{ z%Z_*I*5kSTYuvWMo~4g>9pv48e~~rLmn^t!<@~PY9V-^N9TXRjJKxs$^STx-TGCNxyYr=83p=7K#$Ds+0>jR` zcI-SOS#)^vEPTT8%kj$b%kwafYs4KoCu+ZWqv~+H_Ej<8;a8el+G|t*Hr&SKYrhi@jG*BZdxWO86l{>z&@w6oI5RTX51_uAIpV%+#rr3_1yB2p`F>~Skr%vrryR@J^lTkF`g=tjzK?V z1mJ6CKe1ofPn~~-eq#UCw2#wI7hS&MvaQ;0_TgCrvH!Zy8mFI@Em+F)@=+_vd12Ienqd5CD?7@)bdj@mywvRb=~YPy z^b_|j$;<8u`-%O+e(L=w`icG5+dED_EnIxr@+Aw(K2aXkPZNx9nb_*mZ#jAXm%g9) zLbdnPSm(*?7xvSpZuArTui?6J`suRH1q&B1Tf}vaHy_nc6O2E1Vynw-&c~mHpRP)l zVm#sBEbfIhMq7_}2FIzZ&@zMp0 z%9ND)Y3t%=Cu^-c&DL7pUN-yQJ4*D^-q~U?v7gv4?5ED_{dVWaRqM)9{gfOh&hJ{W zxMSJM1vak6ZMOPp>*C!&!gc7nH&0-#*$y}>)lasB*YRGEEfy2|iT#rFlRqzD{|#PM zs-OIR-7YXqz{TpPt&5MZPi>>jU*h}ez~uM|9aJ+`Kly%PKd~tLZ*V~w{dAcdOz&De z?pU(AbNgum@o_&jFI%wW-ItZOLcXEYeBc>)T*u>BxL2wSpW1k`>qb1!=6N@l^L(5< zS?6}0VLx|(Sn9m{^2!@4-;`>+arz9U_b!}wr;2Qsr)|fcj?dQ`Fdwhd*1hpLx8l2yDeOfZ=wU12gSrbL}!1RLep1B&&>~rFH>f!wRU%H^txkhE9 zsL@{Y%j4Ns_M7VB^%-+|*|%L;w+$xc-Sai}8q2KN?{DwF@Pth#TYO&o|M{vFjh~zv zSsUV*7exCs9=Ya%HLeY7SjVrHefWOYhFQP5cz#kZm(_gf^u~K$^vhYEdpd6V+^lcb z?Yrg|&)&AyUVGiY9X0Eimws~ffz|y@;d}T--BGSx*{Q0x_T=x^-TigGI`z5pPW<7@ z!4t_gXMgd#z1 z=L#zQH&$F{_(=qUgw@j(P(ZOkjSkD{JdYPa~J&drbA+nAa|u7wAG9Lq7T-nWzWDGtxLK9*x#!%DnA*2lOg`ipA&o*Ls=j&W`8@p%gR zXVtW99Lq6olP}Nuw7xszp}_UA9OJs*jrFlU#??>F#<3jZI{o`&eTu^~u8-vy*LMZh z$NCtzYFc)EEXTM(|NdAX<65U=<5-SyLw+9jTEEUi4jBi+vc-G79HXNs1 zKg%<|`x}U7yt}h!kNEYoUgj;_-uV7m zp79M2`u6*Fu>VTMvpnMmeg0T4`>#|y%QL>=5x;)l4sN&McF*>+Jmb54{#h^M*$><< z8PD>JZ}9nNy=-^M_51RS?|#_l&$omAD3yPfXZ)a#V>`HB))Tg$y7 z<5`~ZJdR+!?7vd+EYEn>&wAPJy!d`sn8z#p9{1oeIDTP0Y(M>1%4b%7mAkO|3U~Bi zM*`EP^-RMrNuy}X79Jf(QT>a)6d(U^-g_6m_cCyI&iAm{h}7K1O^*{j<9Hn;H@@k! zEePfJxHku!syOGVy&s$6?{P;K>%PaG%yIr<%k@2Od(ZYLZ%X%97=c>!J?`>r4Qtvt z%)BrU%nR4fe8s$Z>0EanvX;xDCx7kp5;b+XKJW4U9v^VILiUaGttGCx4t@aZqHB z@hA4zb#5KjU*UvWG+N86HLPXlG5x_jFfVKY^A&T??XE9pZ{)K7+j9GyKX2K%!T1!{ z7w7x__<*0=Yc|mzbA#nrn*3|mW}2>XA3E!MW#?C1S8i^toG4_|@R(x3J}iDC!^ma(o@aUZ?-)!{J}Uhx8=R zCwM$cFVd6gst@;uSMaNU+*BVr`laM}S9+(&A zmH9$*=DEBqU$3Sae`kr$qCJabAE*&}j!S=+d`bA;u^eRtdaUh&K+*Hzdfu4c@C zY)shpQYtTDEg_Ft`7T&!d1-a)r3ZiJo|n-LNnej{@|MgYu+`u13eo5Ed+VR!cY2@K z3wYkn>mIz0!S$Txa%;!CpK*z46GCkqz-HZKx!MqZur1o1On@TK? z{l0fq+VB0*1(nyk2ja&1*YaYIHGUk2WpM^#e$Po-Sa=dJ^TIqZFKim~6?4y*-G0_h zJwJ@+*Zh4HZ!a%dxtHH=;-w}3;r5c(&wD?1=t=yH)_)M|u45cm`Ho6^l&msY!0n|} zUcy>JPAZxtPb@D3?tRmP|K-|M&WOtUE>-xJ4)!nXhQV_Y#j6c>KWc3Glcgyk5`a2p(6kR=cKgs`D<7A1W#;tMiT@h7QDiQ#c>^1ory_ z&*tp^S$S$sA2NbcZ=&mTWD^<+6!Z{E`i+vwaBA3wyg?)ZW8+~bGJ z>VqPCj6bFOEARLLwdnYvyjsU!?~W?Lyf6>U%cctCh55qz?RepojcUvEIa^kNdHi7K zA+L4E05f#)H{>E&@D{e$BN$2vdkk6u@GeRPnoPen&Rv%J{jIOldd4i2Y^=x1)J z-8aR}c7us|VIG*5&KDss%opCu40qh{$a=o5pICLE0q^6XFYzNo0snB`sm`I zU>-6rcKpEOlytd@sN11_-|fDcoL)TXo-;4Z1M@-;GGA!;F)lAlQ`?LC-Li4d$2Q#I z3h;N!AN9v!xBGX??S;(cL1!Q@u3xpi+#7w&{cibVzP_M*2F>~QD0N)N<89p4EE75@ zfq7vbm=`vd`65r&xot0F<)yMZd(O zs;~KSJ#OwFyoTkMBr|(GoJze`>h<#Cx1#;2ihCNrv*P~d)C=*`Ef3Bg{o0m4Z3xS` zZpe9`qe~U9?D!toaN`9{;abXl4SCGw^5e&TI~fC~?tgNyJ@mU}PTHyI*=ODLm|4d) zHhlHT)xUn|rqxxy`lUZCwR-tT1q4scoA$kS9@jtLzSmym`Xl~cd(GtdUVD(91WSFd z-SXG(O7Z-U=YtI7c_Ke24NlyRH%;NcXN)Pb$v3<$!sQmAy+~J2S?Y_U~?=#QeS6RL3>D+U+{Z0(m zx(aPw>8bWI{C;KVy_gSv(|_;$0?Y@0fzMStqjjUNGrEfSzEr3CFuRP&@?Yo5asB+g z$e~+sSf_Yw-Qd z`WR=wqq66WV>!kR`ro;+KE~PasM2vPm&EygVSS9d)TfE-8}#KE*ZnR(9{hS0_tMPz zSdMYMzC7z=Toj!hKjr#Zj&XgyUsxaGR!z&su^i)i{qM_IALHB={#f0~`g}RY4g37D zKE|z@mW^XM#&utXe&Ko-yUdBby-R@9Tzq?~O z#tr!Vu|CGFnwE`YImXcgtdDUmQ?q$sImWRZ>m#>J)%xsrUi1rpCo$-MugUV5!vpAl*30d(WdHl}j2}GL$NPF2Uuyjm+%VPKj_Od zzM&2Ate5d@N7#QX&-jt^e7vuh{YU?V@hqRj`}MP4#+B;75nn!upXd9}w}b6xJ)_p| z%QL>=uYJ6)m*Xe&7WVK9`;{9<_1KZ(!U26Py z`|^w*d>h)&db$2m?Pqz$cfZ5O`+C`bqde^W$?}YE@cqVm8CR_3hp-+!zp96v12crIr<*#5luepi^sv%JnT@>?9=vL0?f+<%nXA6WVH@5b~y zyPC}J>^8j&zq8}K_8ENMKQeuS*Li##uP5Zj7r(P(8h7~IeAMGkrkDrjg)3&BV_y4I z3to5E&1{N)XZK{2yVG-X@jJV?N4DEPmKWEt5x2KT-1G39H*aN`FB#_)uzLI5>+}Wv z(fb?!yApq%TN8b=egBy*ZOT7hf`Qn$YJ?i&9tE&HAN@w3(QggU zz;E;(y~g7^9%u2mE8UDa?i$lu+zVfHpEvBkf6LVQR;ioPej9!Z{vIUfz5BvzZPCR1 z#yDUK^+(^Tut!|Yxc^xF|KlDuj>8GH=Ui+cm{#C(Bz zTwZK)^PXsJ)YH@y^}KRT)bt&5(702zbB#@Td))lr?Nv{iTWJr(jrDK8TX=`7zf@kr zT0$PH?p?9WwwFFPgm|3&OV@~UMwETuV)WG0m={~_etUF%6L|%uDiyKsqgayP?ov@Z z|Ml^dZTaeV&EokN&&P)Tfb%h)r-h%l@N=8+^NS9*LOV}C&CTuiJrxx%tNy+p0qOIx zUiU$y{he>lJO8R7{(EYD@56k&o}!l-$L+uNik$fHcWUkLYeD_I{xtU54s!3qCj3s# zV(oWoem?4ZiFQ8rGWQ!bdyGG&`|HA-WT6(FkCj*J`0L$KC72iHfq5BRio7siJ8J#g zt6s~CJudR&IIOoK`l@?r_xqh1^T52+T!XwYU*Y?lY@E)EK+E`RKfucM5e_lDE>ul@U$ zgV#l=V}NW8WyLome(T!*^?yFN*|nkh(=WPYRQpf7`_-fVPR7fg`_qQIpF4Fu+j-%t zKh62qEvL>V7xP`)1BXog+^9U3`&!;Ow6Vc=^wt;rIPPR+^8fzI=+N-*uULun_u@xK?D$u#{r0d!lJIwG>1zb}E!lB@ zed_Ko{_nUBB+IB|H`CPhk|D4BBjN|@#?Xcd?lz(HiXX8}e9#2I7}NKxHY-Ca&~S5Z~HO%__Cak3|_Xj~@hUq|Eei<)HI zU<8b#!31LxNi@F?=BEkCPlJj6lF=CXf4}G4Z@pKqs=BLZriU4MZ|2qA&fU&A_uO;O zz3=vB&!+X?4GUTiO7FDwpsgjb9+aDy3;a7Zt_KUto@Q@{hIfb(zB;W3SrR$SsTVDv z)D9ILfhf^MbP!!eYfcx@%bLP_&!TIZa}!RhG{edLhV#3$TlZyjNvB*LNZ)&Q0d_L{ zyh4{kQ_9YUUykDkE zdPlnO-japb`R1kzH`I?Ux`+;<%lfTO7tt%G%k%Dz*@txTaFQ+`iUC@D8ZTYaJJRLD zpv#9_N|`$_H(h90JGST|I*2YSf8OaLdO0>?I(T>$=(0LNr&gT3D+H7K+1#J|WGh$* zxgM6-pTqaIyJ3ym9qs7|-yX^Oy3vIt+0I|c=Hd1-j+Pk7G0{PEk=`JBMckL0y>ZJQ ze(*J6e(|vA@^MV4_ux(9{bLC85nUKgrdwjzpK~2=>!uf5WVG}o9C2HY5?fc-p4jPk zHzG-sZglaIU|o2Xx^qsWUX*wsVb(!|%^qo(#654712xI1QRDSBIvnRYI%)u@DbK|}q+ZEjVuk(3s z>$UDC%j@LV_*XuS|MmF}`PCzTItnnf`h%UFk%;_R}c}u8I9=+!!*~Yo)60gUOmGhFKgXpq<(CH$2IbAqj zlIJBEK9IpbU8}TOM3g}8!w!Ajvf7S7EKi$L>K7|qL=r3 z?(>qIN4Vbl#o$tJ;iGtlm5%iSQt);^FA3(JJ>i!C)$7CZyU8&xDKrQLF0ABUTX6W` zG{1-rqKj$}y*xY%xy6U>>V5c1X&{Q;vLTv1pL6!S&j7_co=)?4=k?gY@ui6Gp+D*M z*x@Pl(A(9m1k#1;G3nXI?s_c7e5bzpdThy0&3a7hFRjPaXRXupotnN|(>hGw=?eZ* zj1|h6mmz}RF)Uwx@sf_;ukBrSH_uDnAKV9vKF>{$xU2HIxf=h8xL2@w&)`Wf zwDVef!~KJ4q-@`|eW+HdHcI0o(a1UHowp_p&_nn&fJxJ2SGfOd>rA*;?z(Vq&8)jy z!#ynPA8NgiMb#bZJ%g%W_my3ry4Ozi$R(exLO^iJ_h87U@&vEHQmuS~Q@+*V{yCMW zeCc}z1*d%XhkM^tUYyT;s!wprw>Q+M@{|vMg>o7F$|pGG+ZyUqdCGU&39b1Ar+h1Q zUtp+L`L-PY4T{cYeS%ZI+Z)agDlg9GJfwCCPWe`bcB(w(gKliBr+k7_z6V45RG#u} zIeylTTq&R6ly5ZLPpI;g@5f79>l2*v?GgRj@UpT6FM?A(jT4op`ffX6WefcTr+k7_ zc?$n{X-vP>h};{-pYBmQ5bh5Xy!bTDcf=3#3tsux>mIUDuJWh(Ncjb?{0FXfIiPY? zulQ5#QhvcJ|N3p7U*#%a*ZKpz@=u4b%2ob0z6|{ryz(Cy5A}y~#Fy#u*KB`)SN^>f z&#!XDpJ_Rx{DN2h^}_*wpVPPQ$DSSI_Cc=xQ9;qtM4Pug_%b-O>_|*L>IM6^s?{+x`*zbO&3;8>CN~~Dbz$=3K*%RP?VSHG+PP-mwb|@ka@)>nBSuUP4^Y_aynaQ~Bvq(&72aKho(O=d^Qayk&MSzb7S42gyUp zKgq-WOZ@LuNKQ%*lwK&kGOgc{cX)r%tAP8jV|*`Ja{00wSty>QKDG5neounj2mjmU z;q+4$CJ&WQ<8J*)9rCB|N!a(YFmLNSnKV{f!P92C90pZNQ| zv%hWnLNgpa&BE_N#3%6b+{jG8%ex(@x&B}{nI4kmnEvosgpz;HcjwagM57(>tW0t# z^ZAl4oyQ9jqGRu#1kpisQGZ1*g^yNO^Gi3nT)u2$3w6`sqorS?ztMV6g2G=y1IbyP z?nyZCdw zSo*uKx#2VKJH6Q7cgeR}?jHEtuU0;X^7=1De&+dKfFt|`DC@V8pLrPmB+6x3&k6b8 zd&`!Mm6;FkJMfji8DRd8z2n;(?)}{}@BH7pUv?+jaOcD;ZtFkqBk$Pom~%eKHf;F4 zPmF!$<>&uN|Ev1HbqCsDZDP5%yr!}dZP>Wsp*uHxwDI!(^S*o;>aYLt_qM<4j(6Yi z!%Kc}@=5*C?5+#GHhS7UuYJwyHvjBn-hcP5A76ggvI|e!^3LmCclVdS^1jV)`AK$9 z0&#gXJSY6+(+AS+=rxXfl>S@1>CFD} zH=ocpt^`Z{kM|@x&M&)Jvai$&_}m5roqV!(id)x%2mada>2kMzC#(nm z$6YU>`>)m=%BT5yx?}#g1zPAF*dg3wehc$rJt(*1dT`agKE8P!cxX%Dqap`dhiC1a>7DHBTaF)IvJP*D!a78ekGZBN zAEzIdl#EM3L$ONW`h_ayM+)u&N8_qawOG(-^Icckk*`e+D*pyrj==fJvrH#_Q~u zY=7GOkgc!Vp1N$ur(yEr+HcviiTCO( z?V%lndjN2=A$%qZiRZTXZ?ylk{mpjvdpG*6`9<>$qU_N;q_u?3?r5(`dryL=``-|b z+GBdmV}87}(;m~VPh4($>`nJSe7?Ea@q?rNnzoy_ecs-G>{B{6sxKbP!!cSJBJr z^+qm?1qE@SFs?b!hn{C#=_E`>_ zLQ>kKG9N`j(M5C+UDQO;%fb(Q*2l-br))X!=BI91adu(L`@VM3=I6cfKIjAUKN>Hc z=+fa^Oq@~q@zRY;`OaT9Ay|Glx}-}|32bBBl7!rcjEm;yb2SJ;q1vU;23y(M?^Hg#R}hEHNVCB#>M_ER`^CM zoq7AVmtVW;(n85T#!4sl7=8`l(k!|^d~>rpe3P~JmtD`?^|n9y9KU5<@dLM&j{ZM) z(^Vbnw^*uQ->j?%-`1q-QJCX@6#{}&zOCVJ?W#P%r@zG#obnwA^{G7NOMi%-qPS9!`8MbB8yIa2uqr+g~{om8Ik-F8B2KEWxU=&JIR@4jWN z`2?qYf>U`4-xn5CY$t7Q;uoEL-y3Xjf){?$_-*D7@Xh>F&VMRb{q34Rz&G<(L;g^% z>QDE-S$}|6{^@$iAIeqz-SP{*nZFV8hjN8Kl_R{U{^&t3w-<6( ztn~HU{on1d4pSo%F55i|A+CJVOFQQODfsq6m^)U!y$~Hl7m-f%vherDE`{Y}pVFcS z^zB77ko@*Sb9J|GFO=Ra$2^_(hGtJ#if=E3%U1Z#q4j}})2Z>T4GSqPUCNOQbG!_o zI*qr#fWI@|THE9+fY!KVNb*DSLh?g;lH^KS{z@LE9*xcpf8gN4Zt5y7l-Lf`d#R~{j!>{E*8?3ym;0aP^cB6lIXA(sP`xW|8p5~C-or4@ zsC*+NEM4xNuZOVq9TZl2NS0%EpjTr6#AheJ5iMKJS0LTpA3!XSE~Fv(IQ@7j@!$OI zt<-cWM=mV7hz_EQ##_s{G5eg;!CUwe*yq~mvZMoE2+#9>e7dA}u+M!XTDttt@p`^q ze!J1d<@&LA23&LyU4#SC%fsE3X+FL1ze6tU z_xmWn8(n^|w6)fBcwsdyJ~YS6)o0^Ix-d^YfGT^LZ|%6tNdp}lSV+XS-hIQJs^s&% zjSRi*t#7q+t;|P%GJg^}^Jf^yFpyy&!$5|C3@%IP4l{$aDiv`i7OQ3`3viIpu7tzb> zUxn`vK6H277KHZ=-otS69*SQN_Dc297M$upN z7X3$05A<&tpQmq*qE*fBPhS6fr*FRT75`!3B>ksCdqnRv{gs|-c1QY8N4ulx6kw;I z=+80ydmRA0l;fi_LRxR7b|~lwMTst=gXki8D|&fzc&GX=+c;GC;X6J29z^I)^~Ym; z@Oig8ZFj0GJtWI9x}@(^f5P(jME|Y9B*+df=N7)*zH`w1Fv~k~cZUKW;V98XbP!$C zEYVBhqt(3?yf7DCPF&Xd{Yg4}wDfDm@3h{juCVS@-?jTs$-k-RH{0T#{)E;$)nELz zE9`#qgS}HdIxV-4cUkLB_1)o4_4DVsQ~fg^zHney?ho#K!$1ES+Bn<)(KkJ%|GpnS zaL0L{@H^E%IQjnm-~8tF8=lthcdGCIKfnK(zj*u3{$IbQ^-lG|;I;v@Vc?gqef@@y ze)f$1t8aViXCS*jarcRzx#QI@xnRTnzr;J@_kFy6W#MxtefWz5fBeP+`~LjD-nH*v zUVPog|2*f8eb>M8Uk9GIV)sA_aar&Y!oa?l|C@c=l&rqjIPy{YPIdBz%6e<=UtS=; z+{L<6UF(PJPW9P--YXSF$HtxN&HIbOeMP#zNc^%l+-sz;-0j=0EftEDL%PD~H7G2t z`)&>Q@T}Mw{&x6V{Qi;syWM>-{0;e)|G7B#7pZ>Tn{y!C*P?!>UFr?15Ggq2+Y|0D zQh9Mc-X`Mr9It{aIOSVC;r&*5gyoaIzesS(w<6p_r1CshYy(g`1*d%1hx$~W@}=)D z5}fjlhWb>V@}=)D5}fiq80u4balREx=~p`ir+oL%I9^nq@z^6v{P`(C%#pA%6HAO)_j6fKEbIxg>O3{?jP@G+8V}#?#J2x z`#vrNFZ!qXhxlQB!7Kl+H+X)Pt9)s?D!<^Bf5q)#e1>+Y{xp4+U+~JmHQX;Cb{s6E1yFysys{S

    r2K+!<`4Z>xyskA{rdyF^6z?mpns@eco%<*FIB(bm4C%sL;g_i z>L4Gw)TkA^CCp_gsERu1M~t<+$W>vX_(} ze0JbH@x)nZO1_#%?r&W`^#$AClDp^UTyCshx-j{neB#rN`Dfo0_*DB@;#-BSxm|zM zAK!msUhHp0a{V4SW?qWFVzNBq-!|thdcEJI*IIsSGrW{|f2;RWTgy38A;}NXL3C05 zq8F|}-xo!{jQtHhTQ^ld`=ovUdD$;D!ye!ID?Dj`gJJ&NkCz!3>9BQE^oy_GO4rx= zt2QFQhgUZ(UjdqI^KehUET49C@^Sh}my`~t;UDQR>GA*?q4D+f(HR)HGT2lLT=fs$_uE8U@*zmRv)z^j*W9G_rv@Oa!v_^Ks* zn=oBH?>*l6_;rBjbYZENlDt2#mr}b{x9ABPFQS9!qVXnr;nc!Ccrjj1fO`Vmbod~f zI(zYD5#A4d{^y<_U48fEUJ8(W5YKy%jWp>*7vH~y0P0D4A4KJcIg98bI*2Z+M)dOV zPK+0OpkMK64Rc&@zUO$LOFZ#WJi|(lum(X=zv~0hCja{$`!|&=hy6ewc<=EG;cAxO zZM>vQN{8cWj}9N{G5|bkp86X!3&DAx74t$I-2m#N-)J~X6dcxvc-@T>rC&(j(7uTD z5a}7R%iJIA+G+a|8@C-Y{xOgTJZH6Z={3tvWubVI`o_xL%kJjik&wIozg$na|M-Qi zr<70QbnmiG`F|O5laJO?oIx=C&Ptiei*?L^iHv*l#H8)Ux-W9iu;s3dt;r)334lm{74+GPG0e(Kx zH}3afGd%=@ zh%Op$qSujW&B52gvBI|-U5?fBVxoiSA`FRMQFPMhqUhC|qiFX&yaS$2eS`6)J2dqQ zju(!bok5;R-(XndsdDnKynwIi8&_|>+{=riq`nbFzp%8|vBI%B7hTdNrNgTKXmL4S zRsfHhpT2^IAvo_7P(Cl*(FU;h*>7q2+t+dX(4!8WB7Uj>Qofsk9O9?_?>@yP9S&cb z25iS}6fAv3`itt4UL!q4dW-hgWH%A~%OP86FOmMTV#RZochX<>u628f+yjsC`R&24 zp56tIs=-~!W98Gh-}Sf-`pdoxTJ@D%UfUXOExIk#x7?#lf3dvKU*vYwU!Jr4X%XM~ zpCrCI=`UVNtiSYD>iqRC7KG>`I*2YSpL&MTRrIp@d9Q!;@ZE7+aIb#|C+#KwlV;kG zLHGK1NjH1RW5JI}d&y6h{CV_~F6G7Ta2_Tf|Fq4MqJ!w7@g{m zdFcLo@NU_^@5+1dhH;a`RJ&i}MS7<}bhnpabUkPJkCyOlFDo6R@zRYhUJ3{op596o z^pSTpUPK4cMJ*A%Jltv@>1Ho^3Ghfg<%?n7k^aIkwtur?=b0_~$Mvtf$>YP{?^9Uyzvhqc{`A0qz2Jq> zwjG~V+*~gEs<#u|$}gX9_3wStl+}CoO($N$m;0MvzW0ht)~#E&f$rPhdYZXUTDmHF z#fgWTN}XEv=#1NkZqI_UF@|Xung0=uf0P0(Ak5dfz{*OMH@ozKB`=It1qhaNe6%+D zEx5Co*7*11R^Z$_F5{!NcXJ(zzq@{Y)c8+s z++ODOmu*Xzd0cc7+Oni+*ReIS0~++Xjj`%Y=F5IE3}hI1v|->`$3;=+zu^67!$j8K zM>7VX!{Pfhf8#k+7@6I$%w}{C9}f*6>|ZwL-VZO$;cu}0T~l}9_uc#sJzbXO=uKB# zdexRox8=5(u3)F|^hf(|yjJyj zQQ;UbTRuepZ2$24{t!5w?O*6RfA*DcXt5Wm}EbEXTfyBpgHk}%!% zfa4X-|8Kv{xASr65N4}!^7`mcq8`5H~LY#eFKiS2zj55_$XRs z?~-UXIxhNq_+JQj3EuDwz#X7o!+hjzSsqkQfNMH;|G%eyj&SMcF|*6gO2;vLRRu=C zLwL3nhw~HV#vzoztQwzjG4*YiZ;C?;_Z@2fbd9uMuSTTomG6b0c-|Ghn-o0b^iD>T z(aL{uJE-ytUinv~?4ZnRV+MAq2hPEF^ylAdb|d8%yz;AFmCO7lXhVM4VVQpv39^UY z9oo6F{sSw2|E=z>e`b2$eYT%AC;uJz+ zHZq%|6L_Fs;n`G}cuJ=C8dj_Dolf(awR=|BM?Uj+Vz!@Wc^&RYCc{WumsR^9XTG;_ z>o<3XyFMh}XZttfXj$vuw2pV6yk`IH^?WP$(9Xnr@8@SIBm3!p^2c6f{!a1$$@Z*~ z=Loq=46*7}tDO2^{_Sk932VxKHi@`omb>=MR({lqWgebE5N-z|vOc>4_egxm9X z{v8dx_S}EA@9Qf(AOCXyaju8;asa5@FT&4y`Ra-N>R-F-{L)=dS|9E;QJIf!Hy$_6 z%L>O>AzfA?D7<|EL}(woaX#^n|C5b=-j)(ijee4OU@Pr=V|fBR*v^XH21rRL8Gq7D66jC!k-{;E_(^!{g`db6(zh0ijt73l??;MT`e^ovZfQ5hiRdW2^+LzJ z$gX|q55mv!oPM?y#|y>U75SNBEvlsx4#GAevACb&-hxuP^)++IBRbt{%q(c|!{>;nApDLDkfv;KG2+xmp< z+Ko8bt^N>x=1tqL%EjS>ZxqVQU4fs&_^91#r`oM5)Sp^uWb{xPp4+Ap50A@sKO05K ze#db@n)$==V-H;UHKwBIMOWf`9}sibwHF!fo&`|RIppi;yy(it^TsNTO6{CiR!2HQ z%pb{BGV7|xjg8JdH(74E*jRT{A>YW~bn8UEP@AY03pXXx=dUA!$S{y$;Ml>yuGM*) zxg0CvGj4??%iX*YdMVRS|B{Uhe*ctAN3i3wdE@5% zSh1Fm?Dw4W&O1mWX!p7}D5GHW-MWkI`z&{*UDs^yB5;fB)83XEq1Nnedk8E8*0kNEh0&g|}9lgJ9*lO?d$D zqHj0(%hI{K*6VZKOQUEN2A94$c@Hwi+hBRxrNB<}eAPrP%^7(PpIqStZTnr?}U{xe>DXyDBo?%Q|O!yg>zUKz); z-XxUbX8Zeo@>@1no$;=#!<;3!SQdCpI?UK)T+)wkuWvuM|KY7KXqLJ1+yCDk&${L9 z8{W6RXmPK-_pJU)U+|1O-|?gWV`m9k`@^zY%j>NT4#m7U-NbhtsP*v>yDr4TwN>HA zAzR*0IEDdt0p7C_-a|OH|1`9j?PNOpayr`2HZzRB3$*6_=*v4p`*(cqOLzR>ad+PF zilyg&u5;TxSFgWli?3VZ@N||Q`RMxWG28#?Z=PiMf{l8^cQ0Jk|2ub0H1#^=qwBgN z-3mEh=>7w(XENu5pD(>rYv;>zDCwLJ zcB26G=S%@GIVWqr(fp$MMrX)052fqCd^1xn zaepVBvVd?8^UaZ_W4iU%uX@{@_Mbf)f2(P)VqUhlbv{uK9=Z8OElBq*9sc~P^Dg20 zga7&KpwkIL{5sb-Pp75BEGrq8^hXivRc&%R#kIFh<+hgRWh^9aA+Tzp+}ZvIANQ$^ z3d!vh_m2BdgUuuTbgDZIGk2IY4s>1~-&E6#voy^&ILilI+u!EGIpljU@o>8Q*xAP_T{oQf-sU+W7g=s! z|KLx@Izjz7R@MpETnf7sxM$@{K4J4929N0!bMgWbuetP^;`Dq#J*3+>=?F)=#v_5ejrf|PySrghJ)n4dVUDs!XY5hK; zwU)U;D^8l*KB>I2Qwm;o%2feCE`ujUCq}EE+Pa~1{XouzdbOut-uFoBMe^@_@ovR&6JJde09`&cw_!&U@EqM8`t~2oN!~0CUt&eQb zbmNDI3z+Zqk3GI6UJ$g~(q=7r$9TfCe71|}qi`jc{sxImU+hP6)9lKeKY|=(CkC38 zTc7WYqQ0A7xJQw~L*LE!T(=~;>+_dyxZ~7cK(^UCpLg;tHxe!p*Uvb@J>{XhH~jps zlnw6vXP$B`;SzEEj3eCNU-ZQOHDABR;O<&CbtT~vas7-V9KQkJ%X%N!_`pWOCF1%S zN4T{p>+et|;ij&Jhr373fLXB^?!*L%=s!rgM?^G+sQ zBCeltghP6N>GXH=4CS4DH{;GYz$N1P8ArG~QQoIMfB79=-dDd%xI`Sv`|5WImqYtb zdgyM0JLTFNzCpM|9NKroHwYK{b|=f5x^lz4giFMszZ>o)T)>sVJ+N`r9fV870e`FR zARKXr{04W|x?lSk;SzD6$FF^iaA@0xTYjZ%aPL3!yB{E2A`bNZ?gt3>G2jmUGq~rS zy!*X`OT>X+cE6W!S3LBQPp}XE{_VR7mx$|+qQ8AN;r;=*`)nxhtKaqV5^?>EBiyrr zyBkCMZuo|`FA>+zIKutoMNho*xuL%s?)CmA;`$j!xc|m?DBr=$_N}_Z@t26}XB^?y zqpbT-CgFbVV@{7mTtDLoS3ui-{BKU*?|#7Pn~3XY9N|8PzU~VAvirTxFNwH*#u1M7 zedevNx`6KAzPrhPitA?_;XaM>PWUtD=iTpheon-pJm=@@(7yFye0=up zhs%QpfxFQlUvBt@%a=qP= zaJ@n^p6M$XjdC7?U#1a;e#O)Eb4X{{y&Fs;48LJeJYCoO&WN4>zklCwruh|5_lbB} z7jGaT9Lu3!@pQ2risuabYao78$(iO?Jl&H6%qehrpB>AgU-5KZFE}H@pXjkP!qBgH zx=+E&x}J((rV)mI#na{YRfOR;qf8?V{fejiG)4pFXYk83!qBgHx~_Mf5j_KbrV)mI z#nXKzqfySY@XIv9(64y9tMC%$bo?@nF!ZmY7x8q@pclX7Af^$9e#O&$Hlq>qv-ovR zJJbA%r+XGb0K;<%gd-&Vil@7p(SSJ{zf26y`&>o?=6U#K z8e!;HJY8JNiRX;yT>LVPF!U>)?s<#`3_sOn8e!;HJY61iA`A~V`6s<+nqTpB&nF0A zAZ)`Ss58y4c)Ax71TfFXFX31h{fei%p3#8e8lGu{p;W7fln>pWt1hpMuevNhRD9mG#ad(GM`2`tFufQ8O!aO-h5Hhfvd?-lzhff9 zLxzWp2QnUbBza)VMW^_R@yue)$UXpZBEo8@}=Y z85=&{{HqcFo$r5p1N;6bfIsW4`^^6ol=GzLzSI0qL-}w2$!+HU66$^Z)K%vHN3`dh z51wuQJ!t1^qEpQOMYR7{Z+M*f*{@#=@$depv--~p@N1s2zW-N4Ilr^+^8Po5^0&Wf zd;f8v-Vg1+ssCAOPkpfeA3{6-`ldpEF|_|=#D637i}3xSzbxlV0S_#Hb-)kn{Z7E! z`_P`t0zRGlT_?!=KYe&Gz36!8>|vi~6NtPo5SqLXbk!8PByLVYnt_8rP3>8D>1!fsEtYk9nxO z(q)+OT<;N<>pYgl^&(w{8PByH%iwyBdAatZ%P`}qqcRWIZY-1QJh}`sp6fN1#Wfo1 z;(CrQ!;D{rmvwMG#+Nv zEycRI?xM>u<8zaY2_GkybJwwY@d_KE8o zx(qXZBVP7p6JGXpAh--OehXgq@lw3(+veah%=pXkvQJy_vd@F4 zi-OBA}yzKMK@De944KBls-;S5KxCSqAwJo>|GyYn<#L;zl ziJO-Pmtn@=fR{LV1zzIpdc4csk+sXE_KkOI#&HfWV z#1rvId=lTpJLy9Duq@J%Z70212Kj=xBL6V&v+$BO|W&&SL0L>duiFTl$@>{}n+0ldVm_*(ocJ{3QT@5Eo? zBk~LJCA_fzvI}UxQ+5H;VXo&;?E*SCK->|B-JYghpc}wE@j9o#ey#$MRWET!oM+EZ zHwJXi@WJ+yd~-X5hWKbB3KHK?Uht9Jpr7(W@st(vlgH(!jF6x5L4L{x`Bx?U&rbL$ z4+KM5Apdy@KjnzxDXZn@*q47G;op+*Z%z0qPXvE;!hcP|PnjZ^n-cz868=KMKbr8D z6aH$#-$?kU;a`Q9Qu}uNs;;*u{JY^_g_qAJ2)&gc!t^ir-+s9dw8Q^s#cNvs7K{NW zel~5}SSUoJ2Y&%%m{wTVJP)U$XwOQ&uh8!xoF~UYBzOLkfU~GuZxrG0=M2n-vX`05 zG(Li95A!aSc9IBZ3}hIX8w1p8{BO!F*JPZ?z;zPW%lvztyfY^$f8x0#ks;+>5({0|K}8 zJqPaA>~GyVY655R*s3r+(xM z8;ZN<_{YRf$9T()qJZgWF zb5_zHBSiY3@YYQq{Mvh}fhGfq`=LdjSRa)BCw=ht-*kOYdSYC&`=}32)FRjiXYlo;8_180#v;w`eH-P+T&cj^q7?J!s&}w!nw>)%KFr7H=!| zraqJIV?17BeP%WQJ+k|qY(#R5rTq#Ej$wZn6MvaL7?>k-G7MxG$S`0SXt59CWLE2Q zsP@4`feY3LleR(n!yM6*eNgjpCw(wB>uDZpchmY{+CI4T9hp8Db4omaYaWm1e}|Gj zD7k%uks<7~{e@IT=p-+wtdlvfm5?83r;8^n!sFeXuRVq3VPD4l6ue^}*d!S23;m z==|WJ=!2S%JL!XND`9n%r=8vT^uhg^eb7;Ww z*p836^ucxO*0tzy?Ya5wXH)y?st+RHVgH^)^KmDAFm9)GmUcI-52p8v_h!|X zFSZ9sH;h4=`e49YH+`_z{bK2V(g&~qzUzb16XTlQ2Ys+s%-0V^AzY9?xcBSXesRnX zq(O3wrTq#EPW+RdAB=G*9L2b4P3xBK{Ga`17|1Y?VPJj?BdYhJg$Nj)8;!o}{PyW_Z!3 zKS$I)sQEap589-z7A5pQkLs=urtO0(-kIrxO*AgRJ}A6((+7LC4@&=&KDhc#t`AC2 zj80v$TYpcH?Swv9%TMw9V%`ROP>-=r)7ss=2-9cR|K;M_2ebX+?nIa`CDRAz!%&u< zVIaf6qYneIJ_y5E;`0y3#60%FV9V)_wZxpYV14jV&JSun?xYXKb9$`*c@N@n+CJF! zJxO+cFhTUBT`K91L1Z7?8t~RlAMEve66t@^2iO0j>x0r0?sn1#pBwHUd@AoB%=AG= zT@!!lc}O^QFzJKB+o9@%(*L9nuKbGYgVGZdjWe(7gXeB37OUJeJ{T+Eg7m?y|FHP> z!E_&6b%AWZxE()n%%er0j(eQ>G7MxG$S^P;25g#JG<}eNhcY}1whwZC3-`?Et{Ifk z+x>%@k2~pu)?;gwbe49vlRlWdk9x)Hv;ATbwp9;F>V+|c^g-e6Q1wCSf6@o{zQgrF z>4|a8?t?y9&Nmvx@pCs<#v8SKy|G}Wa6$Uu=npe}Fy;%=AUVd;euV`W^H6r*OpFWX zx%Z2sU|(y3w|V%t!ozb!^+CfT7QaA>YJ}A5$sy-;m*b;q6fMLFs?e2e-b@^+D;0iN=|C)3z6l z55q!O#FnwS3pNif?C%%f|GzW)V5SdBPdi*LS$VFqI;9)?XFnMRG7MxG=m7%>``{w{ z{o;hhae?~a0O0lVUYq8-8UC)X&JSunUMziZ>zlIu;+VO*%~3H#(>@sRcBuNG^gro? z`~TJTLFtKc&F`PLqM}08N z$DQ=SxHQUEKJ9M$dy=;M2j89PgN{4luhTpgLr5Q75%AVcAMEx1LFs?e2M^3V|E|^0 z*rX@MHM?)qwkz}X9qHHwg%_j`?*Eyi!#)^=@#l9eCHY+RA`axA#eMNtg!373Tr&O8 z{H=Ahm(`x0*$0z!Xva@04m+hYE_*TzWEjXW&W8uqYCi6y4<3&DX0~SfV1jJPIVCQ))KInL8$6qpD{&xHs z%Cnyg0~rP~4D^J7gSQX%_V=se4UJ+%Q3a zBdQN-K3*(+aBHRyCWxM%mlTdcqz?*jhpG=s|C2sAdaLV$(i7vF-M4AmRTG7g;t~6v zWcuH-^MkQ2LmH4LZ3(g*jC zXZm2wTbzqJy)lIJLE-IC^+D->(gz>>W7h|zC&o3qZ_~DIl?JXKj1J~6)p-#M(g%0_ zII|DNJV6AKKjfzU3MbQ@pECQPHVqCNPHf`HJRLfV3=U!dR@2DS)d2nI(QD6U8nLZfv1!+LOkel`^ zoJ@B<%Jf0ULp%PG@$$Fh&rqKIWEjXWkYS)F3@omFkoshJ7OD?Y7d+^{U#$6f(e%Mu zrVom+@w~5jNp1|$)CU9J4pkqN{wIBK=Z_|u$}bYlqV zgTmXP>Vwk%qz~@B&h!uI(df$xnKk0*e-r)M6^u)Mk_fa3LR2riPwNvax z*utq@2TRu!*&1W?-WXd|D+F2-{Jb8 z^u)Mk_dy>V&+jO%+FGgXI7ppvLHgkSf62}d#{57UB*$3Vudv`^KFaKaF)o~wli{?# z9e`k?g0xMuf3AFK@X z&lew|?~5ON=HlB2+ijJ?JKfAanC5|GII|BXv61;R3}hI{FhC3}_I`15)>^1ONL?_z zNlNvm4{AQ{qz}fW`Ml}%Fg6aS?SpOm#Z%dSaVs80tE3x4NFQ7g@YYQq>~+6b`k(Z{ z)h~5@P(g#<3!SzAu ziE+*D+qCVP;`AYWT#QnTlVf&H*U$`Gzt=yw`1{4pl~%LrB>pq|U=uAJJefY&0V!Ej zhJg$Nk8%vO*augnkuleP@saxb#ixGc3mf4^%z{K==?olhU!n(Y@m>YDgV>LT*TAkqhgw}aIOuhU%Z)2b$=+oJ>eLP*?an1jGl7IFQe#(!q;`7^Y;8$wOkq>IoK}qdpXi8 zUL&sB$e1lxZCtbd=a)q1z4&P_`mfs<t>r2=X!4F=!~Z;l$sS4#DA4xo8DiC2P)Gi)t8G%{NAG^k82#Un`EYkNKe; z#R5~KMsci~D~%V5(@_qUL{m4ey*V1?4_i!kXf!`QQY_>erLkhY0Rl0yuT~stm}jIq z(E#EmYDET7#Et82MmvkSLUFiQtD&2HmBDDRTp8M7h{zXeLzP0&ySHZTdXzO-#arCj zh=9!+j(`9ibSCpP%Yon|IvSO#l?XNA9{LEO!BS%^U*8ec%cVjwM`8pYC^9rrBNh4z zwGwh#u*l!2K3bXDQJjg!&}J6L9#<=Mx@)3Zv7B!p1M4rAi(}CQ@H%Nkb)vDRTC=8_ z(LP@QK5NBcmdZ@^M(xIRK!o{AJB!})sE@Vv4c97TESBIfslRxW%Df9Isbu(fGtzZm^s$pcSK~ zkP)+fpgvyKx_pR;_yc9zCvXfjj!h`(eQN6 zh6Wku`8P*4kkFoTz81F#91k)AMMK~!H8UAGMuw`ECMyk4vkYz^bPj9_zu~+swo!=+ zjcE{}UdITjVfa-?^U+YbR0S5yEshr=biW=|YK_rKt`2k*qXO=`4TvK~a?=4dxf!rl zX&5D%GZWo#Sq^<jOYjU zYlwy*05jKb#Q1Y>u3iTEDC%;_hJh4R-+mIG^U8X z#uRbKBo6c-71rDcd4yW4mL(QIXbvT=H@M!Is6vK$b&w$iZ*jEl|=oNxC&qu$G4m7<1-_be}f#7($q_996xQ z?y#BTls8pFO*A!H8XC=2CK?dx5hk=~FxnA8kmn$ai9(EYie);;Mh7fjr8||cnG2wL zwK&A6u~N-I49yOU@7R$bfZ|xG!SHClR-jwUV^Z}zkn-bot1dq_$TXBIaCjkbEfHRW zBt!v&l`cjqM2^)gFbX^-xj3`p$`fPO-U37tBX*R=cgPJGl;8m0&1l;Gw@Coo}A zp2qCC27(n@iOnv36b6_B2BA(sXkxy=@Zt!o3|e5_&Bhj1q_MC`uklI)LILx|AjD1` z2;+FcM4rdg!GUj*Z5WyeL{HB0Dp1GQI+%RwAW@+NB?K5bFSIWRh{~Xkx?BjOQ>GRH zwm#!OITJ!T=QP4oCWRm;_~LX9l&h5nF*)a&W5l(qT%%UR+-ODST+OMJpk!E+$Ia{A zaerxixIDr60&GgK!F;{svpn(Qaijt`5t@z5_GVubaeYITLF$14C)6v7z*xOfW;r%l zRRg9lwMsfbNudO+k5!;$dGct!RC6C2?>=PDnIMPC3rSsXl*(mHSDf)3iBQO5-HrJ; z9~jmO4ptc|=EpItO+5*t);ecsflf9!QHChNT#bB{aSRpANA)}sd_J~8GGgq=A1H(v zIF@&8B)2ufPdPs{F`ln+mPe>E)PUlOxdvXJo!}eEL-*oLm&=b;CZJx9*C|09sgvWm zsWlOQ*V^wo`#qn(W5sDG%MjbhIz|r%GgW2lL4ulbq?6Io&AXPY?*b0Wu<7PQ@R({& zk16UN15Jd&(0Ul)&SMy1%BYVPrl`CY zrbg^{(0(xpBj^pakr_ijn7QIZm>w$#k`+uw6>JTEpl?=+7}{V3@PYfGP6i*exkB)= zWNMg!?=hF>>)^>@W*WnEU9UGr@jJ@q77Lb&EEh!3JdJy(=P`fay z!5q`@BNtWzSfGW@L&i)%(;D;U5x`~|m&>5z`L?bb18Qzu1NE>9!Q~4)iv0^Y%Wyhm zQ!yjg>!#TIoJ-Axb1qQFSS7Q3a=%U0A&cT-aK(herEznT$_-64AaJ0`&5VJLHE7!) z6tNp91oF8~NE4z*n_GKMk;-zS`dFm_%j$movHE1d?WM`O&Fs<9Www&#`#o) zAP;<90wh^tw3A{N3|??tmM5@q7@CPDE9Gd!R*LBBc(IJ-FqaWcf3DOFv3#Y#&lH!5 zjcM>ETLO>9JqJ(F66C`~oTtLZr6bnN{9PN3VC2-TQuh&t<2n~7B!Wy$j#10l5@8VI zrFtb%fXy)0FHpEqu}n^F6DgFIxpG8jt^Xo~6fgmpC65&{7tYWz!K2hTZD?A$ORR~( zIA*W{L4aITrE^@-1g}l%9$Um*tY{3aVQ9k&nt{NfV9RMhgT&%Al#tN<>n1kKE?U90 zIVUxiqm=lykwL8JZR~MM#2747rj9{Dpa6yZGM79|sfeYVF^K%8y1K$vgsMOl7J3DT zZVd~-LcX@c68jKY<+#Jjj6O0TxDR#$n~mjdM%#cecmjE-nTWb8Qxp;FEFXqV6Ow*| z>vI#?aINGLVwn1;$%|-s)F$5P8B2@`GtdA*%%~2|a;=jhgrOi!=!Joah=+>?*24Zx=Pt2I5WDTuDl`@Ab-L({9RZh7DzH1|_%25!k zR{S+nmM!$6z9Ob55BC`aaR*ChrGa9jsS*&#c{vyt=nd1b*-)7=nk-ULVt4bPPc&7u z32}5yG`cn#UK0)DcOA@2pghKyErm%Zup3NG6EyQc+F~9DpRofh4Gx-_gXN?;-l$L5 z@1$$#6YfmHh=Uf8=2i;&CR$p~6_!{&q<%#60$Q3!_6TB$G{K}Q^q zrlL{U!)k-T6s&nZ6<{D%X~1E;qso1Q#Yq?dKoKO@+=mIZGVaR><~PHV@nK_%nzZYF z=EW+47pd0Aum%~zIz4bYmj+luMkpIdH{?Us&_23`KWjt(Y0C*XFfTZAd?LcHSyXMx zx4K}+8=+-|F+@5U+s0#kl=u3(S~mqOx|V>y{Y2YhdDN*l4YSq^Ugk2HM@FO6#Yh9u z-IA7@A_8ek!4LUpm?LpGKUONw7?bx+T8ukDpao089fYSbNKPB9z@#%|4$Hz)uR;^3 zxxfYn`Wj*d?%Lq4p&`Z1DjweqgNxR>w!?PPLNf+a;S3zCUd=66U<~aWqcZ_!F%NmY zZwwV+MLI?c2HfC`8D9Iwim>Ry@)tsu0V5UKGqq;xeQvN}fk|7Q7Nk5xb^~=;_5U$Gb`Az3d;@5E79sc2I^<8 zK0E4zh=8UTv8m9kV5m1b5(5~LXn61udx#(*ut;Mm!3hEsoP!~PMQd@YJXuCxMv8R7 zEp%Lv(Z?MPBO@UUt0>j{-fx*k*gy1Y2=*juhkZUnVT_ev7$Sy)Dh=sbg;m(hf)kTw ztBq|QifCZUM+R}PlkplV1m3VKygzIk_JYO(nfr=ko6X$Y7hH@Ix8s8*`Dr(V&~D_| z2byW)ce^1)Hg!5~+T`*zSdI+{wi=8A3}pA1;G#{t&&>ezy3e{#V-r1YhBq++Yqu-N zA%pRrPhr-g2F!bCfsH8Bd|70jGCx={v7ZBz7`U2yYXSezSA$O!;dBKt%P@J?&=^;=wV25n23i^l=A|`&JRJBGUi9AV z6v3Lz0;%><%%UPXGf@!8Fxk}5F|-M!q=^$nnOV)1Dm z`Y0@x%Svun}eriVBqpDAB=G!L|?%Tw|D&1(V(PZgA_QY1sst820fL0z+WT zArKDv>1AnX#>_a2Fi$c!;=Ne`!0LdXXbad5A)nG&8^#x>22kHBcd4$*QSoYv9-bH< zG8t{AU*I7(TpG9i*fH)3gWJHBlflr7nc-NjO_8HO!(2s?IRUzUTt zf$K15UFq1%=*kN+k zy)Ug|^59^_A;Woyhg?uq`i3||+e}A;OJb1LiZIui{gXqMhY-+5 zSXA@Ci-pp&jYVQy=S+#faSE7dpl>l_LLKms?fF43@RFEGv%lbT(hizPf)<-Atw~OD zxx9(&L_>0eib-@bmrwONM|%~jHFs;QMI~fIx;g=m_LQ8PcIVgz*MR zVitb%XWBj3iyohZJ-N>|HNygtm~{RbR071?UQY9G8xkk%nNn*-`CP0g|?7HJ4 zu!#m6FNW1%0UES9xj|d|1)Th(u1~IV`T|OxpBVteH~kYF@4mBh;WR|7%0O;0Xx@$Q(<6#}aHpF(Onk9Gn~w zo7iK8nTR8P0z-`MFb*uZk5){qSY5n^95B+r)&N3andN?JBT>;bC`P!~v;dEEwS!2< z&SQ(l1d$3c;S+{w)3)R7=L&Mz;e)k7!b<}POb}4Wx!e#7?Tw?#x>juZ%1s}4r33fT z6IjOdLZ;9j83t~tUWRqfY&JtBvq78S!1CA@azr+#sn$s17m?&_2xV$m^tv`iHi!Ko z^vE>GK%RtvqM_f!1rLQaFg9Rtn2IWHcQ6O029KnMJ7H(QU{ip9$`-9q#9(-U1!5{H zOhkpr2+Jez7pydtL{=tE8tctK0=>l!Ur>WK98?BJiD_^rXpd7P{1ePH?U^q3aT8ckfAU7FP+-!LKnVP_7)BP@70E#W*-4QFyFQ)n~7!7Z4uhsQ_MpzcQE~3KLZzm%rG0 zfCIA9;Zz9ePQxrsuOrx5faX?$p`MDlGb;39PaA{s0wsfEgG*w{S91}@5<*eITLA;) zhswom+@FGCkPGXBSK{;oEwa$VI3Wfv%VdgKB-awbz)9c|`ZxpejERwQ5cWqu-9mld zh9E?(;&3Vs=10sFJTYbL83$d_v=b3UV2#rXHr=p%#R`k8)u^FB?i`}$uv0R&j=i6u z2FD4vISk42ti?oPTa#oo+LfIe*sL@Ujy%g+<(@e;Lz|j>hr3+ywJwSaYaYb7QH@3npq|Gfv8oH^8>6b7%|hc~ zi{+sKuou=)rNWJCpegXAso_vl14w7~HCr0m5gBeq!jNGa4n+eG;MkAPXFH)>M%des z>0%hCKDdm9^u@v!3A9uUV_h%>MH!51Rt5|Pw>Efu&QdU8aFo!gq8VO}`D{#iB)Tx> zKHq-u^n@R$GlqQABoB70RZUD9R2{koS{D2`1SqfVm-CzvCmWn8qz~=&PC|pd)qRc! zb{}dpdWeHAIZ6a##*ZQN)gTjKP2*7(tY$Q;`aFB%8i;r7vkhW;4#$&lJeEApbrmg% zepUn_TWo`45Xp0Yq%~bwq<|bkQbgb|*_h`5zttM&$hFv625;EeA)FAy z@mLIBKOewJ1luW-@#>29S(}Oy)2UCkm{D0G7B^6=!+7Cr2$ju|0YCLFSeLgqxM>UF z<{s>OPC$#nk*u(=#^6o(k*^t#B~8=6WBazP+j5()h<0p$i9Flo*_PXW^%d8I)P#R~ z?7w#NWzmi;SL3}r+HnQ^S8t1UT)P=z_^-Ss+Oc^nB2Y9c;Lk?OhMq4RN!Z6TnC%k0X0l9lZ{U0mA@Cmbn->=28K4wL!IQ2b(j= zY8;-}xpT(07IA{X%LLsickR44Tesb!b1yM?Zch3!D)fbCXz=UC8b?zfH%H8#VR+z9 zNgWmrD1KfzunNA%87KVMD5M8N6--he9CDo_k3AQ&E}&0lb7rU912uOC?452MdeN2$ z+BU~I>}Es<__thv)PSM|v&|6pV7M3JrI*I5IG{=O2;>Po+a$3RE7ysjNy|=x&9^a* z%rYiXxaPH0j{+Q1KD;oIGr4bg43Yqg%{*j1H&}D|!X$OULd8Uo=~rPfKRvV4#vIPC zVlHF|+1vs)GEstMgNunPDQltlUoeV0ONacS={^fAWz^HM)9HbR*~{BJA5BxLj2wZ-x@=Qp@B!QBbNO3n5{u8t4D z4GvndtQB5JfBL9dT;{8HGw5CgTf-2xPkAB&lHo;|Hm{+%oYT>Etd+cX0H7==UIU$& zdWOPRYvQ;1k+$8oQaBLVAV%0mN~|KhXndGWX{rneZ?u!-!};1}JP2y3*bb_XqJOlj z@N{4&Kup2=vT&rH2O%L^ZMxj9IWQRsjgAK~!6s&{X$5SF4UlB*kxC`V zagu8rH47ZaG4%`!z8dr&98M1hBSVH+?|bqRFoI8<5a03{AEw1wkx1d@r<5J9+pffw-%nHP$t zwHb_LZkYFRAPqZ5U@kX^gJAGu2LZp> z=I~1ftZATTxx>EaE8+NE9>;EB(a2X!GtO7+OdCQaWC5J(133m7oQ8<^F2+<(X0!Y1_`(l7Z8XY^16U-$Dj$oX@ zKpsbghS>KJ&S*~8jW8|2r%2f;_nE8hWL(I^i zM+^@Q*;s_T6-#$$_*neDq&RaKC;v+^v0xW`O8j4#+BDNB)~_zswwt_1QW)n`FQTQR zT!cN+Ghx}q?+k{_9OfSs4HdjfsG%5DJ_v8cg0lt6g4QDQZHHb0OQ;%PahSD{#Va;4 zZm}cNo)Zh2N-fR+MoATcm}^o%n82*NHuSLCG&es{D1l2*leNZz+o1|_*@jVJ;Z3E6 z*KMKZs@p?xBLy30goO(QLq#eS@nuj6Qbk3kLSWWJ8n)_br3A~can3d73o6$LjJ!6a zYM5oQ1huU6V+kq09{_c*v59FEg5$MV#!z4~Y;da9w&Q#(R7}IQ;a3F`YO>XE^l|F5 zX}xT=gdAZW`m$Jbvsiw(U~= zgm^3$H&@1oOPmFUhfC9@x$soI6@^yCM!NiXexy889rfiQR0D7-ri~CBGeHPwXh<|( z+Q(DUm?2|pfmk?!QRE3vwlw(hVFu_H0yvrs4KM_-4#u|tudJ?hczT@V)PjPSdSfcQM>n_0h~-Bpy1&fl<@wiLG#6&^{Z1fV4pHH(M|~Y<=)W$;6%|=1En6JN%pgc+Mb1U~N1B3kjrh1>K@jQaIlaj9Ny_Lg)+)qCtaQ(8UJ_sLCc7jtDz82Q97z`hr&Ex?Ahk)Rr zeDDBg<2b~*jy9y^U@Rhtq}45S1UWa-19@tSAsK z2E_5t%9J{Z{#_KOkqOO|)gh{_AWZTksR^H?yh)0iSlWbfKzS362&3wC(3NoN1IVUp zl%xj=BMr0M!^7!1!C-!XF@lkhFm`qf+iJne;-X`MW-lHpixcq019e9G3W{{oiid=# z(WKkl+AI_YCq^*oKxCQR1$R^KahR;9?JKbP=mftO3mbi=L-6xmAub2Q5Y~fE3(jsd zTNTi9$G62$|FUza);YAmI>ry;tYa7>T&grrBhVAfu#jQn_=>+*!Yhl~CL0|017|u`UOJ(nY4U=R9%Ju>c z1r#}4|4=H@rKH5SbsU&AoHVTApkY2Q-Xkr8&@>2qO=(}(`k4nv8Z1G!(9Q%!(Riac zU9xYXC+j$NfN$48L)cxnmv9axf&8x-2ZPgKW;N>GdJh%w2)pfwFux%|cYnv6gLQ>{p23Ov}`rq4EGZJd~o-(vH- z1YqAd#CO%4Xei47Y1;RRk~{7);`Nz5Q%Bp#v^-vb?>5+DXEav<18&e6>_ed2V*TLip)dI;bIWxf}MKmhoHkcR8IXsS|hUN08=>rL{ zts9QP*T;2U#eCd~3F3s0rDI zTO#YQYc004#Q4QWE51VHl7mA4+lesPl{r|9C_bc|=3E}C>`oYrO(-yuhW6Z51-xICEVT$XR(qY2x2S8O5V8q4-=s!%WcXbAI&-ii8r;Mu?e+-jNzzjiIpcE{P6V9UpcV(IiqGey#o;h5RZTxF&4p)cC_ajWnHWcH z1<6pH#(Y?nKzACdK-;68Arw^^3`K|R%`m%#!ZWRE*Hh z3huqasYtdJJ3IEveo#1BhfGS*q=Tc;`0xkOHVCGuzMA0lC1;tLR9D%{u{dl~4c2urq~0OD|Tw0T3ssVB6qL31%AOo1>bH&KG9!H~gCAao6a9-h>91r}0Z8sEi^&qO%k zYyo$%WrlsUU<<$ve}i_Cm@cRs!EywRAB~w@%aeg6?7-SDFPB2V#0{2OUIja2oDX%A z3ovxo>`weigq=AdL2-VQKZa$RGL2LEaPE-bh#-@d4yJ{m<}YbQeHxpjIEn4rl3iiw zG58!Y!q*DqGESfd?F966`XN175eC;<}3*U90mo^i9cYzT~K%FtSx zIqV?5FQRQAE0>K5<78+|K1E-IqiwKNz(jlzJ_JJ=55|K_cv=`=Eg}^I9sHUOb3*oX zH+1t_gTa;v$FGh200L@+d5xvng?qlmWkKj9*ofinl=N}Mjx{Ir;Bi<mmU;Y6r6F6v@gH;!w zr9s442v?GoU?pmXIU?9wM)VN^2d)NdIrnh_uy0rxBm^1AFu{|HY_HIQ(Ge#=R-ua} zKlrB#yxcehib3!7%K5z{uPPx^8Q)PsFb>14Tefj%$A_Xmhyor7LkrDAZHq@cyi=ag z46ud}fGHfq5foz14*sxHhndJ4f_V|*m{#&c*i{zHmwrQNuxgvheU#fNJ}AlKBpjx8 z{Bml?r9l&r41pu+?xFMIfq ze`&_*$H8!vtK}jNRB~j8NXkkr_z(-jaRa6iZ?NC3!|^-CV|9pyR%psFbP*~aX8pni zC%Bx-#5jC|m@@fYyM5J+LsjJoXhOWS2xrVNIKrTYyn$Y;u$x1u8%~Vjb1yg2=L%JP zqE0E}$HBsQaN8g7*H`t!(B{GVm*z`E;j%N_1mIqLvI#{Jni&qYVR~n>AM7mf038Rp zTg;pf{k((S^Xd^;_j`MJU=56lQ-d%?<6|kxItZo)HDp76VjW>iRx8Rr6ZrobI}gCB zitPW-dwD4YMZ|^$#g5o07VHopfD(v=W{n9oQW6QF*|1|0Au4`F)7rSCzds}r~ zd#~&N^F3$oeeY5H{R!W9r?)$E=FFKhb47L7g(o{vZ11FMLD|fSUX+HGqjhNBtQ{ZF z-Uzz`y5*EcWLlM;v820tK~rcOG#Z<5vYR!TzUVu#heZ-(^;XAgX5hduphE6dLJByk z4Uwwt`-tRuN0v!lIMPfjjGK*=qE0k!itZ+ePn+6QsbsN+yZSbX6&w{{y-@5BXdq#`lUO&*?KE0)A70+N+Il4+(HM7B8M=Wc4jQvZj@V0PGZhR7(D=K zHM_UVuacmXw1H|tAbzRAZajv5DQ%HbH*r8`7*q$3r%jaw_tA$&O=fay_IN>ovpxH?-9gyJFlhS zvT-iMWD1Er=>qaA=-oaR6v$2aJQI7&v%nhjR6{DFHE3E?x5Y@QB}TD^H6oz(ocB67 zZVeQ>UDr&#l;~s*gv_+MYq2L6O}VBV1tTWAuIfpiHbu(9=!EjiBI*VC<=e<8k(|s>*qDiENS<0~aj9Ht(ol;Tx))+qrYjbHQgBu{NnMj?L1+`kYO6Hw zr(KfNM*m{x*+`8AMUH{aioE5MJPQ((GnX@4-D!R9MYDJidP_6!V$%7%o5fqE8#yYN z3t44~HOxCm1w9I3Ptw|Go5nSMHvTZwA?_DS+qKubFS58Z$ZN)22-$Lnjq=Gz> znDqtua27QxO)4NZ#4QC5w7IyGqP9=m)Z-@jJ4>7z=|59M#Fbd$c%bda7rNl%+gFq* z7CQ+X6D{Z&iBFpLGW#Ep`m#sJpL?rIkb zxzXgUZnQz^M&k*@HuLh)Ey~wB?-p55lFz%T+aixIa?_-Rh^E-l$oLWgouMxd2Oq2L z#bQTaXUlC`Gc-Rnm{eGyJ~7x znAB2G<0vUH7ENIiJBw-7&tjE4Z;2J8wd>Bw#JEIg<-CkUJd*VGm*LsQNmymI9Pj)j zuPr`Xh$s;(-0p)|NEXSQtr2{Rxf3^Sgh1@ zVORsPCMkMqx1+A9i#Ut4b6S|xMa`RpOS-K>$Xw`W+f+%wxMvktDC|7Nm*mrkL>Q@q zUE85}=9-eRysbC@s(@0WOCv;kaUexbLs&{0XsL^7GZx#@_`aDbl7}9SzJj4}g^oU| zOtIzg6MVyjH7$E`=;PXrs%TU_!eG)QPcXnzxcsSbe0C6b~}aZkRe{DPy7}WrHWGQ`+hGXx43(+HW^O zrI<9y4XwJ&--T8>pG%LCM0)k$h$RemO<;uXsl|7DTu`jf@VMP~eA7T`E>2X$_$_m} zom%I5V)eAKliHek_Q`u0X8|~Q0;;Q$+qv`%k%x9_{LzawgNtaSE8uThZ5{;> zbEGn>Ty2^e4=qE_-OP3h#7yzbfte%cL}`$!sUL|-BboC#iM6p#3r}xLm2i3%Te*@{ z-H3})Oe~|P)lza8zS%?^k69oV~rb~xTW81 zPB?AnzJ9XK0wV`yU(;Hfr;lc9O>F+8Gx4&R4K)l|BZ?cemYqFKB1s0iEGplsxq{Nv>xMR7P^_(4^$8uHViLU)8`jPO zoA9r|o^U2e(lv1=d@`?8M`_0)XKkH{l0jme-9V9CFvc>}v>(%(Ba$;OqBT9Y;}n&V zUN|@FNA)V!v?kqM6LcXPMYNeoy2I|kiAvqyu%t6RWIT7tbA(&5?DaNJf?3hWeG*MU zAMSdGNtGu}H9?pYPu@FHC7tGl?QU#H^}Pz!ZITTwnpr9ziEbY4%f=BjLxOD4Qk!!N zG%Kg0Tg$;f?Hbu$7{h~I(tY|st4-Ev>`+@%BsqmngrD9V-L>7W4|@2R_t(3G8{$*6 zl~SQgl=>jEN46-MF{^0?7lE)&lna{=d<#jPPZI`Zv-j?fuBDoc1i6VcdKC&?O%`Qi zTem($8CIgsn%eUt#b%a#b8y8EuhLZnld57&G?Q#&F*?J z>;_YDlzMr$oT?HjmHbsox^mK!AxR&boH*5^%x?-uF^DTp`JyQeqcI*@XVVv9ySVU0 zt7KaVjYHjrJFj$kxFo=6mbNwW@M)KgR$5AJ#O56>W0SeQMmLMf@L@6Td+pAJuiaxc zk^1I$0oag{#6c8N1y3yq`sYZW16ek25xF+MbD1WPMB^G}aDO%VdCiq2TQb3Rg4qUU zsiZ#5R-~le4XCVmImNs1xw|wElaax*D05%?cz-bWI8T|GX^&fECB2l?LGu3so2Q*z zg%EhUN-zO)iwS&}8d*<{-gytw!4FH(6awhnI$~p;C=vN3D&uzN zb-_WnwkG>9pUAxg`SAg#GIPQtCbw8NW>0p`*nN^AR&}Yc(j~Hjcpvh5GIJ*GRxR;V znoW6IdG<;>5|R6mvA{z&l<*RDWY3LgzSw5FMhikvyY*xu4cs(USGi4NRxzdpK{Nx& zouzePchcyNsVFfpV`Kmuo7vBp#&-eqksL0v=IEY&IFV(SsMvugBb$sGJyWi1CVMxQ zvHG=j2#%PU!%W{PN~~VkMCS!gLx*H^NRa(gZXDJ|qYQSLwcq{R9R`bybz6UnE7FkE zx1hM)LYlew_}Mgu2}LCZJ*J@?0dwYQOGiQ;_S6A9CKVH}89{Z15z?a1|M5PMq_W@1 z5Vfg?g>7=hj3$}b*9pc5@=w*#K};zpekDc6KiJ2&?w$zlF?lxn` ziv^0B0s79p1zMu3MDDKz5NT_(m4U_#eUJv6KDEaeFHO-y{JVK29Jw>tEJwINEgwX4 ztTsDspw-*8ujXWA-2*2bz}%xInC6Eu`bdPX`qK4&jPVxVQ=M4D=nfP6n5?+9eF$1_ie&K)d3$Lp`4#<5;3;5k<2uH?_ucFZz{TiCW;~vb`AGwy)Wr;VhVv z($8ggO2BtKMb$-Ei2qZOYw$I$rNA0U{G^!kB)kV$f9>{^Hld`fgj7FL! zF*N9Kl8@R%jj!-}LJg)yQJJ}uq&QSsOd(Yc)HSr630$4Rx`B5<5Ff@esO$F92Li>- z_`VLzfEm*1F>kG(iZguMOS7(oyQd0)6^(NYUcIZ z5qbMzIcJ9&h9%ST%w}zfrdCpF^ZA-q$y>-2HL>x@*Um`ZG!4^ex-rOE9&IQ3P-T}T zk=l!=fG>e2LHhk-PWyuE@J73}oq0-6tF|s(GlPG{j~!T;KX^ApBdC(2`+ypiKJUtt zBT3=F=J>@3<;&Qyn`Ynu$~kqN*oyPx1=2V`1KakxMFEGeVRdJD(kGLJcnqY z1vr|a%~+PEXc3CG*$K`GwahDCVEPVsO_6;3b_rJ4O^u-2}WEE)-_3*vpP5D$eg zU-*aLXmB^=N045yO;hqqEmF8a!7P!-(6D0T^Czy%fdwpd)Hc-A^tP*jgMDJIb^3TZ zlquv%WkdA1H&-_4lT;k**aPUvDsqVq>Jigz=oC-L5N~z z2&T-Wh6-bHl}=1hhe->a@`OXI3v)0>&vfk?R2h3r71zWB2j{8dmYQ^wCcYNlDD(lE zArhgsv(F*I--(1F6`NGwGd1;Mh&FSLrMu?MjFx7-=(L}s%^&-$`sqkfBQ4FRC!SLgJOzd;$G#fL#KM$4lMKov#f|Lxk=N5$eaX|S)p9%Up7l^ zj_*^=^M|&g`9=%Be53^xQYB;tJK?GboU7)Suk}fyJ7oIU#ITnehPTa(PMG#We!=WN z1l~zcTwt{(X$=7T$q2GKLD5hf)`FD79gQ@bI2!r7Np3Q?+Sx0v!xF`3Vu3+`uk&$l zgxrnvR$YtAYc)MyCJ=kttYjve?<5__J8^-h2Zo}_!yib4Woy*;sb)@Q#_;>pM0j+V z-?$P@meFJ>)F(;tjXqDap7`!X3U06x#Ne9Y+~^dZoTAJ?CYu12d%dJY`4GBWAa9H1 zRhAYumYDTXXqsZd8gyH-Gto9@n4`<8%-E7j!sN5y};5ghVtwBP$ZmU>jR#quPj!A#FL(FvmClo=)u^B%k4c=Wq)$z zg1W^-Xp<>%L5(3{cK@zOxahaUypa>YV2$4&0mV337?x7ODJ-4uFd~}JK9{LZYbK*p zFdU^iui0A+g$og^BS4Ixz(Z`|C9Qa|BBs%$bM1%{MV@;jY(opcRqPlPZkWIxj6SiU zmupmmcM|WQ;7vu7zIdRWxf$G8yy_LaG$*d*ZBd65N(q~3P^*rWB?ln*7zUjaE zhrm??-JJ*b#W%U*h;y@#IQx*HAIamBhVGVxmHb@^B;gag$0@YgTPg@kZ!kJh6gzc^ z@r&%FklM+%pSZtyl$Re~07J_@cu^<$l(t|{h_ueEg<&F>_G#7J{T!J-;S)!YsqIcj zps5{&JZI@E!Be>l|Oc1;`M?v)MJG#DophPlp1z;T0i|vz5UZG_1Zq$<3EyV+uhT48890p40 z&3uYeN1E&l3$_f=M8-y%&kJt0oEg&5k(c4V{%J(Z+*S&FM%maJRK)D!GWM@@(8hTF z_@xonPg>Zj=+bOwalspFaxTNqa!CF<5vHCKTiSNV*RFctT0&XjefS)`L{9L|63bd$ zo!0e?G*4WJrlQ{QxeZ^+Vt-%TWVD+^!(!anK$BpW#STY1+W2XiF-t$Lv*70d6B~EW zBGd0~f=9ie$#!;umeU;|T%;x67)Cwcst*V2Pq}y-acaoeI%@$~(Rj(4f=PO()=+gt ztz!%Gx~;O3fh(B32`Q`8bEMGjVv8HKiFMrMHj+_!#2Y})qtqrn-J(9KGX~LH@`mne z6l;ubx>(;-XLWgTH$OycQdzg7W(^Z2JukQWi%0|TwL2YnoxxA*cz)XS=`FV~)o>vwtb6NZy9Qh8QQo=j7A7OUkP}}L&{f@F)2Uq|?ng{mnE5G_ zM(%8w?3zj>6Xi#~ABHuGZ{t3spG@HuvDu*0DW+lH+BAuqBurw2^h#!*0d+B%I1|_1 z@fH)a%bGjBP^TX7ym50axere+>N<(tSQ(q7xeSTBkY@JgQ;Bd*wqWLFeVs$3SBTwf zn2JQ5ThRDS2J8^h_AsYsnA0oF?HT5>lH&`h*zMsq+-1X$3ZzT3#wpfo{pgv5TjQGP z%k_5jlBU(oZK2VZQuG!b8?mpKD-F?D-AHPm$Fa#;1RzkJAi0!iJlqMyRhLm|=CHff zWpEmzd*7H9Xf%^5K?zk6B#AUQ;%n?SgCOmZU7{a7(GRdEpKdJpmW{m=<~tYL=@ZnN zk=g#?yVwX-Ap|UWl{HJq_*rbRTdV{crgFTU4?dba++U|k?lG(qZqy}8Od=xf2>w_< z$4Zz`rj-#6-6=4q3e~iz_^`6 zlrCYPu3}4W#OI3|Hj$D`ye!G6uWxsxl75JpS}~EDB-Ugjz_gUvHK#iz+n0q-`LF7k zAU|H@CYiq9?>4?kr#!6G-mjx98D`>QFZXoB!5IC0VrOnk@oD$qouBYET5_fjMq z;LvDt#)mT)`Z6B$hJ8fd7Q@61l3V*>UzwO&6;b<495vMGT*8XdOIm6cH|sjg7_Gn| z#>Pb=Gz|8X~Q*$x+`Vj6^6c{4jkiTI{o+o&;B&rN$4b}W!X zqV~#7w}VdR7f^Ulu~(Q<7xsWyBG9F!Ar;jSESysWmBz13(=`j47tsin37$hjX1{ib z6MU#Gx$(=dh-6~6YsnE^*zICE3BqyFVn<#NTj&e}A}4pG*mB25rB^*q^h8KS z?vjcnX-6qjZv;HNsP=ex&;ersJ;YSW!Ch@SUFnh5}z2b$gL=}%|5Bz!)$!X*e>_? zUcw0QLlXp|OwMCP)@6n-oy3-Uw~p@0PC`%=erQ9MKO&mjP&VyQ$W?^V4Y)Xu-lD5~ z;ArFW$Zk8K+G+r;O~uvBGFHJBFJwHM{VJ3YcakbJr{itVVHK4)2Z0KlbIKtH~(NlJ&J&n z_#S0yZ$w5yFNl&f@+vUfEgjZ0Nf8^{n&+}vBDPf*QMsg(m7l7|!#*qI8v%BOjm>y8 zx^++14lI@JD6wk{p%}u+c)!cQ-k=E=Ee`D~FT^$`RgHn@Tf8Zx1(JqYYne%#c<$zR z*1KrO%_w2nsuQYU6owB|i|uLT2%S#J$RI^=znK?D7MgN1hbY{W9hCoL^kJQ@@O`hmyHX&?9y@g`*@2k`%qT(yo1re#M`C{Qyb4m(HvrGjp|FL z1qT<$R0w5v;h5;LCOp&G!?EPel0#A)rYV~ce2^h$us&*=0#Fh5^UbKG2lcc2SM~lG zP_Tpk(HSnDq7|HF=x&8`vpKW6-geKoFA-^)wplJv-_O}bYdiMSk(*3Hw^-L1_fD?E65DJo z%rZk?pK~e<2@{339d|~JZWW0Rc9B7`lU;bDcflNG8(HH*e^}7af0jN|;`g>AzKgF| zQ*XV@W^jKuBH_1*8NC>^{U$*NxMtjE3c9gx8ED_nDU2_`)irE?AZqu>PGsH3rjQUu zTbR`A;(=u2HhyE3iP>h(gzhEQRHgyZm1aBNWQZTrQwsJ;HI>f4mTcoDF>2Vveym*; zg__l@%VTv7w)b-*0<{xnxSA2Hux*;sBwkU~)AxLQ5gso)wdRUucpJ35?UmBo)w-$8 zKIJSiSBow@)_O{!4z1DWUqhRzQCB2kAyVsrdPzq>DqXDQ6Ej^@pafoto4a-8acY#`)M-Oau1kD zo6HuM4`%jBJ8w+bYjbg$VrN4lD-c~^5Nr)xq^+(+u^QG1r`cjo;*iCz(cig&hvkwF zkGxGXSYy#_y0#(cN-SKmZB7AQM&A;YB;7S!$O_q?f8K#p9!v3ho?4Wxt5=AKTYQGv1HD*{N#3;!8n8H{E-hc(=Wo($?nQ$O zvinW62x7Af-E)p7NWIrSMdNBLB2uW$A=dN^TG23Sl!mSlu#IDk^eRe8<%sQ&=n!3Ab z@VZMX$z&D8#!@rd;jzNT+;eciZsrsF?IqVKFuID>LhIAUXr#b)T84A3@dnf6$b`zo ziju2;j5RiW@4U6UxyGf0(z4<@*VkQano)nfnEauc*%R&Zaoo()N`#09Mv8`K#3ZjQ z(a%RP*ka;%4H}zoQWr>(WaFI9nTkl5lQbw@%++g2rfcXv7cIc2bVr`99-|8Sl^c3V zZqfxFyi$GP#f>)2*>M8tU}Kmvtx4C?un7Tm(*{F#D|HMm>38}j=y%E=y|k!q;PW51 z4{5vH6^@gBg_1GX{&sI}F`Z;)7S>3nYhw4b8Ba)tbL(Aw-`G+=&%%0uKJN~3P3J8X zE$l5|XRd&(8t=mKFkLd}@`mUv6#>YCdqj)v8dvI zxxB2>)&l({#Af$HP3~MotFA=TiZWXLCN8KjeEl4g)X>E7rX@MBB8IDFA)?g^_m;AY zpiArGvYZHf1yhU<14b(*bBMLp(#c64R~#5!V+cr$*RZ*;Zk+jm2$ zGN()= zdT2s!>8aoGZb_Lzo4NgCwjw4LPy;BwRU@8qG(-JF8PPjnWd~7ps}-<78AFUZR>~D; zeB1eh^;29PiB^UgT>&F{vW}p8sc4J|w#@DGeeoEoTL>7P^Fl%s|G??8%gUw$TAqZF zfB}wEi%M?mv(Na_5$!%)?O#g1gS^GMfQms;)ilc;pgXtui3_|NfnLn zp@1rhifi+(dU+%Io*Doqb+&h|vA{Qa+?-F>?F?TR#JE+R*A&MJVp2D;W@N@TrWVFg z_^WLJ4$ve^7@uNnDdGZmGsboE#5S1qD2Is`#3sVGifRY+FFPB;=tvrTJ>C7HZ@ zwUMNh_!^anxlp0_9a38nC7G~Nh-VE%ZgfOZy9}(GnI8)rOgGvcVtO6~CfwFvQe9=KCDU}EZmj+h^-2`RxPwwP3sunW#T7vhQ`j+>(if5~Y8OU=~dqNWnH zvYQv!n$bO&tXt8|Q`YLfEao(`XhEj$%Exlr0aC=EcERC9``WOM`obv_e_Rtw5{-^2 zJ;RhDamkx|iEFh{L7SDrXfDH z#5cF~c~PV^nx0(1q)83st)hw{C(>1h-Z5yh0t-cVy^Lf5l_)_K<(@b$QHsQQS*1z* zk~-N)OdMki6uA|(L=upe)YSorHA&1HC~>t$jpa2nypg3wZ-^$ujrtfVJPi^CbukOa zaE2R*N8+?JO8O$aD%_@*NK!{E&QwH;_g+_<%QGg-I+1@88)Sn*QZG}TbDP|yNar@F zjLUV9B_?hXQ_|@z>&Vn5+fz|cMp)^q!DYGLxD2@IVVy7@@Z-U|jUUEhY41E5SRz7lO@;># z1ASrlP-_M6@S1QX)kMn8Vu-YLCwM|B;R#LS&L%OBg%q~lzF>orD|2W3a<|ryCIu@9 zFX04~O($AmjkPyy7Tcjqmu}-Zqw9Qw=OKHZ74gq0*&StG@VEj&u7<{5QN$vrD7*87 z;oWtkk>pPp#7?HHc@!x626VKTicBKuGm9r-wN!#Y>Cso1$H&g=_$K{-RB7llCn7vx|znJr&E61M^Ej(Q4PTr(bK%*D`B^z z_{wrwvQIN<4i)ibhhD;9K0mJoAc`tpx!CSjX@4CW1H`s(ce8ch#yQZufK8Kb+^CI4 z5e}G1b2j}4wx6sQQd&BvRgFGGYo%502-@yXNjdgqt!S^mvq;)4HLV|*+0@|3-u@-F3@1_9=|YN?_cOht#PcU z_P8a){i!zEQHRsTWhf0xy`BNe%~)+VFH);i%niqun&sZg$}-U@(5bUx2PRRCWibun zW1AaMc4=n5LSwT-F*8-AX>;v^>2{<%ZkRofDpANOIK$IV2>Az{BC{pMSgFcx;Q zD2CwTu|$;wah9&{iJKL%0iw-SffK(Z5$A8zb+r41ez4t;R^Jw%$e?v&8t#5_#TkdR zI%1oAk(zh1Q!*^L{eTd&GIN+nTdMD(ri(>a8$=^4i<;E*0X+D4bQ^odsFNC65~G}Z z<((6woO|b;F^WrqH)TTRx(+KvX4>Ia35sOX%(*8%i9LZ28x#bK$1tOe$Z4$2+^{;x2a+TGiTE!vrXhrpd({rSFB_yV ziNdh`nz|+%*wWfm&0te$-!}WTGp;ad+7grBcH7kRX|lvHOBz8#(Iv2-0oueJ%Cuc2 zl?tS@y^zE3J5j&AnV=c4`k5Gp45&q3&*U}N;^eLPkOI5@T=P{8qi5c=bj}ImWev5y zA|9gKBEq2BQ6nRxHl(F_fJr>VaGTNs4*gB7w5nFKW~iDlZzS9lN#GOqm@u~rPGE`* zp&v^!%SVY(nF&D#r9NPIbzLGu!dh3?Z+M}-dTeUzkF;$@Lme~rgytn2gB5m^E+eaB zyifoYUYXjF5VwwIneV28%8oF(L)}ys4qo9JT`<~ToAJT@MsO&M9gY6#Q#B3KNq4-N zZEqqihZn2&_-f~xYp9;882VRPwJk;!!p$&n`m7ox-$SNVaf^br+W_C34%U|V*>3V^ z?Iv5);p13hDJky77(Zbon@&nN2^Wjyk%o$W8?Em*Oh^khh*nE2M64A9V)d;-z-yl< z8YF3Y7+sCz#D6W{8Wg?;>Ux7J5vM9HQI|^TjoeydJzgRI6K)@MHW#%Qe+HWu6R?P%~tDfu&BX-ASqE zaJbDn$)~L(sm)70fXR)-V=h+iyxD6I?L`)^Li8DG`=~V|>|4@d5W5!knrbAbvMSdh z+X~gZdz(`&Zff&nBO&uDdneM{sVQ`?^ACO(xeawSmLfOriG?w%bOTUP7?rKap`Uh# zid<@%^!@N6CzZTTlS+|mm8xIlQYQiH(k=tI)1zs6+MO*F?{Rjq3-4fR>Y~@9&zuw` zHfl8QR&05Z>j3VgV98q?lsvc*wkTYGIF}-aG0gNu4*lXc6pI`Ovz=4qP}e+>^QhyC z8?8U2Xo>9P63m@%h^G}ZhoY()HF45qo`czjvHsw3o2Rmr$x}0zix(Bhx*8-rRE-{N zgr=^|_QQ(;4S;B{V{gMOhO1`3&+TZ|LamCzYnaj#kfn6ysz0bCTiR!V9} zmFnz!lYikAl8{5s@*oCXypSLo5dVfw6w*0hNVy{hy{~|D- z4Aa~{b*XoteCsA0v~9h!BTJjYFfC#%JcC&EtK7sI&Vo>ySliQP$Yc7iW#N z-0l+^2i1-jZ`dfVXLQrNwD}ur>~K;o+K{1&i~AS)B@iWWvR zO=@E1A3t|^W8U1KtcN#>n1um+r>7}0gCm9w3Ik16*gV5~U2CWvY3U4&?xVyO7(l9>KIl!TIjv$?HX#g~hoYC|EdCt<=KT818oHC3G zkmgzF;j`1+)US%8G#1+vE-*4uC6x{0=a>fFP|ey`>ojK^EVTKnBaEc}HNL-O13B2J zHmry~8vWCe%sXkc#yVVE14-t~TsxVw*W(JP zl}jY*`1Wr<1Xiuar>Z6GwR-{skUp^fS% zgSF{O2bdNcK?_!>kv>6Z<&WlcS!NX0Yza%Em9GWW$}Q*zAE@2%iLEw3%x|b&Bo9$R z+)Goics1wf;1+c!mgN(pm-=7Y)naMenrxZnk2;gQwKXMAE@R{}6dO;v?bNO6NZp!wwmK3v;>nwO4{gyQT&DA1f_yH z)0hZwLv5`PBdJf&X`7MGB^E|&V>6ePCiWzLVu#)0d*ID!N&|EcW8z73`hqHP7=bQT z8gvAbpJtYBp6iHwv}B=}crmGIpEM%8l=qVJ{wr?)D zIVrM@OJ~#yoQ!=;?baWesJvsQ&W)PAmyBw&WIjmJQhAppBOnmWd%7U6z@Bc5<=u?) z&0D7@5Xclk;~hSB<8Kj+sV5i=41Ig zeNx`V`crDPVn>d+ihfMPM^S)r819s3$c@?=|Bf`xcK#cO>|t|cXdJ>FzMOC)Xyv#rZ?D*=a4-L-5^Zk zri|p4-XzP=I0CK0nM_|(pcHx6p(rCQ?OKNlx_#7_t(+E;S&o( zS#6|NQRrB!eVRfCiau1^qlIp??ow{vic17!J+X|Csq~^SO|SS;?GdHyCM+rp?wy)R zXx4-oh3@%ENoHQ?<8LJ)<4K40Y0%gtpZDCT0~Zi4@kn)Mwu#v6#`T&hiol%}@XZBt zPxvj#ot;-S=Va11izWt3lLDaUG-6mkPpvR+OrMYgbqAEi^U{pgRlJCZmvS>H@=~tc zYb`n0QtqQ!X=~oeSJM(6F{mn*rXV*p6bljs)iN*gkLkXK&EIiWhCmoUsjy49Tl^|r zIpn;pf*`Cnwp`|cOj|9jEEJJ6%Wk23!D~TbCeow_h_y&+GF=>O^nvsZW|Q$>&(mL0#w~>lAUn9mziPsVAu!f z${>|#5EtEgc_No#u0xraHFC^i4Vdt6ienCTUyb<>uzC-ifsfhKrein5L=lRExsGp! zM`OO}aqq7${W6h9KbR=E*JxpLsA)#?boCiRU*ICr53K4EiPsky~7#4WtcCYzs$mdX@{RtnGfPJIPI|I-A0X0 z?QPSm_$okay4U6cr)1~NMI=benYc~ZU>+DvWMciGz&(k}D$xq+qb9%egxJgP-;*3( zOF<@flWogf#jb8*H;c7F;u57_Hisl`Y4kXOC+;SMi00wS!G)mI_7^-_${c zNG*x4E%a5yD2pt36G@N);nW@jL|D_Z4d5`D)kH*FZ$NU%0etF-3Db;pI#-^Md!yvU z=8TRqQYh3=S&bGtcyv2AX-1RAnhD;UK{Ucn9!3Ge7&~I;X2YQw}Nq226h z1MT$O>}l+UrT&8u?MM}I_Ou~21FiTLhh8%T)qUTkW$T0~BXJ*qevkPj4)`SU3tvK} z^IkQk`ax_;N8yI7)os(At;;+2uc>GBBiU^6;b74cmteO3eooBH&gHwiu?DSfcJg3B z;8jtZ8XtVqKK2^7uq@R6tvJrOrC;s6x!QZY7QED+F)+in?lDUN3xSYN-xzF^hCS-) zP3%DnYy2~XE9!7~1Uq>(WPHEzGe;tI(kQoXK0?Qy)bC^%)Z8$&pXoOwE@oq(`C2Ls z=)B5M)H^9fKCG$L*4Y7*#If4s46+$7AF78UFsf%+GiKzd5mlpx4jk5hAgg~nO_rCT z_zFE0skp4mtX56U!$r0zS1oe$1~DhZvBm_$XRto9kRTdO2x?!abw7 z)#&s!T5Kq4eueOe%**KO5$mm^#w_VlU^k~b<%!gJ{y zmIzRsbbswfpt~eh$K_+{nT?DL)N(Rf%6sWdmI_jwL8@f5oE(<+UpkAW z!z9dqI!q8BNKP>+-(pJzK|77J+CIOfg;^?8UDNb7tp%8|#v${D==??47K9}YQFsLEmY5f&iPm2*xy-xwpFml(j$ewNJhboxcsmqn_Ad@7d8HiK+?gQq(ivL z0h8sYH;7}WG_wM<{zZx`2`6X+_pe&7*MQ-E3EJ{=>jiTeuR#2Z%uEX-e?mS@Zt0HH zALX?s+tOn<3Dvg7rg2VIjECvhIIbV3`A}{djJTH37e>M^WI`rn`OC$>ilDy`I)=_5 zhj|5_9YfbJKgCLFgbJ!FA%3I=p25=R=Zkf!qw(F z=lX_4$#f1CC5y0M9p-2H=4!)TnT4TGN$2cX(k5={C1GJMkm6+08A}}H zPQGZIE-3Z#=rrpIm4Oizxkr{LPQQ zbBMVxypX+1rO$NBETTq>DCwdwInzSj0^$0GZlxG7>EAi_JD)r%2y;$Ym|cL+98!Ee z_X2TS!t12i(PH$-Os3A0GYhCs3n3KhLHTFSv9J}H*TekW%{l6x8B4nb;=c}hQ1Usn z?t7UK4j@j*+=X8)WxSbZN1%Tzgs$0cl=mD;I2gaXLLcIU%q7^zmiAp)_3wz=gQS7E zVj(GYB!w1i2T=MJ@=$HMlJn#eZ?&$Wb_Jy!LQ6aD)+f}061VI3>Wt+;{EnGg%GNPd z&`O_@&wI345A0WmRok^FBe9ZnMlPH~{K4eBATt^B zg3vkFm6W>jr?<7Rj^q?HHs)iUYW3xGIbHZ5i?qhGZ zg}2p>She<7L5h?4ldZFvXaU-EY*@$sXa&;j$lI#O4W2vL8TB3ir(WNcH0h022h~S3p)={OO6znk>6Yn;Um)fSq{4{J=za8| zChBE_`JGSfKx)+} zGffO-7LHJIk|VtsXTQfNAz#XY7A$Ao|&*>C;+bX<+zpOR*qXaZmXKl3godO zrVe1Guo`}=k^gGsuU;ESJxhwgQc#PpM!40%8vM5BFMtf@&bX|JZ7mC*4QumUhj3lM zy2M%!{|dr&CFJ^q+W>5c+eXCNm@u1wO^K~CcLSRdzdP6*^A@DGCC_zrD z2mU=lFQ67tIeS}f3b`)jS}$xvj@wfD?ZEa0;rn3T0qh8N0-eClY1`z&E|_-(yMeys z*N;+{TlqVLD$?ptc;!6+3BaBc(jl zfMK-8N|ydcVL0j3;5&Dj{--7W5BWCIIsX54^99lf|IQ6x`dO-|8JymO3Zs9J!>U; z)~S^2G;lgN1DuKfS>S8{Z3yR*-+7=KoDVJl7lKao#uDq1ThZoQhl}WuIS_!}f!^yh_~H!0X^&;0^F5cniO`!8_nx@E&*{XpDXUJ_H|ue}j*~C*V`?AMhFYFZdjM z0loxZfv>?g;9Kw=_#XTKegr>(pTRHSSMVG79sB|Q2mS;hQywxP3raG%ps|<3TnfrS zd1goJ|ApnQzywQ9rOVWrG2%s}N~WzdQ6 zqHU{SPWt+)g1tAjN#>wT(EbjH4BW>=%V>Mv^%XKk>Tc&-c9BTmd`!+ZJF;uoW0XeYVc*7J4wBs!#SL&0d7-4V3pb zJhuhgf$j0z)aq6q`e5FHymlmwoiOhV&VjmWrg)Ne*#-Nqpqjq4TRQHc!-Ve(`hhCY z9}EBkK{Xfz^gagj90GO+dw`*!1`GqkK`q!5i~x0%Z6p{4MuRb6EZ7U|4OEY$?e`)4 zzFK4ENUToo2Mh?VI1MdgTc_637M)eF(W#zcdYi?IZVoEeC`UL z*f%s~`h^2&n<-!(y<|n|GnKg0z{{ko`K@?diNAvek=pTY4#J*qE5(H_ zZC^!rp4(5X+z>(l6 za5OlEesV17t_Adtl74&~eha|y-~@0Y{wINx!Qa3sw8KJhD(2I`>EH}-COC`mXM=OV zx!^q9&IcEO3&BO;VsHt5mx9Z{<>2q&3UDR33S14Y0oQ`-!1dq;;@wETH`%-D6K=+S z3($MH)!vuhW3{#EZG`^^xEXvA-Usdn4}b@8dk8!X9s!SLL?QH! za^W%F&Er6vY0mmd2v1;N1gha8PAYh3Pm-42YvFr(iu9fa&wyvabKrUK0(cQD1}}k^ z!7JcZ@EUj>{0qDR-UM%fx2fYhle z1#Vx0uP}cNz5(BY?{NDb{6L-Bz>nZ3@H1||fM3CH;CI6Q0saU61R)Fk1zAu6a-bBH z!AzC&tN`smWfq{|oHpAW> zY!0>nTY{~?)}ROINw{91H}%nV&EZAb($9Ft7195PLNk1O|g4 zV0W+wSRMbNJZrMU;dzvoc(o2;82JwewOP@;Az@F-CmJ?_^y`4;eerpsapDI==SGsw zC@`AxjmdU3`ZgB(USMyq4)1eE(%6Tz_67Ta{XsoA05lM$5sU-lu}{dZN6O`4B6d$B zOPnlWl@@h^(_Y=U?ONKw+hCIUYi#AhWZJR``(peKJ zBGS2-zIh3_6kG-_&yEOxC(IS#O4{x!a5d?SrHt3`yp}lEf$PBy*)ed`g>9ogmbAmz zaAS6_a8q{gaC3H_a7%XIaBFtIa9ei&@Q-YLxIKG7xFg#T?#woZyRzfLKeOY*-K2L< zc0#x}J2Bh`?gtNm2f;&>X9w!>FwaN8qu?>{ICz3`<@;~W+FEU{c3p)380z~Z<*nxV z6wjx@GvHZk|4HFF%2E;9hv!M>1;W3GpZdvS{52Q9#Pem!4Ydoe;QuOk4ZM!K`qaNH zd?WoV@ekn*+}^~$6Dv5$cHbiHy{Tsj_P2@q4(Jpb@PW4`+iL*XVcDx$eM(mGk>#n?XJOjPYpkWC`K=?X zQjOIYvdd2EJwM7$Cqyp%hkQSy{{Q9q zc~&b`<_X4qe$H$md^7ESkk#`G!hIR*q4r(OYF2IdmASVfA894WR^l8KzRtFUZ?ZGO zxA>`lsBfr`RMWQKWhXJ3JB07)XWx;|58y}e6ZjeY0)7R*fljQr)#o0deSgRPM|LLZ ztA1^~Gp!m_2c_iR`Z_YNh8#XQTyN+so?BWa1pUYR^Ql^mYNS%t7eW4Sva0a!8Su`2nj z237}a5Wh26)6yvqYmvszX&MwgN!VtUNemQQ(Dk9b{6j-*XhX69@QdsIxnJZyk{ z!&uLacy0_f0h@wq($t*Yjd+_;zV0PQ$GRL7HZM6gY*BJt*b=|3NTVYXi1y2ETeVRx zY;9>U&ttAeTCqZ`W6zS_p%-qdLvPaC25bwq1KSfPc}LYqH#`s4RFrQA{B{I85pL(0 z_Aa=qef9o#Ejcl^2Wu(wcfY4SRs0)O$=^C)QY+r!az&vV|}VH}&_mpido$ zKOEF5of54ta$!&6kHB6>xK)teW-RWh@%^gbpB6@zoE}D%oDoKsoEgTHbU+?`R@jR; zdxL$5zc0`IO3n`Zmz)#hHH7+-hHwCA0F7WA7+-R3m_Yc6U=ndAgQk-6!ht2{$2xhu zDJ2(#sU;WUo(t2!^pcBWzwt5COj%pNVqzUsaxrf!7iN&w-q}mcEO}IG$)(J6`F7BI znHk^BVx&fGq&tf^vw4aR%_+Gg%q6XP*bfGWfL8nu1&4vd!F+H8WBACD%i>tSJRC(? zj|RsO{#bAvSP=86MhcbmlOB{zas%}(jV-i6&iuUEyaC=0ePE^qX~g`uufW@cwaqe9!9d@G*qFi08%N5}>+W%JVXCIqji3 z|DF7=D7k^T!1K8h_p89wUu#bVq!4vo|BEKh@OP(Ul zr!hZ++p|2ME4eLA<9Xa(ApDD9G3J-R%ixv&GmU?wX>=#eSHWxK^ZH-LV?B%i8&+oR zMcf|g-yPx2k~_m&q@lU7TKhs)M|c9lzXRT-Ol#0r)VAs~)ksHuo?{)1pWNT)xfqG5 zyQ^R1!Uv@JA*ePfs@e^{2mBihCQd?6`nZ3@H6;@ zG-lxUE9QCho!_wk4*mfD1ApSaA(G%^{08*Ij03%Au0B;=jAROOSu?E zV`nkaIeHHk@h)I_AcRc z(iYFGF{-{Ln%a>xRtDk~I^`aT@9WX93TdngRs-``>6akMUY+!P-Ss#!)MRauWeu3M zHQ*Yt4xM?f3DyGQ@7E@cbwC%e9(>liBuM#|2r0-r^M>k_)*u9d-Nq%HoWd#(%n9Z9*L z44YFvt?9QQ+?HS~ur+1uLAZ^G-;-xA&>L)H<99TTHjBiuPwv^U zL+-h-W3EHk3G57Z0lSi(c#GX~zP9g+U2DpIlt*i#DxUp;*7gH<4g^}`SIZ1vFo@@1 zFa+!l_5eeH=Jgt$D-(7YX%43zdZ)EK_XHzA9T*8lfzi}y3>XXc0&0uBiMJ2f7wkt` z`-6IL0B8V>U>q0^CV+`x5||8{z=2>2X-x&w$YVNa1})eR0y8il!JBBsJd?0(U>0pM z8_WT7!93g!Cfp+WgyD{88X&a11y$$8L7!#c*71 z_ppF)$Ac3{YaZ>kD0_7{F}FCJl)E6D4E~m@45xsFq@Om&4iQ zaZYZFa4v4=8BB4{$rU1KbJj0{;YegL}Ze;689acmO;I9s&=8N5G>w z?N_}P9>e@N}ul2JUZ| z`!j@n7KpBOqLrQ_%=5JS3%N7d@z(C*nHElC`bEMl1}}k^!7JcZ@ETA*RyyiGuTzel ziK#usf6=aQfH%Qgr2BU6&F~I+yqkNAbS3M0KCEkP&3r{2-UlC$&WGS5@Ne)jZl8cp z!GFMK;J@H=@CEo1dFmQ>JUni;g%xG)c8-NW<-whiPZey@X>6u~E zQmqSiN9XJHuo-UM!RBBK(%!Q4J!|8wO0P!VcU9OLw;n)y{2CiQNv{{^P55niZVR@< zygko8UdHr90m>t^T83g9SM#CM}uQ@J1id!#}WbJ)H4yj=hI$IG1$J zE7e->LwLUS;r!C};R5_F1Q&se!6o2Qa2dE9{2g2YG-j?W{Ro=VK3qk-t8u#qi08Pr z^xyDMxo{o!>%k4+MsO3j8QcPH1-F5JfZM?xl;uuv7v_J0yTM>~&y|jNVWn{oxEI_9 z?gtNm2Wf+ccs>jymw1Hdqu?>{IC!E|`aPdO1EE!feG)tcp2qJP@)P~kI_d-H!x(ny zI{>&`+Di0nNO-n%_wXEH)o#!8d;z=&7K4|-EaJXg`k(Mhsdn~1Bi3gzF0&8*uPH39 zpO)+z3FmLmG2fPd3qnz)94=DGC*gpdQ1|Ne7 zkgbQHYM+#T9zHGoBK)WHOWx&w!)N$yNPfpL-wj|c8)tI`bd>UZj^7vHOYjwt-qP2l zUxoP=@5As7@AX^W;diAUhwlk5*?`kD=qvUg!B604@JnpN9+d4@@EiCY`~m)l-=9F6 zU>T4FYcR%2%8-6yE(K-a6xyWzbvD z3IA1q_`Ox}TMdZjt5@=)&gsntrFG&UCKIzb;~-0^>FJ7)-Qt>1{;Enz{aGv z3C~SIH?SG#PPom%7GO)T71$c|z^^Chg}FD_2J^OHJIb~_>GZ*E2e2MZu_Nv~ft~T& z1?&oT1APhCk1$oBKNtW860RBy0)w#+0lQ<~gXd6CL!4nehl5(MCm4Z$9T*cf2_x|z zg?TjTk16{yjK#heVfF^n+j^Kb+6VJPJohczE$mnJHRI%K^#<$1`{P#+4gd{6@{C4H zTbe4&O>s@Lv-%hA<72)P%D$zqLubiXyq4CNq6_O~zrzmgCER4t1P%mKz*H~|Ob5-N zg|Z&Ra|UQ7otZ%IbPSp?o1!JtMtNp|rTbPk%*K5VmLJQ$Rc)*)rzg+qBd z-Pe5NbpJ5?6WV_`=J}v_4uFp1b|i6+0!M>mz_GX;2gX2O7EtCBGe5wi{XlJhFnaq8 z{Dt_`PONE;FZ&U>%ulTEe-0j`Z?+86g$n&v29ZF%OZx=-~u--q$l3 z*s}~&5(93M>EDb$a;%K>IVD@Vh5V&2p#9ieG2dqK;m0xGj`{7m7+gx+Pr#?(Kj1U`{)_wPn7;sDg0H~W;2ZF5S;%|`9sIuRm+(W` zZ{bJ6{{(&}&M)9s!u$q)$NUHG{{w%5P!6vQvY-UyKq)8#<>k&+Z^CW^wguaP?Li;l`)3uz zE)P49{*GWL((7bBnK45ct(SJ;xii{x3b!kH><0RRe&t)jk0-pV=)n7-3b+2{9m0U} z55hp&rkZerz+f;0>`q$ZIriW=)beuOs}(ci>)K~(%F8mt%2&t?FR#qhmVd>b;U{5F z(i;Kl%G-yLU=$b)#(=TqD`xiMxp#So%s!;IFOWQFKf>={E_(WXs4uU`98fNqO1n%$ z`AV6_a;@7d!?^NFYlO{P%i#*<;+Tex5!wO&X{z_6sJ>WBIQr^*)=97VV_KX z(oGdDyMn&op=6azcl?_0I}l6(Q^7Pa9W;X$a1fYLJ}k7BuacQrzG|kee6`Fh>M^@~ z^~{{|H8OMYp9c;G()T)q=b_**AYIPGc~|qn5#R#yJ(A~9U@QENrcB3xV+ng4&jsLk z%qM^o!Aaoc^3IvRm9LrUXFEGPbb|oEN%ED!kmTw5#R!& z{awP@<*S5qXzz2&SI(SAnllM|e)^sXN7xI&Mc`tfwi*E)lm74}=SAwg+)!-W3t|g!A!1dq;+-?MmnJ#bQc`og6bNOcB7TWRF@*&|id*|ri;&(e( zgYkU_`P>QaBCUS{&HZE0*jx*$+b$y=^G@OJ@=oC%a4+HR1NVamz=MQ;2s{iP0gr;m zfa>!&&nLhl@FaK&Tuhv&X@_UPv*qi=_qrDIfF%9PYV$6P*X8-4*GnDdp-sB_a>J~h zd7gY<055{Y;3c54y$oIfuabu7`aIS*uTieo!N1B^4{y+BZG+pvcL;Blcg?&_ z8t;^^pLv(`RQLCIz7IYijStH=_&?IvF!K@b?%#yhy7Xi6*ZlYiZS^VUi$S$%#V)TM z6i4|goYGRAH_nuxMGK{*A0t~S-z3v+ne|ZE4&gKM_^;)=X=aUOhExAn*krtWn|@Bd zUw|(yF0vY)7f_C`d42<`O>WyQ^DXV8zW81FX3Xo|Gv8zX2K)ei1V5E;PQL5|VEzUC z3Vs8>gFnFkz@Mata6V)}7H}{qbVnOU&{EeWtv#a5Y)6>DTx2AwLl&a6WGRl#atb+AT75Bh2ku_W{r<}TdU z1Z#oCXdmm0!rJ7$4(L+R3wzJZx|r7k)o3MG0#1kUPMFs!d@a3xMJ4=9JNDO@<0$Kf zV55p{==a+YY#YL&AC237#MziKZbDj{f^HStW;&tW96)iH-kHtt?+!L6-WKGuWyLP+ z=R*r|+nTcW0Q*DVdSdSddRJ^my*h+#FmDUC1KWc>#NVM}duYLueNTNj$bpe{eB8ZZp^;h+}m2}V$cx{6L=Bp8MNXfTF2W5Hhd?+y0B zJR#dY>`U1FDt6*sX&!GM_NV>o!2zHFG!j=l{5ZmoSDcES3A<$bsLVTMCX%l7RR$Ah zFlkMy*oB#E7g}N$-kIk2T{DyMlU$;Sv<|G;EwkP-(@MtQ>S0QS&fj=n7pen(yQB>wwaB&BiivDmRpw`?@j5jPeEDdQjU4xVB8J?hgJ+A?IqjP zLoD4@I6-hWX`KVk1?Lgwe8OJ%k4+#)>_lGw=%h+zf63w}RWiKgd)3 zTs5Z`5FLfval3;!cY?d@-POSVq62{Y-PrE|V>sc^h5YZW*gbO}xF0+K9t018hruJ@ zQScae96SLQfhWOJ;A!v-c$Ts~S1~m6Jn6qcSzaXH#XvHwm$1K#`zzp8@LI+2%ssf@ zf%$cyy8a8O%x{1@IUY;faC`z<&Xs>AO}i887K!8pdF|L z?ZFCQMbH7P1UiD1K_{>ZSQV@WRtIZ<&R|Wj7FZjs1G<29!Fr%8SRZTvHUt}ijlm{h zQ_u};2D*dI!4_akuoc)E^Z-3UFVGuo1GWX*f$c#bumji;>;!fOyMSH6ZlEvd2dY4S zFaQh$)nE`942FQ+!5&~Jr~$*ka8L{O1S3El7zsv!(O?V<(y=`E0(*mfz`kHVus^5= z2Y?392*!c&U;>y3CV|PI2^^_m=2mj3pfbO0IgsqXalprY%mAR1@pkc;1F;q zI1C&P=7S@^k>DtBG&lwv3yuQ|!13S&a3VMfoDBX3PH9(bV{##8^}nAO7ou&|oGR)J zXc?m;`?;z<#L{SB<{Xu7JYq@HO|$%n~B*`&>dt+n6Cxb zf$PBy;Kp`dm#sJrbue*nBF~$F_}g1}-b&iHfq#J8!5!dEa2NO|xEtI9?j`Jfq;)@d z06YjD0uO^n@OumAHh%L{WJIl{0e>}{_n*91Hb=)KLLkRLIz|(34)s( zC@^sk{GJ4Dd%XSJY;Jza0fPEz|DmfORWJW!B@_m3Zq{j-l_0=jsqPsO%6n1RH@nH?(kWqkmBBcGkX&eU@k zuq)UN^d)XTAbwZrS7GiC2H-caa_>wvxy_Tjm2<#_nk z@uWYV^tDdx6!s&{{R`5n$9w>2u=I3ZgLMFAwbN#x5o`s-?gm0=d{v%!LjNwobW z$~=iO>)iBY>{`>9UtVd9;sp6wjld;N6UqA|@;tdx=c1=)wg=RhcH4OiE~lq^vuQJ5^yQ+ zf~#=5nl!Hg*MjSCyPl`CP;|a~G0@)TBWQSE3H{tP*FxL2 zP`?)Hhg^&FZzTLpmF;=YoF})uI)qzrzm+z+4g3S#PMABuo!~C;&&pN8-IWJXTXb>A zQ~Ouo5s`roYv+vDt z_c{9Z0j&;LHp=dQii@UC~Qz1G@muj$}cgZ$iqxie)jK_j=J9(8XHP4jkkw`K==5T;CMPF(JKwjUGz z5NZA-rEKVM%5cgnevq%0-aRymM&_DrB329NF7(^6VaS>=0*{bCwLh8t2uwFv%he{I(s{e|1U_tk3Je-i{dv1IlLLfVcQwK`?ani75kjtOrxt^(=7X0$Yl(T z@VOFcinFVlX(kgUH+FfTDfLogpB-5t5a^ypzVzgID<29a%|))l=sDBB@aCbR?&T*) zgO#Bj%Xz)|CO!Gk={nM`x#(g^3y@LJ$&XzDDCjNZn|mQSurTA96-ww>7_$fz1v?k5 zxU>#+QK*<_&wSB*>vxog;`oWP6C9ByO`7j3ft}Tx{X4{85=ud7C%^W)#8cUO z)I1NZ-Pc@gC3dGrS#4MaKUQW?m#pqLVqX=ifzB4Gj(HQPy{=ZDTF2YeO2; zfx1u+>O%u>nHd97`WvEyo`>{ogqwXQ=pC^%)EK$aLH$|nxo_e<&Ug{)gDDGEH|g8a ziIcH<&P@rQ4qce*ZbsPVptZN{%y`uDjJl)v;)!?Gv@B1Ua;mv#Jr`R}CHKh;9Tk`I zQ|oeDAipJO&ZrzEtRZ%BxEZ@vJonb#Q?%pu*{V$0b|^FNY+2DWQMy);SBi`EbCl&< zkkJP2LTC9agk48Y0?^4z(jizguDYN+XiMIyooYvz_HZk7ATK(4D`}?#9oUmc`*((S zh}waQ&I)?Cv8C^54&U8JA35`r|$T z2EzUDfVYI_w}iU21pSx%t8S?b3_=%Mm-O5QP!IJz!WfC!ukJa6y?o9PPkka=mWN=f zj}z2~GL%KV|Kqe3%V8*utLA2hd27h0HN?AycqQ9&9wa`E!TL$fSwmyLdxm?OZ)IH` zaz}Wtgi3JY1EX?;QNKv{?7cQRk_V(`G>n0<VLA3sz?1M4tbnIsrMHgqqW!^2-yZU5UFaF? z)xUZc^EpU$J~ZX?d9Gi87hx4LSHny2GH8AK8q8N~+erKCgfBtZ?c~K9@TRAI3I(0Fuz#C8dkmsy&_!akG!wER)=_HbkHp0ZASKHY&N6g#?a5Ej%%NZbda9ByHmFCF4=;gE%>o(pyl?9x0UzS zR_wQ8uRcQ1{xBX)JinQA+UI+L{P;c5e*D4ppWZgw@@<6OM%aSRMf|p+p8iE%UIINU zwX1)7uak#rQ`HXGeEEkwa>7BF?Y!4@P5+bwM-w8>Fj%2={&7s89JyBk;{bN`7b;5ZCfSnN~AZ~m&rUA@!GvVyEAn|uRP>MUUbX{ z|IRbX`7oq+;6>h5+m&~u^E&+HhXPO#3PE8g0!5)%;u)w7wdver`moA-#;8hrI1@1%0O8t2j!sxRD>I#5>$pNaAWwRL>x+k_OQ`M zG8YEgftWhv;?4j(383ZS8h-6rVT|iipXv~<5~msE24ZNguM+TxauPVLa6eVBd?_8p)j`Dyz* z$$^#NSM;$u(XS!>>TBPFT{q|sJ)kFg^+NyN z$h#N%VAmJ!E_qw`7X z#);5SWDmptgD~9W$1%$EG17g^qALnGO z8KiS2%;J7F<{X#{^I$$KfQ8}js8O`*ptC4$p{;4-ok`f~J31(1XQ>DDjj3N1Ic3X+ zVJwk+wPo-J($2VI_?-C$l{~elkA#0DoUOZy!{@1I_N+SXJ76iWvxK~Sl(fV-r7H{J z8&PvL{-m*}$B@0$q~&MaehMuM{}g&0mctXcJqb^Rf8m+fIsFyfKMgD4neeYhp4=q2 zH*?!6D^uuO#yR~$mg}*94LLPw zcjKH$roFfuu+zA$&*@|uw<+dmA4srw;}U71w-r9)Y$Cp3kJ@IFZ#u=yb+#aHEBER6 zJCZDa^gv*>`;XD>b>we{H$dkqy@~l2yiK@w;9Wjivmxg_uHT0bU1A$|Xu?FaP$zLE7ezkfS`^Pk5c{dI0kvsLj*!N=?27IiB+| z<@8WEi>r0n+CQUjd*z$XJCLkC-0vs+Cxkr=+Ef22=4X(aoE6>wJ;r&GG#badkrVWHRe5ZmN4JL4{$CVC2rYky%p>0(D6L> zKVfP-`e)2Ir^#`4Gk$Vp$oK{OU-750+~2~f==NV3Hhi3u=Q#7(#CyTWx;7yzSBCxX z#y)q({U7E&PsaV9++Pgm&A8VbL!1-q?6ba({Iu=ZU--LZ!sh4sD^B{iCVx2}2we*h zZWU!+{oft5v-Ye|#?(S}SpZQWA+Mk@Ly;ks|2JdJ3+aVfsl$$s_9)!%qGC9GEIgsgYvjYcNKqJy(=r+^&rjM+W^z zWb3Sr+>sLI*BCiyFN<$ea3*{m;NiutGY0t}Z zUjZt@4NwUxgW4ta9PC(BvS}ZyL~78NwCB6tNE}u1R}Hf|=1ow8>zbIgFl%F`5l;bK;Tj9hI4;k?O|G$q9uzgR%;B zE*-zx^ATrnO-=LeEaNsK9|}ckIL)C&5FxLbx{2mO~hO zQQq2d-5IGmPg-ef&;70F*8w`hT-EX`#bP+Cv<_kkbgIHg?peI z?%kmW^aQ zO1mPo{zC{q6yluR=wdUBFb|Su>t5c~SjlkQM?@;PI)h#P2>boSI1JxBBXJuAqoIY$ zvw8XzO_`mVttZc_f;$Gcv7qxW#$k?!hayEn6CxGeiIE$qFB+erERoL6XrVLZ;@C}! zRHD8l+<3l|(QOJ;Osb51L1${Dikl1fG}`rP*r##Aq~2}Qkv{`wMyeu}bN{%W4Ri1_ z7v{lyPxXW!zADWa1@A20>S>%{nUhm4 z=OtHi7m${P=$!0Tb{7$!_HRpu&WL)Ld+G7WW$|mj!(!|-ma>F$rGD(Aks59e>a;V-xZf5Sh>;-DEP-H3ma>-$yR?Ot$3Lv1(e*LGvR@8p0~ zf1Z=mU+P>7xsaLLPjmBNYP^}luV@$SIVk<83whBcANpw??mC&2TRo@zTo-_XPzW6~ z=2{rD2oyz3G0fsn0(_P5`8va_o?D){DnKbtv##XS zcbB6_cG{AP*xdkXI|lI_^n5FEuX8{vV^)D1p(<2^>Tna(fE2>l#HF%|h0L+Mlaa(|&`x9=G_W%qc4TE6_XuU-* zWDYfDn)4jEu7rN&LGP*u@iW}t&D&4!Reg_Zzqs<0vu=Y1~hT8OWH4ISXdP9GL63 zbmzf*Sit>4KTl{8@jeWXAgcs29ne_wV!vZ(2|SA1W5`_!%OF@+^*GndWk))P@ooA9 z*H6MzumYZjis-C$bt}1k#=qHp)^FuL=eKsB_iu4uK<5`>6?&|O8KAXSFJZn6YkaNQ zX+t^Fsmg88Nn=D>i^i-K^45ahQJRl_mFsn|9$teDp#0s4Sp<`HrS2wQCpWc2Ry$<1 zaX0&I+%0~4mRq#Pu03{)v=i?((wmOXuM>8ALe3lL`6kclE%J?7T>Q68=;JtV6Xp=( z=I`K#-^&R3z^Db|6M??Bx;0s&^e*Aw^QA{K_kF^A;8zUo@U_m*>dKl_bm@TX4#-wd zS#4u5Rz`o1v8qLsr&QV!J4V;h^nrE~?=IL4c8>ox$_{l5O+Tbu?SZ|xsehKr3DN2| z*)bH=ZF^R97q>I^ooEg0IV$@IWBuGtp0OsCeAo{M;Glm8{z^JM&3wU~v&EJuAaRAj5v;fpT!3hz?_`w<^ikCakF`Ro^YQd=O>fLHeDyU z{uzGp`|z#U2mgJHtY1l6x|#oHu8Hdlg#F!w3;e6i>dSNOOPIcd3FK)kuLNfg*t6FD zAb*tZKmFeBMe^k@t}nsgi8Sba{tt4ssXG+a>El6L*$>(MaOj8Z;CZrwHA{ce%n9XD z+c!@lTym7}b2#M<;Cai9eSFwwi4LR;1%B;3X;$pj-_V?T68^G9?>F(d*k=cwr>yf_ z(>Uqe%Cci=DbXrCXWr}hIZA(#p%d!dAWkhGgpPwuo<*YU_k(Cudh#wZ^$y($lOsb% z%|r3cnN-WogS&J{#XTqJo9-E(uF2l7HbxDN6|0VoKCpfD6c zhoaF*PGe`HQ!F}|KECG^k2ZHoKvw#A*GGrAC8POyLiwFin5Cf%;mSfeC=V5&BHRF# z(6KUR6}S;}cAd_$tIBmX+^WM(Py=d0E$nNU3e7=M0JE05cw=Y!R@8Y^N&*N^)u5b^2*YZ5N zaowG3jW;CImi8bGYL`|*PwcxmQy32p;tJxhemLve&HOzqty`iWfxO-@m^kmn)EbaJ zn0?_sP?=fDyGif1a-mc+_C25LvsvlGMTb#_wWc?7O>lqo84!)K(>kb68qa0z13Uu* zk!gPqNo$E8qz|n5f#L4`EXI2Pd4ouU+F`Bt)tZRGQLPV-GaszqSfcFXJ`{$*gV7Q0 z@Ms-p1dK%PDB>OsV{n_#ss5FdN4R6L9~T`(osu2vNx1JH8cqG-oL>A+0QH$BVm}Ec zb3X;rv75^MG?)%EU?$8WPQB}9b3F&zbEQ&(Oh{L8S0`&U4FHb?Q^T8rJQ_+1C zrLMjgeaL+uzgE|Y#?J@QNp5y$5@9BBuQFomlGa4*!0%4j1-qk@dCrsZHyMAdf5t9Y zqZ4PAMPoTCk9$aaD(~98#HX>yefW#>YZDP?ocmF9w7VbsOkKvi2T1cpf2?~D`;YN^ z2tJ8UbX#Yg;vSApb*u2J5v=AXPMxW%Uyo?+d}`X9;QNyGDzr!Hr)^@aM0NiNI(!aa zz)|=Tjv-g=TpH;+&h=N2sXyykqBWfp$T^AqDNq~u4SWly;X613XW@JJ0nWjXa2|ew zpWzqymGC+zDVg!&-;j9$eviJ!(^~KRVcI<2!{~Gog0&TYMK|!Pg@L=;#AftxtF~88OHan_=o&D%V5NG1Zw#c`V}O#J|3uuf;uAY`Qx; zGK;b`i|03s=cjVPm^pIt;4g1%Cf|zkGt%a^{jm-f6R9Z#Adk#ky8jg4&%^^>?n+UI|pOKj!Ta5Jz&Syit$?}MPkjJqDD{p zN3qN@RGj=O0oUWEdR2pdY{}RG;_{qQEQ&6Tn|ZHLew0ULxGxLJV~tPfTfZE7=)BkR zm=&NR+yIrJGNiNGt`K9HRbrfnn~)d8R~2{3s)kt|Zh{(66KX+iNP{|17wSQMXaEhN z5j2J-5QnCa4$YuB`nQP9B@gG4hjSBoXvVCZw_}5LcXC@z%e>(r17!vBg*TxAyYC zgnsDd@`Es!%Y2ly%8%BYTrT%9lMZVi=of^S?4^|TAl!f5FPFb8p&xx3^u3#Uo2mQb zSLkm2NdEHw=q|fJ27MxA-4lBv5#Gw|j>g?oKh>Ax7jXWYkD2aICDKe^DiKD{CN*ir zzw);madeM8eT5uruQ*m-RY&U{==jWK&->Y{Jn!eOkZ;o_`Ojabk1ZcPVlP}Fqetw; zD`W&^rblcQZI_-CWzdwN)fxBdcf|QsAN&023zA-a!yn=sDb6qb1opC1pSrgx?`ycT z^6pLe*LeeSQ@*G3%Rv9zeQiekeT+V@X59BR_v?lspF=U0ZTe48Klp@Zb~ zgZ?lewjo3B;QQ9DgV>lTubdT4IT}c~`$20J9>5#~gH8OKGU6+2%F*TwdG@)`M>hWE zx%PKPHNJM``>GRpI24(~@T>OoLCoPGeMdl0Mn-Zy3j5KtFJoXVjDzv;5KO>rB22>H zWbQRDVt+SJ?Gb%d?54srm<}^wCjR$k3w}F|@i^M0*)Rv@#pdqs1?3owIo?H8hh`e(c8m+E`qeAXtd8aKq#6@UK+Z$Q!! literal 0 HcmV?d00001 diff --git a/data/quadruped/tmotor3.mtl b/data/quadruped/tmotor3.mtl new file mode 100644 index 000000000..af216a1cc --- /dev/null +++ b/data/quadruped/tmotor3.mtl @@ -0,0 +1,19 @@ +# Blender MTL File: 'tmotor.blend' +# Material Count: 2 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 +map_Kd t-motor.jpg + +newmtl None_NONE +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 diff --git a/data/quadruped/tmotor3.obj b/data/quadruped/tmotor3.obj new file mode 100644 index 000000000..366398a4b --- /dev/null +++ b/data/quadruped/tmotor3.obj @@ -0,0 +1,325 @@ +# Blender v2.78 (sub 0) OBJ File: 'tmotor.blend' +# www.blender.org +mtllib tmotor3.mtl +o Cylinder +v 0.000000 0.043000 -0.006500 +v 0.000000 0.043000 0.006500 +v 0.008389 0.042174 -0.006500 +v 0.008389 0.042174 0.006500 +v 0.016455 0.039727 -0.006500 +v 0.016455 0.039727 0.006500 +v 0.023890 0.035753 -0.006500 +v 0.023890 0.035753 0.006500 +v 0.030406 0.030406 -0.006500 +v 0.030406 0.030406 0.006500 +v 0.035753 0.023890 -0.006500 +v 0.035753 0.023890 0.006500 +v 0.039727 0.016455 -0.006500 +v 0.039727 0.016455 0.006500 +v 0.042174 0.008389 -0.006500 +v 0.042174 0.008389 0.006500 +v 0.043000 0.000000 -0.006500 +v 0.043000 0.000000 0.006500 +v 0.042174 -0.008389 -0.006500 +v 0.042174 -0.008389 0.006500 +v 0.039727 -0.016455 -0.006500 +v 0.039727 -0.016455 0.006500 +v 0.035753 -0.023890 -0.006500 +v 0.035753 -0.023890 0.006500 +v 0.030406 -0.030406 -0.006500 +v 0.030406 -0.030406 0.006500 +v 0.023890 -0.035753 -0.006500 +v 0.023890 -0.035753 0.006500 +v 0.016455 -0.039727 -0.006500 +v 0.016455 -0.039727 0.006500 +v 0.008389 -0.042174 -0.006500 +v 0.008389 -0.042174 0.006500 +v -0.000000 -0.043000 -0.006500 +v -0.000000 -0.043000 0.006500 +v -0.008389 -0.042174 -0.006500 +v -0.008389 -0.042174 0.006500 +v -0.016455 -0.039727 -0.006500 +v -0.016455 -0.039727 0.006500 +v -0.023890 -0.035753 -0.006500 +v -0.023890 -0.035753 0.006500 +v -0.030406 -0.030406 -0.006500 +v -0.030406 -0.030406 0.006500 +v -0.035753 -0.023889 -0.006500 +v -0.035753 -0.023889 0.006500 +v -0.039727 -0.016455 -0.006500 +v -0.039727 -0.016455 0.006500 +v -0.042174 -0.008389 -0.006500 +v -0.042174 -0.008389 0.006500 +v -0.043000 0.000000 -0.006500 +v -0.043000 0.000000 0.006500 +v -0.042174 0.008389 -0.006500 +v -0.042174 0.008389 0.006500 +v -0.039727 0.016455 -0.006500 +v -0.039727 0.016455 0.006500 +v -0.035753 0.023890 -0.006500 +v -0.035753 0.023890 0.006500 +v -0.030406 0.030406 -0.006500 +v -0.030406 0.030406 0.006500 +v -0.023889 0.035753 -0.006500 +v -0.023889 0.035753 0.006500 +v -0.016455 0.039727 -0.006500 +v -0.016455 0.039727 0.006500 +v -0.008389 0.042174 -0.006500 +v -0.008389 0.042174 0.006500 +vt 0.6520 0.1657 +vt 0.8624 0.3762 +vt 0.6520 0.8843 +vt 0.5790 0.9064 +vt 0.3543 0.8843 +vt 0.5031 0.9139 +vt 0.4273 0.9064 +vt 0.2871 0.8484 +vt 0.2281 0.8000 +vt 0.1798 0.7411 +vt 0.1438 0.6738 +vt 0.1217 0.6009 +vt 0.1142 0.5250 +vt 0.1217 0.4491 +vt 0.1438 0.3762 +vt 0.1798 0.3089 +vt 0.2281 0.2500 +vt 0.2871 0.2016 +vt 0.3543 0.1657 +vt 0.4273 0.1436 +vt 0.5031 0.1361 +vt 0.5790 0.1436 +vt 0.7192 0.2016 +vt 0.7781 0.2500 +vt 0.8265 0.3089 +vt 0.8846 0.4491 +vt 0.8920 0.5250 +vt 0.8846 0.6009 +vt 0.8624 0.6738 +vt 0.8265 0.7411 +vt 0.7781 0.8000 +vt 0.7192 0.8484 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vt 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0980 0.9952 0.0000 +vn 0.2903 0.9569 0.0000 +vn 0.4714 0.8819 0.0000 +vn 0.6344 0.7730 0.0000 +vn 0.7730 0.6344 0.0000 +vn 0.8819 0.4714 0.0000 +vn 0.9569 0.2903 0.0000 +vn 0.9952 0.0980 0.0000 +vn 0.9952 -0.0980 0.0000 +vn 0.9569 -0.2903 0.0000 +vn 0.8819 -0.4714 0.0000 +vn 0.7730 -0.6344 0.0000 +vn 0.6344 -0.7730 0.0000 +vn 0.4714 -0.8819 0.0000 +vn 0.2903 -0.9569 0.0000 +vn 0.0980 -0.9952 0.0000 +vn -0.0980 -0.9952 0.0000 +vn -0.2903 -0.9569 0.0000 +vn -0.4714 -0.8819 0.0000 +vn -0.6344 -0.7730 0.0000 +vn -0.7730 -0.6344 0.0000 +vn -0.8819 -0.4714 0.0000 +vn -0.9569 -0.2903 0.0000 +vn -0.9952 -0.0980 0.0000 +vn -0.9952 0.0980 0.0000 +vn -0.9569 0.2903 0.0000 +vn -0.8819 0.4714 0.0000 +vn -0.7730 0.6344 0.0000 +vn -0.6344 0.7730 0.0000 +vn -0.4714 0.8819 0.0000 +vn -0.2903 0.9569 0.0000 +vn -0.0980 0.9952 0.0000 +vn 0.0000 0.0000 -1.0000 +usemtl None +s off +f 30/1/1 22/2/1 6/3/1 +f 6/3/1 4/4/1 62/5/1 +f 2/6/1 64/7/1 62/5/1 +f 62/5/1 60/8/1 58/9/1 +f 58/9/1 56/10/1 54/11/1 +f 54/11/1 52/12/1 50/13/1 +f 50/13/1 48/14/1 54/11/1 +f 46/15/1 44/16/1 42/17/1 +f 42/17/1 40/18/1 38/19/1 +f 38/19/1 36/20/1 34/21/1 +f 34/21/1 32/22/1 38/19/1 +f 30/1/1 28/23/1 26/24/1 +f 26/24/1 24/25/1 22/2/1 +f 22/2/1 20/26/1 18/27/1 +f 18/27/1 16/28/1 22/2/1 +f 14/29/1 12/30/1 10/31/1 +f 10/31/1 8/32/1 6/3/1 +f 4/4/1 2/6/1 62/5/1 +f 62/5/1 58/9/1 6/3/1 +f 54/11/1 48/14/1 46/15/1 +f 46/15/1 42/17/1 54/11/1 +f 38/19/1 32/22/1 30/1/1 +f 30/1/1 26/24/1 22/2/1 +f 22/2/1 16/28/1 14/29/1 +f 14/29/1 10/31/1 22/2/1 +f 6/3/1 58/9/1 54/11/1 +f 54/11/1 42/17/1 38/19/1 +f 38/19/1 30/1/1 6/3/1 +f 22/2/1 10/31/1 6/3/1 +f 6/3/1 54/11/1 38/19/1 +usemtl None +f 2/33/2 3/34/2 1/35/2 +f 4/36/3 5/37/3 3/34/3 +f 6/38/4 7/39/4 5/37/4 +f 8/40/5 9/41/5 7/39/5 +f 10/42/6 11/43/6 9/41/6 +f 12/44/7 13/45/7 11/43/7 +f 14/46/8 15/47/8 13/45/8 +f 16/48/9 17/49/9 15/47/9 +f 18/50/10 19/51/10 17/49/10 +f 20/52/11 21/53/11 19/51/11 +f 22/54/12 23/55/12 21/53/12 +f 24/56/13 25/57/13 23/55/13 +f 26/58/14 27/59/14 25/57/14 +f 28/60/15 29/61/15 27/59/15 +f 30/62/16 31/63/16 29/61/16 +f 32/64/17 33/65/17 31/63/17 +f 34/66/18 35/67/18 33/65/18 +f 36/68/19 37/69/19 35/67/19 +f 38/70/20 39/71/20 37/69/20 +f 40/72/21 41/73/21 39/71/21 +f 42/74/22 43/75/22 41/73/22 +f 44/76/23 45/77/23 43/75/23 +f 46/78/24 47/79/24 45/77/24 +f 48/80/25 49/81/25 47/79/25 +f 50/82/26 51/83/26 49/81/26 +f 52/84/27 53/85/27 51/83/27 +f 54/86/28 55/87/28 53/85/28 +f 56/88/29 57/89/29 55/87/29 +f 58/90/30 59/91/30 57/89/30 +f 60/92/31 61/93/31 59/91/31 +f 62/94/32 63/95/32 61/93/32 +f 64/96/33 1/35/33 63/95/33 +f 31/63/34 55/87/34 63/95/34 +f 2/33/2 4/36/2 3/34/2 +f 4/36/3 6/38/3 5/37/3 +f 6/38/4 8/40/4 7/39/4 +f 8/40/5 10/42/5 9/41/5 +f 10/42/6 12/44/6 11/43/6 +f 12/44/7 14/46/7 13/45/7 +f 14/46/8 16/48/8 15/47/8 +f 16/48/9 18/50/9 17/49/9 +f 18/50/10 20/52/10 19/51/10 +f 20/52/11 22/54/11 21/53/11 +f 22/54/12 24/56/12 23/55/12 +f 24/56/13 26/58/13 25/57/13 +f 26/58/14 28/60/14 27/59/14 +f 28/60/15 30/62/15 29/61/15 +f 30/62/16 32/64/16 31/63/16 +f 32/64/17 34/66/17 33/65/17 +f 34/66/18 36/68/18 35/67/18 +f 36/68/19 38/70/19 37/69/19 +f 38/70/20 40/72/20 39/71/20 +f 40/72/21 42/74/21 41/73/21 +f 42/74/22 44/76/22 43/75/22 +f 44/76/23 46/78/23 45/77/23 +f 46/78/24 48/80/24 47/79/24 +f 48/80/25 50/82/25 49/81/25 +f 50/82/26 52/84/26 51/83/26 +f 52/84/27 54/86/27 53/85/27 +f 54/86/28 56/88/28 55/87/28 +f 56/88/29 58/90/29 57/89/29 +f 58/90/30 60/92/30 59/91/30 +f 60/92/31 62/94/31 61/93/31 +f 62/94/32 64/96/32 63/95/32 +f 64/96/33 2/33/33 1/35/33 +f 63/95/34 1/35/34 3/34/34 +f 3/34/34 5/37/34 7/39/34 +f 7/39/34 9/41/34 15/47/34 +f 11/43/34 13/45/34 15/47/34 +f 15/47/34 17/49/34 19/51/34 +f 19/51/34 21/53/34 23/55/34 +f 23/55/34 25/57/34 31/63/34 +f 27/59/34 29/61/34 31/63/34 +f 31/63/34 33/65/34 35/67/34 +f 35/67/34 37/69/34 31/63/34 +f 39/71/34 41/73/34 47/79/34 +f 43/75/34 45/77/34 47/79/34 +f 47/79/34 49/81/34 51/83/34 +f 51/83/34 53/85/34 55/87/34 +f 55/87/34 57/89/34 63/95/34 +f 59/91/34 61/93/34 63/95/34 +f 63/95/34 3/34/34 15/47/34 +f 9/41/34 11/43/34 15/47/34 +f 15/47/34 19/51/34 31/63/34 +f 25/57/34 27/59/34 31/63/34 +f 31/63/34 37/69/34 39/71/34 +f 41/73/34 43/75/34 47/79/34 +f 47/79/34 51/83/34 55/87/34 +f 57/89/34 59/91/34 63/95/34 +f 3/34/34 7/39/34 15/47/34 +f 19/51/34 23/55/34 31/63/34 +f 31/63/34 39/71/34 47/79/34 +f 47/79/34 55/87/34 31/63/34 +f 63/95/34 15/47/34 31/63/34 diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 8bf8467b4..26b56aee5 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -512,7 +512,8 @@ struct MinitaurStateLogger : public InternalStateLogger MinitaurLogRecord logData; //'t', 'r', 'p', 'y', 'q0', 'q1', 'q2', 'q3', 'q4', 'q5', 'q6', 'q7', 'u0', 'u1', 'u2', 'u3', 'u4', 'u5', 'u6', 'u7', 'xd', 'mo' - btScalar motorDir[8] = {1, -1, 1, -1, -1, 1, -1, 1}; + btScalar motorDir[8] = {1, 1, 1, 1, 1, 1, 1, 1}; + btQuaternion orn = m_minitaurMultiBody->getBaseWorldTransform().getRotation(); btMatrix3x3 mat(orn); @@ -568,12 +569,14 @@ struct GenericRobotStateLogger : public InternalStateLogger btMultiBodyDynamicsWorld* m_dynamicsWorld; btAlignedObjectArray m_bodyIdList; bool m_filterObjectUniqueId; - - GenericRobotStateLogger(int loggingUniqueId, const std::string& fileName, btMultiBodyDynamicsWorld* dynamicsWorld) + int m_maxLogDof; + + GenericRobotStateLogger(int loggingUniqueId, const std::string& fileName, btMultiBodyDynamicsWorld* dynamicsWorld, int maxLogDof) :m_loggingTimeStamp(0), m_logFileHandle(0), m_dynamicsWorld(dynamicsWorld), - m_filterObjectUniqueId(false) + m_filterObjectUniqueId(false), + m_maxLogDof(maxLogDof) { m_loggingType = STATE_LOGGING_GENERIC_ROBOT; @@ -595,32 +598,24 @@ struct GenericRobotStateLogger : public InternalStateLogger structNames.push_back("omegaY"); structNames.push_back("omegaZ"); structNames.push_back("qNum"); - structNames.push_back("q0"); - structNames.push_back("q1"); - structNames.push_back("q2"); - structNames.push_back("q3"); - structNames.push_back("q4"); - structNames.push_back("q5"); - structNames.push_back("q6"); - structNames.push_back("q7"); - structNames.push_back("q8"); - structNames.push_back("q9"); - structNames.push_back("q10"); - structNames.push_back("q11"); - structNames.push_back("u0"); - structNames.push_back("u1"); - structNames.push_back("u2"); - structNames.push_back("u3"); - structNames.push_back("u4"); - structNames.push_back("u5"); - structNames.push_back("u6"); - structNames.push_back("u7"); - structNames.push_back("u8"); - structNames.push_back("u9"); - structNames.push_back("u10"); - structNames.push_back("u11"); + + m_structTypes = "IfIfffffffffffffI"; + + for (int i=0;im_dynamicsWorld); + GenericRobotStateLogger* logger = new GenericRobotStateLogger(loggerUid,fileName,m_data->m_dynamicsWorld,maxLogDof); if ((clientCmd.m_updateFlags & STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID) && (clientCmd.m_stateLoggingArguments.m_numBodyUniqueIds>0)) { diff --git a/examples/pybullet/quadruped.py b/examples/pybullet/quadruped.py index 5e4eade4f..10a10cb45 100644 --- a/examples/pybullet/quadruped.py +++ b/examples/pybullet/quadruped.py @@ -2,32 +2,35 @@ import pybullet as p import time import math -useRealTime = 1 +useRealTime = 0 fixedTimeStep = 0.001 speed = 10 -amplitude = 1.3 +amplitude = 0.8 jump_amp = 0.5 maxForce = 3.5 -kp = .6 -kd = 1 +kneeFrictionForce = 0.00 +kp = .05 +kd = .5 physId = p.connect(p.SHARED_MEMORY) if (physId<0): p.connect(p.GUI) - -p.loadURDF("plane.urdf") -p.setGravity(0,0,-10) +#p.resetSimulation() +p.loadURDF("plane.urdf",0,0,0.1) +#p.loadSDF("kitchens/1.sdf") +p.setGravity(0,0,0) p.setTimeStep(fixedTimeStep) -p.setRealTimeSimulation(1) -quadruped = p.loadURDF("quadruped/quadruped.urdf",1,-2,0.3) +p.setRealTimeSimulation(0) +quadruped = p.loadURDF("quadruped/minitaur.urdf",[0,0,0.2],useFixedBase=False) nJoints = p.getNumJoints(quadruped) jointNameToId = {} for i in range(nJoints): - jointInfo = p.getJointInfo(quadruped, i) - jointNameToId[jointInfo[1].decode('UTF-8')] = jointInfo[0] + jointInfo = p.getJointInfo(quadruped, i) + jointNameToId[jointInfo[1].decode('UTF-8')] = jointInfo[0] + motor_front_rightR_joint = jointNameToId['motor_front_rightR_joint'] hip_front_rightR_link = jointNameToId['hip_front_rightR_link'] @@ -56,93 +59,70 @@ knee_back_leftL_link = jointNameToId['knee_back_leftL_link'] #p.getNumJoints(1) -#right front leg -p.resetJointState(quadruped,0,1.57) -p.resetJointState(quadruped,2,-2.2) -p.resetJointState(quadruped,3,-1.57) -p.resetJointState(quadruped,5,2.2) -p.createConstraint(quadruped,2,quadruped,5,p.JOINT_POINT2POINT,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2]) +p.resetJointState(quadruped,motor_front_rightR_joint,1.57) +p.resetJointState(quadruped,knee_front_rightR_link,-2.2) +p.resetJointState(quadruped,motor_front_rightL_joint,1.57) +p.resetJointState(quadruped,knee_front_rightL_link,-2.2) +p.createConstraint(quadruped,knee_front_rightR_link,quadruped,knee_front_rightL_link,p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2]) +p.setJointMotorControl(quadruped,knee_front_rightR_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) +p.setJointMotorControl(quadruped,knee_front_rightL_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) -p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,1.57,1) -p.setJointMotorControl(quadruped,1,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,2,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-1.57,1) -p.setJointMotorControl(quadruped,4,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,5,p.VELOCITY_CONTROL,0,0) +p.resetJointState(quadruped,motor_front_leftR_joint,-1.57) +p.resetJointState(quadruped,knee_front_leftR_link,2.2) +p.resetJointState(quadruped,motor_front_leftL_joint,-1.57) +p.resetJointState(quadruped,knee_front_leftL_link,2.2) +p.createConstraint(quadruped,knee_front_leftR_link,quadruped,knee_front_leftL_link,p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2]) +p.setJointMotorControl(quadruped,knee_front_leftR_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) +p.setJointMotorControl(quadruped,knee_front_leftL_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) -#left front leg -p.resetJointState(quadruped,6,1.57) -p.resetJointState(quadruped,8,-2.2) -p.resetJointState(quadruped,9,-1.57) -p.resetJointState(quadruped,11,2.2) -p.createConstraint(quadruped,8,quadruped,11,p.JOINT_POINT2POINT,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2]) +p.resetJointState(quadruped,motor_back_rightR_joint,1.57) +p.resetJointState(quadruped,knee_back_rightR_link,-2.2) +p.resetJointState(quadruped,motor_back_rightL_joint,1.57) +p.resetJointState(quadruped,knee_back_rightL_link,-2.2) +p.createConstraint(quadruped,knee_back_rightR_link,quadruped,knee_back_rightL_link,p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2]) +p.setJointMotorControl(quadruped,knee_back_rightR_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) +p.setJointMotorControl(quadruped,knee_back_rightL_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) -p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,1.57,1) -p.setJointMotorControl(quadruped,7,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,8,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,9,p.POSITION_CONTROL,-1.57,1) -p.setJointMotorControl(quadruped,10,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,11,p.VELOCITY_CONTROL,0,0) - - -#right back leg -p.resetJointState(quadruped,12,1.57) -p.resetJointState(quadruped,14,-2.2) -p.resetJointState(quadruped,15,-1.57) -p.resetJointState(quadruped,17,2.2) -p.createConstraint(quadruped,14,quadruped,17,p.JOINT_POINT2POINT,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2]) - -p.setJointMotorControl(quadruped,12,p.POSITION_CONTROL,1.57,1) -p.setJointMotorControl(quadruped,13,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,14,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-1.57,1) -p.setJointMotorControl(quadruped,16,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,17,p.VELOCITY_CONTROL,0,0) - -#left back leg -p.resetJointState(quadruped,18,1.57) -p.resetJointState(quadruped,20,-2.2) -p.resetJointState(quadruped,21,-1.57) -p.resetJointState(quadruped,23,2.2) -p.createConstraint(quadruped,20,quadruped,23,p.JOINT_POINT2POINT,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2]) - -p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,1.57,1) -p.setJointMotorControl(quadruped,19,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,20,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,1) -p.setJointMotorControl(quadruped,22,p.VELOCITY_CONTROL,0,0) -p.setJointMotorControl(quadruped,23,p.VELOCITY_CONTROL,0,0) - - -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=1.57, positionGain=kp, velocityGain=kd, force=maxForce) -p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) +p.resetJointState(quadruped,motor_back_leftR_joint,-1.57) +p.resetJointState(quadruped,knee_back_leftR_link,2.2) +p.resetJointState(quadruped,motor_back_leftL_joint,-1.57) +p.resetJointState(quadruped,knee_back_leftL_link,2.2) +p.createConstraint(quadruped,knee_back_leftR_link,quadruped,knee_back_leftL_link,p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2]) +p.setJointMotorControl(quadruped,motor_back_leftR_joint,p.POSITION_CONTROL,-1.57,maxForce) +p.setJointMotorControl(quadruped,knee_back_leftR_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) +p.setJointMotorControl(quadruped,motor_back_leftL_joint,p.POSITION_CONTROL,-1.57,maxForce) +p.setJointMotorControl(quadruped,knee_back_leftL_link,p.VELOCITY_CONTROL,0,kneeFrictionForce) -#stand still -p.setRealTimeSimulation(useRealTime) +motordir=[-1,-1,-1,-1,1,1,1,1] +legnumbering=[motor_front_leftR_joint,motor_front_leftL_joint,motor_back_leftR_joint,motor_back_leftL_joint,motor_front_rightR_joint,motor_front_rightL_joint,motor_back_rightR_joint,motor_back_rightL_joint] + +#use the Minitaur leg numbering +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[0],controlMode=p.POSITION_CONTROL,targetPosition=motordir[0]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[1],controlMode=p.POSITION_CONTROL,targetPosition=motordir[1]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[2],controlMode=p.POSITION_CONTROL,targetPosition=motordir[2]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[3],controlMode=p.POSITION_CONTROL,targetPosition=motordir[3]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[4],controlMode=p.POSITION_CONTROL,targetPosition=motordir[4]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[5],controlMode=p.POSITION_CONTROL,targetPosition=motordir[5]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[6],controlMode=p.POSITION_CONTROL,targetPosition=motordir[6]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[7],controlMode=p.POSITION_CONTROL,targetPosition=motordir[7]*1.57,positionGain=kp, velocityGain=kd, force=maxForce) -t=0.0 -ref_time = time.time() -t_end = t + 4 -while t < t_end: - if (useRealTime==0): - t = t+fixedTimeStep - p.stepSimulation() - else: - t = time.time()-ref_time - p.setGravity(0,0,-10) +p.stepSimulation() + + +print("quadruped Id = ") +print(quadruped) +p.saveWorld("quadru.py") +logId = p.startStateLogging(p.STATE_LOGGING_MINITAUR,"quadrupedLog.txt",[quadruped]) p.setGravity(0,0,-10) - + +#stand still +p.setRealTimeSimulation(1) + #jump t = 0.0 t_end = t + 10 @@ -163,49 +143,17 @@ while t < t_end: p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-math.sin(t*speed)*jump_amp-1.57, positionGain=kp, velocityGain=kd, force=maxForce) p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*jump_amp+1.57, positionGain=kp, velocityGain=kd, force=maxForce) p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-math.sin(t*speed)*jump_amp-1.57, positionGain=kp, velocityGain=kd, force=maxForce) + + target = math.sin(t*speed)*jump_amp+1.57; + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[0],controlMode=p.POSITION_CONTROL,targetPosition=motordir[0]*target,positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[1],controlMode=p.POSITION_CONTROL,targetPosition=motordir[1]*target,positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[2],controlMode=p.POSITION_CONTROL,targetPosition=motordir[2]*target,positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[3],controlMode=p.POSITION_CONTROL,targetPosition=motordir[3]*target,positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[4],controlMode=p.POSITION_CONTROL,targetPosition=motordir[4]*target,positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[5],controlMode=p.POSITION_CONTROL,targetPosition=motordir[5]*target,positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[6],controlMode=p.POSITION_CONTROL,targetPosition=motordir[6]*target,positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped,jointIndex=legnumbering[7],controlMode=p.POSITION_CONTROL,targetPosition=motordir[7]*target,positionGain=kp, velocityGain=kd, force=maxForce) if (useRealTime==0): p.stepSimulation() -#hop forward -t_end = 20 -i=0 -while t < t_end: - if (useRealTime): - t = time.time()-ref_time - else: - t = t+fixedTimeStep - - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed+3.14)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*speed+3.14)*amplitude+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - - if (useRealTime==0): - p.stepSimulation() - -#walk -t_end = 100 -i=0 -while t < t_end: - if (useRealTime): - t = time.time()-ref_time - else: - t = t+fixedTimeStep - - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3+0.5*3.14)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_front_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3+3.14)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_rightL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftR_joint, controlMode=p.POSITION_CONTROL, targetPosition=math.sin(t*3+1.5*3.14)*.3+1.57, positionGain=kp, velocityGain=kd, force=maxForce) - p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=motor_back_leftL_joint, controlMode=p.POSITION_CONTROL, targetPosition=-1.57, positionGain=kp, velocityGain=kd, force=maxForce) - - - p.stepSimulation() -p.setRealTimeSimulation(1) diff --git a/examples/pybullet/quadruped_playback.py b/examples/pybullet/quadruped_playback.py new file mode 100644 index 000000000..7aaefda2e --- /dev/null +++ b/examples/pybullet/quadruped_playback.py @@ -0,0 +1,126 @@ +import pybullet as p +import time +import math +from datetime import datetime +from numpy import * +from pylab import * +import struct +import sys +import os, fnmatch +import argparse +from time import sleep + +def readLogFile(filename, verbose = True): + f = open(filename, 'rb') + + print('Opened'), + print(filename) + + keys = f.readline().decode('utf8').rstrip('\n').split(',') + fmt = f.readline().decode('utf8').rstrip('\n') + + # The byte number of one record + sz = struct.calcsize(fmt) + # The type number of one record + ncols = len(fmt) + + if verbose: + print('Keys:'), + print(keys) + print('Format:'), + print(fmt) + print('Size:'), + print(sz) + print('Columns:'), + print(ncols) + + # Read data + wholeFile = f.read() + # split by alignment word + chunks = wholeFile.split(b'\xaa\xbb') + print ("num chunks") + print (len(chunks)) + + log = list() + for chunk in chunks: + if len(chunk) == sz: + values = struct.unpack(fmt, chunk) + record = list() + for i in range(ncols): + record.append(values[i]) + log.append(record) + + return log + +clid = p.connect(p.SHARED_MEMORY) + +log = readLogFile("LOG00076.TXT"); + +recordNum = len(log) +print('record num:'), +print(recordNum) +itemNum = len(log[0]) +print('item num:'), +print(itemNum) + +useRealTime = 0 +fixedTimeStep = 0.001 +speed = 10 +amplitude = 0.8 +jump_amp = 0.5 +maxForce = 3.5 +kp = .05 +kd = .5 + + + +quadruped = 1 +nJoints = p.getNumJoints(quadruped) +jointNameToId = {} +for i in range(nJoints): + jointInfo = p.getJointInfo(quadruped, i) + jointNameToId[jointInfo[1].decode('UTF-8')] = jointInfo[0] + +motor_front_rightR_joint = jointNameToId['motor_front_rightR_joint'] +hip_front_rightR_link = jointNameToId['hip_front_rightR_link'] +knee_front_rightR_link = jointNameToId['knee_front_rightR_link'] +motor_front_rightL_joint = jointNameToId['motor_front_rightL_joint'] +motor_front_rightL_link = jointNameToId['motor_front_rightL_link'] +knee_front_rightL_link = jointNameToId['knee_front_rightL_link'] +motor_front_leftR_joint = jointNameToId['motor_front_leftR_joint'] +hip_front_leftR_link = jointNameToId['hip_front_leftR_link'] +knee_front_leftR_link = jointNameToId['knee_front_leftR_link'] +motor_front_leftL_joint = jointNameToId['motor_front_leftL_joint'] +motor_front_leftL_link = jointNameToId['motor_front_leftL_link'] +knee_front_leftL_link = jointNameToId['knee_front_leftL_link'] +motor_back_rightR_joint = jointNameToId['motor_back_rightR_joint'] +hip_rightR_link = jointNameToId['hip_rightR_link'] +knee_back_rightR_link = jointNameToId['knee_back_rightR_link'] +motor_back_rightL_joint = jointNameToId['motor_back_rightL_joint'] +motor_back_rightL_link = jointNameToId['motor_back_rightL_link'] +knee_back_rightL_link = jointNameToId['knee_back_rightL_link'] +motor_back_leftR_joint = jointNameToId['motor_back_leftR_joint'] +hip_leftR_link = jointNameToId['hip_leftR_link'] +knee_back_leftR_link = jointNameToId['knee_back_leftR_link'] +motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint'] +motor_back_leftL_link = jointNameToId['motor_back_leftL_link'] +knee_back_leftL_link = jointNameToId['knee_back_leftL_link'] + +motorDir = [1, 1, 1, 1, 1, 1, 1, 1]; +legnumbering=[motor_front_leftR_joint,motor_front_leftL_joint,motor_back_leftR_joint,motor_back_leftL_joint,motor_front_rightR_joint,motor_front_rightL_joint,motor_back_rightR_joint,motor_back_rightL_joint] + + +for record in log: + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[0], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[0]*record[7], positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[1], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[1]*record[8], positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[2], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[2]*record[9], positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[3], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[3]*record[10], positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[4], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[4]*record[11], positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[5], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[5]*record[12], positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[6], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[6]*record[13], positionGain=kp, velocityGain=kd, force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, jointIndex=legnumbering[7], controlMode=p.POSITION_CONTROL, targetPosition=motorDir[7]*record[14], positionGain=kp, velocityGain=kd, force=maxForce) + p.setGravity(0.000000,0.000000,-10.000000) + p.stepSimulation() + p.stepSimulation() + sleep(0.01) + \ No newline at end of file diff --git a/examples/pybullet/quadruped_setup_playback.py b/examples/pybullet/quadruped_setup_playback.py new file mode 100644 index 000000000..a2b041888 --- /dev/null +++ b/examples/pybullet/quadruped_setup_playback.py @@ -0,0 +1,21 @@ +import pybullet as p +p.connect(p.SHARED_MEMORY) +objects = [p.loadURDF("plane.urdf", 0.000000,0.000000,-.300000,0.000000,0.000000,0.000000,1.000000)] +objects = [p.loadURDF("quadruped/minitaur.urdf", [-0.000046,-0.000068,0.200774],[-0.000701,0.000387,-0.000252,1.000000],useFixedBase=False)] +ob = objects[0] +jointPositions=[ 0.000000, 1.531256, 0.000000, -2.240112, 1.527979, 0.000000, -2.240646, 1.533105, 0.000000, -2.238254, 1.530335, 0.000000, -2.238298, 0.000000, -1.528038, 0.000000, 2.242656, -1.525193, 0.000000, 2.244008, -1.530011, 0.000000, 2.240683, -1.528687, 0.000000, 2.240517 ] +for ji in range (p.getNumJoints(ob)): + p.resetJointState(ob,ji,jointPositions[ji]) + p.setJointMotorControl2(bodyIndex=ob, jointIndex=ji, controlMode=p.VELOCITY_CONTROL, force=0) + +cid0 = p.createConstraint(1,3,1,6,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.200000],[0.000000,0.010000,0.200000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000]) +p.changeConstraint(cid0,maxForce=500.000000) +cid1 = p.createConstraint(1,16,1,19,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.200000],[0.000000,0.010000,0.200000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000]) +p.changeConstraint(cid1,maxForce=500.000000) +cid2 = p.createConstraint(1,9,1,12,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.200000],[0.000000,0.010000,0.200000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000]) +p.changeConstraint(cid2,maxForce=500.000000) +cid3 = p.createConstraint(1,22,1,25,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.200000],[0.000000,0.010000,0.200000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000]) +p.changeConstraint(cid3,maxForce=500.000000) +p.setGravity(0.000000,0.000000,0.000000) +p.stepSimulation() +p.disconnect() From f81211f3b02282b319fc2b89b7daf01ddfd90ee9 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sun, 5 Mar 2017 22:40:05 -0800 Subject: [PATCH 05/66] fix quadruped.py, don't use 'realtime' and set timeout (in case connection to server is lost) to few seconds --- examples/pybullet/quadruped.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/examples/pybullet/quadruped.py b/examples/pybullet/quadruped.py index 10a10cb45..6ead3e3d2 100644 --- a/examples/pybullet/quadruped.py +++ b/examples/pybullet/quadruped.py @@ -17,6 +17,7 @@ physId = p.connect(p.SHARED_MEMORY) if (physId<0): p.connect(p.GUI) #p.resetSimulation() +p.setTimeOut(4) p.loadURDF("plane.urdf",0,0,0.1) #p.loadSDF("kitchens/1.sdf") p.setGravity(0,0,0) @@ -121,7 +122,7 @@ p.setGravity(0,0,-10) #stand still -p.setRealTimeSimulation(1) +p.setRealTimeSimulation(useRealTime) #jump t = 0.0 From af284122a310127562f8ae48d4c372667d8a0e34 Mon Sep 17 00:00:00 2001 From: Daniele Bartolini Date: Mon, 6 Mar 2017 19:27:21 +0100 Subject: [PATCH 06/66] Fix warning when compiling with -Dundef on MinGW --- src/LinearMath/btScalar.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/LinearMath/btScalar.h b/src/LinearMath/btScalar.h index 00754567b..b101d7416 100644 --- a/src/LinearMath/btScalar.h +++ b/src/LinearMath/btScalar.h @@ -49,7 +49,7 @@ inline int btGetVersion() #define ATTRIBUTE_ALIGNED16(a) a #define ATTRIBUTE_ALIGNED64(a) a #define ATTRIBUTE_ALIGNED128(a) a - #elif (_M_ARM) + #elif defined(_M_ARM) #define SIMD_FORCE_INLINE __forceinline #define ATTRIBUTE_ALIGNED16(a) __declspec() a #define ATTRIBUTE_ALIGNED64(a) __declspec() a From b12ccd92c8c939aa70f358c8792f0dd3f306c3f0 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 6 Mar 2017 18:52:52 -0800 Subject: [PATCH 07/66] typo (thanks Avik for the report!) --- examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 65692358d..224014b76 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -539,7 +539,7 @@ bool b3RobotSimulatorClientAPI::getJointState(int bodyUniqueId, int jointIndex, b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle,bodyUniqueId); b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); int statusType = b3GetStatusType(statusHandle); - if (statusType != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) { if (b3GetJointState(m_data->m_physicsClientHandle, statusHandle, jointIndex, state)) { From 98e75191341539224d74507013dca74a8eddd69b Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 6 Mar 2017 18:54:52 -0800 Subject: [PATCH 08/66] Update b3RobotSimulatorClientAPI.cpp --- examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 65692358d..224014b76 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -539,7 +539,7 @@ bool b3RobotSimulatorClientAPI::getJointState(int bodyUniqueId, int jointIndex, b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle,bodyUniqueId); b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); int statusType = b3GetStatusType(statusHandle); - if (statusType != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) { if (b3GetJointState(m_data->m_physicsClientHandle, statusHandle, jointIndex, state)) { From 63dc57c7e6243e6b04cffbe151cb35acf7b009cd Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 7 Mar 2017 08:48:23 -0800 Subject: [PATCH 09/66] add pybullet file to track VR controller attached to some robot (such as minitaur) press button to toggle tracking, other button to reset orientation of controller, relative to robot. --- examples/pybullet/vrminitaur.py | 49 +++++++++++++++++++++++++++++++++ 1 file changed, 49 insertions(+) create mode 100644 examples/pybullet/vrminitaur.py diff --git a/examples/pybullet/vrminitaur.py b/examples/pybullet/vrminitaur.py new file mode 100644 index 000000000..c6e1daac8 --- /dev/null +++ b/examples/pybullet/vrminitaur.py @@ -0,0 +1,49 @@ +#script to track a robot with a VR controller attached to it. + +import time +import pybullet as p + +#first try to connect to shared memory (VR), if it fails use local GUI +c = p.connect(p.SHARED_MEMORY) +if (c<0): + c = p.connect(p.GUI) +p.resetSimulation() +p.setGravity(0,0,0) +print(c) +if (c<0): + p.connect(p.GUI) + +#load the MuJoCo MJCF hand +minitaur = p.loadURDF("quadruped/minitaur.urdf") +robot_cid = -1 + +POSITION=1 +ORIENTATION=2 +BUTTONS=6 + +p.setRealTimeSimulation(1) + +controllerId = -1 + +while True: + events = p.getVREvents() + for e in (events): + #print (e[BUTTONS]) + if (e[BUTTONS][33]&p.VR_BUTTON_WAS_TRIGGERED ): + if (controllerId >= 0): + controllerId = -1 + else: + controllerId = e[0] + if (e[0] == controllerId): + if (robot_cid>=0): + p.changeConstraint(robot_cid,e[POSITION],e[ORIENTATION], maxForce=5000) + if (e[BUTTONS][32]&p.VR_BUTTON_WAS_TRIGGERED ): + if (robot_cid>=0): + p.removeConstraint(robot_cid) + + #q = [0,0,0,1] + euler = p.getEulerFromQuaternion(e[ORIENTATION]) + q = p.getQuaternionFromEuler([euler[0],euler[1],0]) #-euler[0],-euler[1],-euler[2]]) + robot_cid = p.createConstraint(minitaur,-1,-1,-1,p.JOINT_FIXED,[0,0,0],[0.1,0,0],e[POSITION],q,e[ORIENTATION]) + + \ No newline at end of file From 3ad49ae5ebfadccb5a5c4b0942ed759f6bf0fd7b Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 7 Mar 2017 11:52:26 -0800 Subject: [PATCH 10/66] Set logging unique id at initialization. This fixed a bug that the second log couldn't be stopped properly. --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 26b56aee5..85fb1dd7a 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -454,6 +454,7 @@ struct MinitaurStateLogger : public InternalStateLogger m_logFileHandle(0), m_minitaurMultiBody(minitaurMultiBody) { + m_loggingUniqueId = loggingUniqueId; m_loggingType = STATE_LOGGING_MINITAUR; m_motorIdList.resize(motorIdList.size()); for (int m=0;m structNames; From bbb7e3c5f584d6edb2f2c63e58d328401756519d Mon Sep 17 00:00:00 2001 From: Sandu Liviu Catalin Date: Wed, 8 Mar 2017 00:46:39 +0200 Subject: [PATCH 11/66] Adjust thread-local local static variable syntax for MinGW/GCC. --- src/LinearMath/btQuickprof.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/LinearMath/btQuickprof.cpp b/src/LinearMath/btQuickprof.cpp index 16ca88cdc..db6d56f83 100644 --- a/src/LinearMath/btQuickprof.cpp +++ b/src/LinearMath/btQuickprof.cpp @@ -687,7 +687,11 @@ unsigned int btQuickprofGetCurrentThreadIndex2() { const unsigned int kNullIndex = ~0U; #ifdef _WIN32 - __declspec( thread ) static unsigned int sThreadIndex = kNullIndex; + #if defined(__MINGW32__) || defined(__MINGW64__) + static __thread unsigned int sThreadIndex = kNullIndex; + #else + __declspec( thread ) static unsigned int sThreadIndex = kNullIndex; + #endif #else #ifdef __APPLE__ #if TARGET_OS_IPHONE From af295b6eed76d510e7db3c482b7192931c137702 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 7 Mar 2017 19:07:45 -0800 Subject: [PATCH 12/66] optimize hand (hand.py, vrhand.py) MPL.xml STL meshes for better collision detection performance (using Blender decimation tool) --- data/MPL/MPL.xml | 46 ++++++++--------- data/MPL/mesh/index0_collision.STL | Bin 0 -> 2184 bytes data/MPL/mesh/index1_collision.STL | Bin 0 -> 2684 bytes data/MPL/mesh/index2_collision.STL | Bin 0 -> 3284 bytes data/MPL/mesh/index3_collision.STL | Bin 0 -> 4484 bytes data/MPL/mesh/middle0_collision.STL | Bin 0 -> 3084 bytes data/MPL/mesh/middle1_collision.STL | Bin 0 -> 3684 bytes data/MPL/mesh/middle2_collision.STL | Bin 0 -> 4384 bytes data/MPL/mesh/middle3_collision.STL | Bin 0 -> 5584 bytes data/MPL/mesh/palm_collision.STL | Bin 0 -> 11084 bytes data/MPL/mesh/pinky0_collision.STL | Bin 0 -> 2184 bytes data/MPL/mesh/pinky1_collision.STL | Bin 0 -> 3084 bytes data/MPL/mesh/pinky2_collision.STL | Bin 0 -> 4784 bytes data/MPL/mesh/pinky3_collision.STL | Bin 0 -> 6484 bytes data/MPL/mesh/ring0_collision.STL | Bin 0 -> 2184 bytes data/MPL/mesh/ring1_collision.STL | Bin 0 -> 2684 bytes data/MPL/mesh/ring2_collision.STL | Bin 0 -> 4384 bytes data/MPL/mesh/ring3_collision.STL | Bin 0 -> 4484 bytes data/MPL/mesh/thumb0_collision.STL | Bin 0 -> 3584 bytes data/MPL/mesh/thumb1_collision.STL | Bin 0 -> 3484 bytes data/MPL/mesh/thumb2_collision.STL | Bin 0 -> 3384 bytes data/MPL/mesh/thumb3_collision.STL | Bin 0 -> 4984 bytes data/MPL/mesh/wristx_collision.STL | Bin 0 -> 2984 bytes data/MPL/mesh/wristy_collision.STL | Bin 0 -> 6084 bytes data/MPL/mesh/wristz_collision.STL | Bin 0 -> 3884 bytes data/MPL/mpl2.xml | 48 +++++++++--------- .../Importers/ImportSTLDemo/LoadMeshFromSTL.h | 7 ++- 27 files changed, 52 insertions(+), 49 deletions(-) create mode 100644 data/MPL/mesh/index0_collision.STL create mode 100644 data/MPL/mesh/index1_collision.STL create mode 100644 data/MPL/mesh/index2_collision.STL create mode 100644 data/MPL/mesh/index3_collision.STL create mode 100644 data/MPL/mesh/middle0_collision.STL create mode 100644 data/MPL/mesh/middle1_collision.STL create mode 100644 data/MPL/mesh/middle2_collision.STL create mode 100644 data/MPL/mesh/middle3_collision.STL create mode 100644 data/MPL/mesh/palm_collision.STL create mode 100644 data/MPL/mesh/pinky0_collision.STL create mode 100644 data/MPL/mesh/pinky1_collision.STL create mode 100644 data/MPL/mesh/pinky2_collision.STL create mode 100644 data/MPL/mesh/pinky3_collision.STL create mode 100644 data/MPL/mesh/ring0_collision.STL create mode 100644 data/MPL/mesh/ring1_collision.STL create mode 100644 data/MPL/mesh/ring2_collision.STL create mode 100644 data/MPL/mesh/ring3_collision.STL create mode 100644 data/MPL/mesh/thumb0_collision.STL create mode 100644 data/MPL/mesh/thumb1_collision.STL create mode 100644 data/MPL/mesh/thumb2_collision.STL create mode 100644 data/MPL/mesh/thumb3_collision.STL create mode 100644 data/MPL/mesh/wristx_collision.STL create mode 100644 data/MPL/mesh/wristy_collision.STL create mode 100644 data/MPL/mesh/wristz_collision.STL diff --git a/data/MPL/MPL.xml b/data/MPL/MPL.xml index 5800a1200..2b8408323 100644 --- a/data/MPL/MPL.xml +++ b/data/MPL/MPL.xml @@ -49,30 +49,30 @@ - - - - - - - - + + + + + + + + - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + diff --git a/data/MPL/mesh/index0_collision.STL b/data/MPL/mesh/index0_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..9d055eb5fd96a72ee1a498ad579f99df0217a679 GIT binary patch literal 2184 zcmb7EZBSHY6h0)04zPlNO@ZTLBkXQKO=&Xw-o1CilAIw%(Qt5-Y2;Hxzy(4B*|8eJ z(ood+vRnx=L6T6u_P+PNtBh8|DqxJti006)kO2cSlMyEE&-4E5{=Mfp?{l8>oadc= zdAa6-v{Y@nId_jXCOa)BHO(CPdequztuDWCr}i~H{IAd8u8!;VHj$igQa5Cgu19;& zqn~|EHKEIeJBv<`(F0wya`Q4FvD;UeZf+sTLrVpKB?BKDZF@S!L62O?(cMqXr*y)k zzl$X8?3IV^>V>K!PSVlhPZOuElCx#LZp1B{Lw)Q1C|yvV#X|J~H2>-q@`vI}%jWCl zFQ?n-*02zI{40NYdrK4bbO8kzet%Sq^U^BQx>VMkT}##}Ep*Mn6*MJciSQ9zAj?dQ3J#J#4q-t9cu>YNJW{< zYxPMHRb%_IS;lI+viqzz9enjRJr(&j!3g{wz>{+W>JNDt%=-O590FHiwg4rMyp$dK z18U+}5$BS@&FAGv#ZJvuAI>oV`(}$&ZErlwJh@oHRhS|F#zVsy@x_r)#d6IoVfQ^c zp%J2rFVg0}=Ly~{z+9Mv%IBAv)-wyI72Xgl{DSLd_q1eM+GVY6K!m0yo7%yc%K519>mUVIofDyP8K&6t-b~pVl)W+Wvp9bpb zkqsF{QdEMg@OBckC-(tF6^`>6!T>IvaVFwU05gS2tRm1$${X%6;#9+|_%}|w5kWy-66E(7F%yjD5!Rth>CTlw zQMbw2iC@R8_&c|UW=L;@42$AS8^H)%g>N3fyDN&S8)t-Vzwya{S@DRK>n!Y*sl&7( zp-RE|inodV2A~-!WgncpA;&bU3hs;1JYrT&X30rU#pzG~G~z#4UEB#E!oBbArtP+g w>Ux6t;>oc?0eant(4r98F&AsYfA9t4P5?b_hdc|^kghQ*R literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/index1_collision.STL b/data/MPL/mesh/index1_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..9d11ac8bcba09d60a1170d54578853f248d874fe GIT binary patch literal 2684 zcmb7GYfzL`7=DEn!ApTDsA#MpD?}>ef<)itWGD@R5 z45<*yRCENi5t9`7zH^Qj)EqCUd7;o6aE81A0!k8;?a%l0ul;-8=REKGJkNQ*otv{Z zdz~$Pg>mJ&>`#mzW~OJYNMAQ?=Jbg7j6v4*X~xiC_+P&;XSM2T=hmAim4TF6g++90 zofdED-NNB=o1s%Z|W8N!IiHmqr3O%IrMAa!c_xRLJGc9h$sslw9QR ztKlk)2Jl~9!=}`m^nD3ydAzwtYrGvUWnFaB$r@V=Mv!SA}e7*Q%$w({mGl)c}qrZQy4Y?a(Va3mNVN^Hr|&)HmN9LJzq( z8UUV5AIqQKRoM}H9B=ucN;@Avm*&6Nt>JqyAHWV%3+uJD=u@Ir5rd&w>$w*~&2D|t zYs-O#PBK&v@d}r*h5!%mo{{2aMchXtStK3s|8+cRSV``E{`;3==c;QO@0v0;wFdPV{%AT(enz2s+`b&pmNK7WnIpmv9qp9`#3>AA&9Na1$t&gOV zwe>%K{Mc^g9t(_2vwY65CfIYVAwXNbo&34=iek#>5`4z~V{ZUvRLsyHsr#AT&&utk zizOE3L5G}~pf75=E-g=uropLSYM2jTLE?6Lcx(;3emR>=J6Wl?H zsn7UUS`(8=FgxxFdjs(Ns-Nnp^P}HZZxYgub1Wi;r*9%pmztQ`^OKaMO(f+VzP2^bKu%5g+7f5s7DrWcuBgB;a z6IiA+r6rM)A{UNxh2IL!7=YKMXtMg}D&1Y0%<;WAyCTQlT|`Z=j#3v7Bc69{#_<@ln9ZBR^EBuOZx6ZG#Zy~kb+Qs~y+c^FTV}!Wj z&K$3mUDGqww4u3zR(K9^mw4&#(}j82w8FAQc;}b{a|0y28bOSAQfckOC4#ybfi-mg z!P;4*obZ{-ZwJgKIEgszcs~O8?9QYkN80%5#;;Y3z*Ts=0_@wrN7?I=$3xTR3rWOi X5#hh&l)mWvDqb4&3&Sd6Z$!kuszJ>4 literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/index2_collision.STL b/data/MPL/mesh/index2_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..3739de3fb6dbb1f114b3b7fe8c5ffa945856fca9 GIT binary patch literal 3284 zcmb7GYgCj~6g`kAiGo>EE73$W0R<%^(77M?Vp?e^Noa)lj)54#Q538th!0dSF&Cl1 zf?Q;1Xv&Jv)y#Z%?#)_=Z?uPkp`fBmLB$6c0%h~_-2OFx@7Z(qIs2S_zPCPEZb@5Z zO7KZcv!wdGnPOU&U`h*`FfMGOkN?W_B|gCc@V|Z$&giZMOC7NZ%jNwYhs0~;vx#HR z6F#fO+g8b83^$xCeIS3N%` z7=ix@pr(AObQ@bjZDpC_qhSMh$CN?(g(NrPQMp_HBg#cHJoGlkYtQnQIp6E|3tn~R zm{hZrmF(F^Gh^b#!o}0c^g1_fW}KI8%IkLtNpH7b_$7d(cs(G!-yhbGX``Ho)+=wY znBh(Q<9;EmXiXz=TUW>D>`W!o3RjTl>W>@O6#Y%)cV_ZyvX%Q4Tq6MMJno4xN9M_n z&?wrzx{1CmT`^R{8dIz|{$-1VnVcJY#3 z-A-1yn~sQIJ?FB{PirWy_TGXL{oYh7IbySu=0eTxd*&If>$@B$tH@_N90yx7*@&?x z!~NpB?A3pIXs3c+)G=B`yihe({vOaq2YDMLj>70sOCgb&J8E4xQ=XQdScLm zytZiFwodY5LNmWuxzUI_iaQOEkPRC|EVLoX|nuQ zUl+bFX|%-JVkTi(wfdO4Vs78{yOY(Z^zGubWjJZSo-T0|?x>1*km@coz6y~|f$fTd zRabZFhxko?`SUz-@{Rty!CKFcIlP_Soe(rfhDLu&KW=Cdm=*3D&JECXAXcP|+ea(C zQrOKyGi|rNv>G?`dTF@wQfrxhYeA0j+J4Xg&JB%|BR9<_gTLv=@C%-NmDP=jX4zo0 z(H0U$aTM+}W(eT!m(Cn5efS4SUr?+Ro_wq zHt>{qYxYqx?GGC_ca`cm-pkIGe4^6|PoA?7cC7Pta;aCP`t@O_llzJLj3@ z^#n6fy@XVZcTCP|6xWX@DhND@7!6RGb6XVdh?K!arzv(BjKHo0;6FOe(ce8mUbfw& zI0~cH96eLc(d6>?#DRVZ66=Az3+oS%RpLh%>XD)o;3?=%SaEJ;%F^rw5?-l{nTAage%h zJumQ1;7L?j8M4;X(DTdKbMI}W_yyOY?qDa4VVkZx! z!VCd29{SU%2Er0|1TfrptOsTYaK(Qal{>A}K$94L!PR1&018uWw6x?IcFp4*1%ab* zZUEPJ`>?#emEuGH>B@d!kHWhGaNA`w?He}0v8OFVxoQ}J^8sAn>@6E3^CkYW z!1}9~vnS&z$$P<*{rF(E#8DWHCkCKmgGK{G66M+PrxY*2&VU^QU{ORS+tR+D`^^Xv z*a0vC&$07z_Fu{d*Pfsqm&SzS8O0q{_ruglp#2eRDVxgvJ#yUO=2b_3jLfa>(U;j7M7Y14*eD_(+c2A&0ge*tWQ BKbZgk literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/index3_collision.STL b/data/MPL/mesh/index3_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..ec42373086607f90ebc91500b1a4c0dbbfb786c6 GIT binary patch literal 4484 zcmb7IX;f9$72ar^5RFP~oDfzN5Cak80FU$DJya4+Rj{d2jVLwBxC8|hdBOOeb%3B~ zoG@16K#^bo0Z|m+Iqw`y>#!P;p~YpufoMb;l|(@iQR#Jcxw_BKvKG7_cYk;9v%l}# zXFonPC#+0b9U0*km9#S6ZCYI9iipT0pZDMM^LHD!DtW1!uNVAZKMVBe>HAm9lZyki zUuxpTv6@om;C#)nC#irnM?Gaxb&uJv$49fmoC=nGAdZ}f`_TrlxGquj`GgqT>}Kj` zv9Z#!EdJe^D&p#I@lOdS0n^&rh|8!Fc72U0pz!WR0?<%@QM}PQQr0B<%9T$Su&bWM zJZXXxBOYI~;NCm)n8cA{Sd>eJXwOc?!9;`4A5;Zy=s8ISFje;vRA8nE>{;FOw^_ zw}=`2nvD$|&)KYsO}yJZic}r$VsANq!FSjGWDByKWM@+HdCQPI{p6MRQswmGnOe$w z-W+$a+0@C(y(CK-w2j=UKg}|nEoA(>^Z)?2%C#~-W|CGi=eKsu0Y>0A0mMxISavLb z)9&Q$OmP&h5c33(TIC=*edp7OwY@233Nxryb@+Cd$@R{B`tavo6i4mtC?#D_w1A4C z{~#e-Y^3Sm7V_r8jrut{`uNFhg>hp1{c#fWjC+OI1n7}IL59V3ihU`L5=UY5^zMtS zZ+I>@edebtF?_~g8Qd{Up6NAM;wKn^^#<_Q&J1DMyhPj|kRWk(tTBuRIGkT0ylXu~ z?eOLDgNs89#hK|mHoHO5E=KGA7F0rbI zep*Hf!fFhK;|rOZV{OqansT>4yZM`uviGPLWNJ<)i<&fu%{yI0CK}@T54TDgMgxp6 ztrrvx$`t@TaL}nwpm&ocuCP-Sh8|p}Y5U2NFOQ^l&g*YSQ?KBj4Cw zo&{sIdkVMjU8$?xo<2@4IrpXUSze%`E38UYi9RA$MoqXZ49_>3uyZi~m|6WCJV9RL z>6(=+)UbB3UU5Ev+E$QW+d^g5peTX+Zt5AtV#7}J#LM{sYK~Cna;@V+u~_vTHUof z*3zHarf4rB=iA3j>L!j^7g=M;CV~+-AHeM5MKU!!ThPX84Nn}*rpkGgHcJ$b>uK|7 zNmcHTV_k{t^$f8-wp!WzZZS;~zh9CDXqz=T}$M z5L^}B3;=auIBWV5gKakgzU=HwRpjY+OO7&m(6%|Y}W{n!6D2Y!MPst3EvE}1UO9Vqu{bCr7#`$Kiqn30R@i>9rTS4JNYm;*e6 zRX$pBbF?i9*G1#x1v2oT`K@N9D(pM#M}XXg6O6x%jF8cxEjlOv z+YNCgxIzFe@*^3tb}Wkyc2#a?yg#VZXV{rk+ORc5bE)vz%t3qaw6i>8 zoRwl91Qo=x*PN?-xaFF){$GD-UtOA_sHB(64E9=;sz08%pA=m8V4v|36#EWOXN(5; zw6a*V)MN--W)#Km!ciCv@XU75?xUY0O+N>&9V66pymAu2dim-vt_mY?M_$DN{P~gO z4y|eq9EH&Ux5{>EH=>i}yxRkn$$&Y>Gan#5Ka#HEH--7hW;>puc<$nf3UL3jFLk|= zX>=ZHP<)O#$9oq*Y-<7?F*Z#baB883Rf3~18ld=J8RC%ZUi-fKWQr#ocCgyruL=va z`yuH<7Dp>pVKlyp0N%OeNRK|ACm&=zGT|o}q4uiZqnWgzA)ouTk5qEtdr3VOaCQ{Mwc{LkR_Z(4TY>Z?c*$(r0A&}&m8g6;Nq?HxFhMSxU1Gvfm_d9#fO7X; zB=8iqr=7Mc-NhZnE&%v=L!u!)*FtyvTxZ7&VsES8)sn)>Z6m5J)I0c`9Y4X_D}EEe ziS1JihYmzix%8HXE5T714R9uBeZZ0-CK~;fx5Sm;9R=qG7?kd6XyrzFv)x;na5xI1 z0V2=Eu!0L#`H_#83HJogdCVrj;}=%iV*?mV@>d05Wng!yDye#CrL&6G8LzZ0<9PqX vQ5da%H|Vs=+?|>+*kvHcyD0uXfOkfKce|{zGS5Hy7!Vm_xv**}5N9G<0wpde zAt;m>6hVE9 z>MijxJJpMKXrrUF@osb6y%wll5_U(bJze2{eZ1kene7VM|8A8aY>1&fKiZJu>Yurt zi%dvn;7`)XOBcQ;xlfAYjYyk+0vCE`5&=k_K2CG%o;@$#(~CVbpGo!?4iJ}TPW;#< zS==a`Cv^+$`NSb3KJI=3XL5LwA&FI6icj6nD?`IhKoqsSRJxkgvYT}T#o3dMilrdU8PX8vNX|N|$c(Zwa@5(# zP}Og1`h`GawLI(+MQeAQ=6vN+GH<^<**wdNPl9sJ&cT}4d}7I$57m%gPW>wZ++EgA zwsz|1NPnGtu&`8`AJI#e9-YE9W|m4~c=PIXmlMP!73|0B{f5YWh zd@sDVjTIX!Ecuf3Zf>u=36JN-&MNus1aAZfXr-j;ZATOed6TJbdI}q>@??J zS#=O~&KyJMxBm>Ht5@WayZ~FKD$KLRunVy_olMq-QUfByWhEU|^5wMF31a%7idc-P zBp>Fy9HY!25dpt=HE zYN2vuIL8Pa3E)Fb6RCGyO1Y6~3<7tK`3D$M4J*rPBIvoyYI%E+8ENQYs^9XZ8gKfp1|=19)t4lyxUV6yuO2W^3C+FH3H6J&8YS&TKHi1NW24N74TD zA#Wk#Tew0tM|tXP!QMoaD^G0`u^S9#S@Q15Rixzgdk(7-z_V+UIBk(Bxn(>o;1i5s zwfns1Ie#wTF+a6YPw}o{z2f}`=yC%3My00SD<_G#cH9$IkHN3@FQ>61AIPuE>=;kP zYG+kad?{U{4WCIXv>L{JFz47Y089>g2+@;0X>-P027x^aqXAm366L!AFS^`#0>#R} zaWVe@!=c$EV$52)=64mtAa)|_1qB=z*<{$Nr-uEgU2ucHwre$gZfV0HFwYnbkkp`| zzCkvmrEMnTK6vl&J_4+tpCbHlY!A&a3nJJ7zSwQaztwh-QI#FX=E$}6l=-xBrJ9Rn zHVX64a(-w-s<7XBF@1DqBE=KM`Pk`B`Mg0%ynaksb!ijhC0HeF9~Ct^`gcaNTtA~v z!rfwSu-*Xjbvjy07x{+)jTnR?A2#qdGR1`BYpt;H$XUA2sE?SwY6>UC#Bslk($QXfd zVMhfR$R6Z}#y{m}H?h8pJ&{EO|D&h%rya=G0WLgNJ7yE>4InySM-PS^(d2rck#V;e z%_2t6MbMk!FNEzQ$9a5$r;8&2JT&nAG?htW6vJQZv)H`^A2+X~)J*nPK5G=l;eo#AM#!H)|UFU%v(RXmym0o34DL46kcc z*xaYuVB%ycv~-Mo+i6f^W&IM1tdf#Vuj^$MYxKM~S4IKcKVaiqBQ7gN(;v$&-2+fe-ZaX>3^K0wZQldUym}fP`Jr6`xN`jo zYshcYmv{VuCq?|IoxeIq+R^HwyVeD3C#J{gxl5<(pYF}kwnezmpzz5$Kvm4^ydgJ; zj?7OK5IAZ^cCXeDY@la-{;L7piS*}tF8+}*lOlA5J2CG*rWp?ts(Jj!-c`^c8xQbo zSJEFm(=qe7I|G`_?tUqfRB3n$0AHkJ^D|37)N2My8UBJf)up=W1=k$tF~{;2fQK_Z z`J-zpJ8nzhJ@e|db4l;f{AZOK?j3UiD6!mN=Sm*xR|ZoB9I-^%)cA2$Qxm zzi#2JljE7`>KTfw<9bVK>$Tsrg_PZX+zjx1u#h-SYLPQ8IBI!CZt}t#Z|F}`&S(=q zb(39&C+LTQzLVTvn<9VxY!rPfV6mM?WQ#>#>un}A`zuwfhW=&uq{GLZT)?<_NqIP;lqnYvHK8^kKXItHkYv2i*1pGv}oDvCS7 zXsj53f6w2lH%&1UdZd!!>bNTrvE(JFY5CFWf?5kH`lVTFtQ*jtcLd1S#@&^UM5RcM zpM#9|50I2_N`C%qr#f7oL+}@j5P4K=&L>4(<7mk(Ma6qIeK#Vd7KBi@Cl`OU^A~ac z!XP24rvk77y zp54(=S*~91v9tzV9A6%4XpZ{LVj_}f#bncZFg&F8==3(Dp;L`#!LB6Y0d~BweEmj6r48Y!7 z7u0b1&vZ&@nxJ;v72ZFDtTQ`Gk?ktk=eZ_3?3<1iF zIiz*$kn)KkO>iyV2lhNbYeIwWe!_=@Zb%^b0$_xAcVi5%v^kX?#1gug;9MAiGXb0k z3svLC$n^RoE5~!kF2Z{P$jgaR``xoxacmaHQ5cQA3Gj5?OZv^v<@Aff0^!18--*-p z>gv=(9@MgTYzmSBc+;Tqy}Z;m#T@qI(o+F#7@my>-zOWSUbrY~oA{i>_=EoSoQ zY#_CH>=kNYgy^UVj-Z%2SCbpnPQtA4CBl9LcpMX~D~KOsYG>s za6@r)GIM+lu=?jMziwn5%+N>$fyv2ff8<{|3J{a;3s+F7qVOa2^J$5Rk_G>x~A zMP)sT^PR;E*T6a!5$8*Ex^Hk5%`3NYJa^0k^8@f%=0$#KH`2)U3x%%mtZ;__v1!ii z-HHyy$z&C3V77P)0ONCR%3cS;xVJ$j_`SnE$L}M6-Y_JW-=E3bTcZi~AV%O!0H^odfM3C?odhV&sJlVIKVKrd1h%hY= TP*S?y;p2Md3QEKXoC)B6XnLD- literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/middle2_collision.STL b/data/MPL/mesh/middle2_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..447bf724098cd0f1a300241e62f6446198ee48b4 GIT binary patch literal 4384 zcmb7HXFyd~5+1NDvS2ic9hDGu!6-#V@SXSW5fLjfC`c?Qx>8m;C}5=76^K|#u#0E} zBM7Kj-n;jnvw{L^H;6)li-nGYE*eY3YXVEe)vrpso6VaWZ`$R`QUctR?Au$prmf6@-8ck+jy5ry^gLVsX=YZqrSTc_P{p* zTs|4fdwy|9G8|82e=RsFSI;xi4*2gd%~EY2rEy`Q{Cw|ddDU9_D7TcHI&T2*XQtBr3==-_7*)#+nspZch%ClwgDVlB?dn;w3FUiPc~WpDg3x> zdC);lp7h8VmD%57soKy}@eST5VMH-*@AR+8z<`I!{esOJfW%n1_A8 zxm^h7{|=OvHRw!a!hHu;&ktUF^{g7PVBmKESWbnkz=b;@>ZWwoTi*fdoPO~ zekQdnZ;dZ&%v{Ow39g#IO|!hpk1GeOvy5-VJ^H{Ji)*FsO>P_``c=SX!fAk$M?!>!yF^%s02y5V!Vb z*>uB3xo6)T5@X@1_*>nUi?T1c=WD(gVV8|0!uJ6FzNv7@y?le1iFkZvx0~`HysF^fcX|(Lq8~m?b|J z#u3>nRjE|lj4WAprIh@`R%Tu^Bk2740y)~CD2XR)2u4(#1|-)(bxW#aPbz~158Q*; z8{qJkR!+4HQum?un*dHB5%ER6v{1v&yuoa%+m}3BbuD?t7Y`l0y{Ba3e zVIGTl(0|*|NP820D|vu0ov{^WKERsdTy65|^>l&aEzChYGg`hW&|FTp&~|0M&;xkn zj#XXGCQ{4J5fZj~mYA-2(q^K~jtwQE$BD9a+@mg6>2)VcP*L0~Vg>g;_2g+e+m*>H zh6tL7brACnU}pctw7fY_x^bq8;V#1cfj1l@uina1(7+IybkJVH@!~v0gE?dHt9{3gL>^woUqAY5Bwg0`%ybxpnE*4n6OTmoLC33@&SxV z7^zl{Fr^+kKVj>`91~}hdf;2#sEd8+^qbzojKVvkSdVwt$I)Wf1*%V&R#0lpe39+B zo3xVMq#%CF;hLb-Sa-1=19YdIVi}9V=$K5MX}VOWc-oq= zf#KR>+(fLxX0D~qx$~5~9tVVJfU&}AXVj8nd)AtBMJ+c=5Vj?}x8Xk-fR5@>(%YyF z>aj72)MJ*p>(*K46tl6N!rw3MU;wxN=SleX8|>G(5MlSh9ffZ)VpaW%`mg3~>Z!L$ vf(Nz|-$-6tthQki;5%3fym4C0K4a>bHA&T^p{R1&UpPcSnN16 zl{juweN1zif8u6!V0dZ$0P*w zojUW5CqS9$H^$;$PaFQKT_fed>sAMuk*ogQ>iuo4T2-B!-&FF~?p0gUQ|QB#1ac)~ z2V3%eD;d3F4|&h3h?$(1-vU6(xDa8ouAR4ED>1ZoKUHVce#&|rLdmk@z%1@$vG$dD zbrVy+Q|l7S*e$C)+Pk{3ElJEPpQG&9=Em@Q?|ckwPEWhqa>$QdZ>~{48<)F zYqYAW?xgACc7)RVBQ7d9JMMY>y}P= zx72*6wQO`7l^6q%p6(_>-R|=6b^Qd6!ssbI4Qjt7yO?3MyTha#?OA9#=$> zFQ2|I@e1=8yAr_h+z$RmShL=-Dv07J%y1boDmF;u5ANWml_3VKPOMtY1%QsGXi+{n zOL498Q!v{x!*Ona!#jgT`H%yum(LAJgIKj#j{vI&#fw|}Mi|4&H*(BfTou;8#*&SG zqO}gC3)S``!)c3oI`=v2E$~_xAy<_YdCbs##9ibhx{CKRMw0D^ zwlSUiHWlZ?N&`6Iyple4@Ki3f#&fKLh?OeQ=R}gx;g{;MZUAx*1ycJ0OXG)eT^v`1 zqwpI6_#)d{iJCBw9ky5_c_MaESyA1&$@JO-H|1H#0;B!-9`fqu2DPpFQ-X8g3IVPz zSR~qiDd3d{&MTO4nE6;M05yjk`OUu_S#4g5bONY)5~IGHiMYZS9W)VZmW~i9_lDE9 zZbvmWq=sGCTubghu~hp!-_J^Ko+CIPK)%&am%pT3*s#Hb%m7{-b zzd~S^VD`zr>z-#%J2tecVRt799EH)CJpiW;KU9XG(c^l7tNU3 z&Y#SF$}y|)8^wAA$l32Deyq&ruHHi>USamhEZMMgm3ZL1T&WuJs^p^Bcd?@am`@xj zRvn!#Cf#vR@mko`u-gH&ds~RPOMOLap8#nZ;3&*#0569~zQAED511VZ3LrbM8|u} z6#Ho|oQ1|yye>xIl>km>7aPob7@OykMzLq){5y)U(h}y?(MseT&C?UPoku;>{!6ED zjF58_YB{E8Ip%9Q@Dq%{xdDEfR%{4svJyEBbEFd)*0$^=_9Fs}0p4+<<@I8Ydw{2? z+>aSGg-Z0JWN!B3GD+vyuX3B4J%7_qvW5N^w8^==?4a^iYdP&oyQ08co1swo>vjbiL^=4YEmvDPMj z9ihJDmE7~&S*eCAtH&Fsc*{&Qv6-sAWWKDygZ7bplhau4ujw3X8=odI8lZr#XdWf zD2&!zG-8u-72?HSZ!;ryAIuUwQ30~bLTDVj#1kK881Xc~^8-%?fa_teaD9E1ar>PV ziMyEL@~xVD|>iXyGXT?6h zY4?woNK>_M;aqX&^8wOH1|x810U|o1srBeg#r&YZg1L(;!4(3`nUcjEOGX;)j-^qY z9ebDD^W!Fam7?{#`4P9JlJ8%qb*7k|e8qsD;C;v)9PjBzZ345{MW+JW-U}2#hd;8IFWA;h8AGil{&);7g|}a+smn$3b{vJ#S`KSpb!ShSAX{hE<5LlyiI@ujO~d-v z^Hoix_<5S7bF6JVuK@mjmPUK81$}i{oDQ=O`-;rO6Mv=A8I^1FEf1D5d=tV^7!9!V pXqxbyoXV_iY^5)E_%w;{)Bp#+OcQBe7U&1`UMPKs!%-Lw@IQXv!o2_h literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/palm_collision.STL b/data/MPL/mesh/palm_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..08625a6f10ad7bbd787297878a431d7962ad1def GIT binary patch literal 11084 zcmb7KX+VzI`#$z8V=a=XWJHp(wY<-BjzUzjRYH~$+7qR;Ytv$wlBFnXQX)%;_kGTD zrm>7O$1c&rxʈ$uHwM&l>Pf>^ddyV{5%;oEX>;>bYPWff#P3zPSpxH$lP^5aKR{tCxYInsHO-e?8Px|5ZMcnB z>^>|weppY-1J(Hpah6J>CMq|vIPe6nZ1od^_l1(6D|%|j z+b=XlZ;uJJRa=BDX3=!ql`LVKYrAUk3nHDnovk2_=^v09TOx^lOPuVkXH4z)h?>r! zg;HGLB3fUSrhfm~PKtAhlnRrKH067Wl$8g4ZB|zdizUwFA2jfTBm)JOrrC){*lst;c zg>|9d(|w;R)NcJw3J)$%r!C%{r3&?4WgVk@pK6LKD>NIwB@p>rt>k#7K+3hdD%`c& zE8TZ9rFxnxLVbjX^zlZeq?gBi8QyU3HY?i0_AtGm9s8f#{_kr^UiW-8OBjxcJX<^4a@EJiLQR9!7OAe*+Sa#pxn|oBKPre( zGoIml7Vf0(V40k;+9kaTYXuRxKb-0LCy95~=3vN!Flu2> z2+jE^m__Pd!p`@KMaVLceQZo)X-lTPq?Hw}uxNwFWR?~&7q?F~XP3M;&|VY$q=f#v zq_d3y^uzM4Qj1TiRPM8xx}NDwce)%_cGttrl|}68O}bChk>3sSrDcxsYR%uwc2H0l zO*p12jcA)E!Lbp_T^!H0IM#`avSTDT6UbdW`@A)NAiwo76}9^LaWM#EWx8=N-P=$j z-5(L5?3G?aFJ@OVgY{@WDbF|CLXTh1q*=j8fVYyr?H+nXvW4$Bxu1IoS(yJ54s0iJz3@0q`RU$A=$gNeK?snp(@B zloPBU{#6Kf{zzN3;>pRwbJaT2_RvvBO9ZV$5t2^rUK*ZUDny@{E^Yf)O|RJQQxGe{ z|5SZyGZgEp6A0`Jj=}S8Nqdd7}O zt&7Z7_gY-4%&PO|1dXHCEBxrgYHsClhCCv6PNr;d)QN5z6G1L4HK460E$HA|#|1bm z{$6=U2C&odW_V?`T82IWMk?- zQcVm>RsTFmPXo1tSDbs%zv3fi+wsI+D;QK6I0n=!gzP`Nu&Aa=d~@s@ymXB>O>sz8 z=f7=ILB)YegiyyUf9BV(K>TQS2Sa6nTEgo`aYhImbmItSWfL%DYB&b3A3Jn>SVwU! z4hn7;;TNb3yc)C)na@mr=tta^8p%*IAY%RnFM1#-UH$g!Q^g^_pD~h|J{&?Oj&7G7 zCi&8f`l6KjZ@vW4(Ayz2VrLx7S&}2_I5u$(8O8*>(+EYl8nD*e)38^(J%P#s6^GaJ zbvtxer_H6ft0*!!E2x}MQ4tFExFxra>x7dX{1|Md^7NwhKB>~<`f_Q&sTk^QHHbEk zJgeNqMN0>>wf}rC<~7abW(7|Z`UixfXVl1-e>h^hJiwn*HMk}ok=VCqzgQTiD_gCMC1-_4YW3vvw0Kyq09l)7>a-r`I6hU)<)<-O^NE?V;wZM zJ&r(K%I%vX#l2C}g3x{c(WpQA&A`R;ENN5M7*5sv8XSbE!)f%)#XSNX521~+4>sL@ zPujgXioo0nwt{FS6TY|)H`(dQH*bZK#K~J#tGX3Ym$7-m=7QbWffj|eHP zz!UoG%1v(q32X(&;}MOc1F%r|f>LF7;W@+cctlh4U$}IM57RRGgTh+^^M05|BV=Rq z5vMd*%Eq&o5%>kp3eFax8b@9ETv-_{n-WW)3xk;#R8)lG)`YO#%Pxy9gU-p24WM#D zg+s_`p$B_mumoSa+%Cg-h6t#^2#x!8gI=AwQ_Slh&tPmrE#dXUXx#+)eoi`GT)lx) z9Egrjv!MBp+ciPWggWaM_)#6F0ND5!&QM-cjIb&dK4zoV#I9Jg2S?!r5b z(4~0=^z_v;)WIR1za3hsM)0Z8j1= z#-oNXVx40wHtFx>5YP3`3RCRj=*g_E5{E`%M-JfO+FS9!!Tt;?J#+wkUOU(G7kuMD z4c)mgfb&-?d(9JGh8oa5s`HXpn7?pVwx`-<$CQ=-;C>IgubU@p-SlCwP6e}V9+6$S zmgW3rjvqdn6aN zkkxo~?y;DVR!s#(yW^3)$hgRWF>udLoQF7>~+Le1-7a z4{OO|@+((?gzg@q5$fdIoosyTMsAi{bJZxACqPz0=yaAo8RYClh95MfuoXN_9`TEJ zZ=4<9RjS(;$2l3>2ScTv|4gBK$WQ-q8Efn3iEe!^OaJ61a0sZJ5UperdELaj#ii7z zHJ-p$&<*g2Wfrz%*2Z=*xY~@sGk`Y(-WY@~baW*aPcDd!nM*hXyp_-mAoTW~CEGLG zh}0}NBf}g3#yOu&++TQ0W)%h`uVNhM+aa2-2;VjLVezHQeXX5jyAs=ew z3%$DGL(kW84gjh?ALkk8F)O&8E}x0fC$L{wv*O2?+Yv{6pS%_~>AQ0A0o^jxV1!;( z$C2oWX0f(yHHCKxwt{Gcdi)tr+E!MI`I;db*b3IKU~DSYsAXZKPt{`@|8=JfzraZ4 zb?{+}FS$_{C>9>NFGCIIX2R+D`H?fpeE)Quxkj6-*20+J_58pB1JcX)foh4@YzEbm zYsHOWa^92u<~{@8z1)If-Uk&2W?>5ZbdO-DQH8gjcI9$ssEH7bkmWlQ_N;LfHn<{i z*&Q5@AH(i|FEi_Q1816y;@*njZRfpcYN9X8|5}YF)#`Jq25YZ;etteDl#DDc#CHN4 zMd;Pwjp6m9kZdA<2Mxz1bM3hkgy#X#2+eRBNaos@%P&)02y}OlC7>HbsN_m#LJh~u zQP(}V+yEkYW~ezDO|V)bqmZ?oE>^0DS&I6#t6HhIr;C3I(>%`7*e1Tp2^p1l;X1kokv&Bx86qGD!+I$~*MgqN&lZ;9 zB#k@A?a;$PicJ{ZJwhi;U|+?mC_{6KDpl@Npi%Db>HH!)jj_z1&lCajS_G(uM& zmCE_u*Rz8BRte^3FmHqJhRUA}{_0J#k6X!`f)+5C13;#RIfL?c_eq<4w{99Oe=v_@ zQJ4wAo)F61aYCNF{~$eQ9?G2{)It6{KAD=3gei99xl^JDBL})yo=Y12M-yW=flO_* z$IwAS1ndc+(T@iadf%AL)^sA!*P29)6Lx)T(d6eX6ktyXNq`pfxH!>^tExc+>xG7lCN_!mnf#l9@cr zJVxs2!m|&2$ARxH2*p&|%X2sxfl zopov0BR;;?o4f7s)Od9sHs6w6&oyFCPoL%f-3D(sy!i;tcZ(xvdc8PMRUyLs1Nu_P zl?bua7r2l658~1>Yq)nccz5}XzA)a2tT*XGjtHgP?!vkT+-Zb<{LY?~+CIQ9+&VC9 z1Ck*_1-xG~_V@ru(m?R-L4e&e=FGawAtSf$yr2j}bcmewAb_ zFU1f0M{~1+2v`?K$TiDI{clGC39kEO19Nhy;jr3*Q1a@0m9Fw1fVZoRMfj=@5j-<= zHTqd~vps=)-BzlGeL)2D@XG%awP#-3p&*<>AF7~2LIkgaRl~1 zY!w#0o@z5dS$Tm+nF>}jA%d@qUY;3klQE&Jn5r literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/pinky0_collision.STL b/data/MPL/mesh/pinky0_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..ddc6371262b3a782c97f36c9c28f172e32846041 GIT binary patch literal 2184 zcmb7EZBSHY6g~tkxb6~Q=uFV=T1dN#h%}nA_wKz6!XVD@9XUOYHfEZB9p#A!(<5SH9gD`}&GCYYoQTd-4n`P4K@yvk$FWHs*d@RY7Zp@ALMh z8qU-`L$(lkY{#K{bMa}OK9iLoC+fizlV}HKXGwKre7d; z{+-~m_89q}!n{7ltGTxY|HuvQk-n{>YzgLF)n_>kzlgsW)WCV?T8Xtv&wuofnr|tf z|I9Xp<`&bZ>I-f>2cBGhLqj@` zjuUg~dY`Ii=Qmo{kJ#wT?Mp=GGj)cAUgrHzu~iCHxEdXR`;a1UGw zz-dgij1@lQ7fwseuJCrJ4tyb(!B=F}X*~frrJuC~rbN-ytYnH`FaysAu+%lF4CoEi z9ciQu=^>=X(?*J(^CK9=PQL%U%gUE(9aWj*m>!scD*;@Ryvpt|fA>ot(3; z%T;1u>$~px#%zkUYd;G+?mlkl=1K~5qpa_jc);<*YqLP?Jz6H;%q|k*=Vvc zB#Jo6EQkHTl>nZQ7b)>PPj9>QB1YjJEaR0XHCJl+R(Sh_gPu+ulWVUS`H9P38DBWw z2ta1Kof-rFQhpW#k7=_uaA2+lTUHEm2 zyX0fF8+(hDV1)pV!DfrAs!JGL;Sg`F9+eNQGxL93o8@q7cjXOnp_^iOoiyXi`Ec9S zwO4f)g+eFGzN*TJ8&YR~W@^*H~9g%57l1H6byouo8BT@ZRlWa`rVr_ppM;JHaS?V*rUcJH@K@ zeqpMoF#)4+qFBbU1}%yCUTaOAkeHm~d&O*k1)dI>{4I%o3(^U85G!PRc%mmQO;05; zbYMir42;6L0hl?QMLQ~j#L~_Y89Rto;j94s_*Nc`PrfGzHLVN-*TrmKq7H4Qqx18^ z1@S0{QMeyg3m^_w(AqOI@;4cSZrmN$#VG(d93#<`v^tX8f0D@uzC>Kfr|Ov`K2cR# x`ZsNN;k{!w@x1}e^-H1@5>Dm@OjeA-m&h{S^Yx&=tm^S}*2(wZC+EI^n3a4-2s+ zlC{mjwR4gS|pX}n#yIDsu{{8no3N|F1`TbZT( z(}-1DzOe0utuT12LCiU6Bf|b#W~+Of7`SJm2r#|AOgVRT7}t1zyIiQ}nYFc6;*((y zQLP&g6ir@CcIpIim&ZfK-zJf<;zk4j=gnnetJ?y8SF^W_PcUL~!V@7(X`y^sZ)HRj zeXfxsOgq@2#w*J4_xc2v;zx|y?kIzA_2k)z%pxzbD#(rjC|RSC8qiz?=ZO zPiW-%`Q_||hV2CRz?^6VQ=*YgD@xgoaeK&uAPdpAYlisPD@(u#TnT`g9xdCMZzT5G zE(y}t73{&?%BuGa@I;kO0{U7bzE=gZ)Lvh zb0l5Q0~y7eR;IYdiO93|)d7rKq?V(u21u(StO?vR6UVB~iwAT){!e=PH6#!#ZQf0N7L;nHO)C>|Wb*SShRx-a5d0Lo3+sm`u5%IDo}kmF2F7q; ztdi7)Qb~;y9N@>pJNR5Ra3-@l2+qV&jkU5n-d?P8tE2J}z;mXCKm5g0);H;A5hHLv zj0V`Z@(35>($79yoGjxs!2ee`g8|a})O@SkNfLa-nZvunYDR2QC}WOWinS_Y)cpMN z5I$^Z19>`VLTwk{8lxOwI&U-xuBR=GzH;!%k>;+6lyvVWQBK6$#o7S$H8gXc?zdT0 zd>oH!VfWGAy>)DtV2HFMJ#Cp(4}6POFzwE{x`UB>xOpqL@%RKIa6bUs!gP7X41wr@ z;c(*Mmr8Mh6=`Z&t@V=z?}xM03CeleyV<>a*#!4YzC+_jxdi|BVf_Ju-^ykWMZPAT zyE9~*05}=2{s4NXGt$k=ggh=yq?qFgabf^iL}+;Jx(96NsU;$I9G(R04=`8zf=oIg zv%ihcpuQRKBzQuAr1cwk>zSw7n|H5sSaV#L*5l?g1J~kxh}io?QclEZtfn!qk`u+Q z+YWqh#s}0p$93sf`)0ILX~r$!E6coj%og9mXaM{Cds3+WGWjPwib`ty#X&QlKT*Yh z_MT literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/pinky2_collision.STL b/data/MPL/mesh/pinky2_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..375aa5f97c3d2b180679c24033c0767ce434be6f GIT binary patch literal 4784 zcmb7|dqB#JQH*NT>Jia`}eoMd+oK>XFX2-UnM1`tcZ?sSdx;s z+`%_KIw2}L#ofze;v@%`)RmDA<6PnY`dg?!tu>#@E|)wZs~@*1!E?5W?E#}iOXC)C zpQ*9*&bUMO=YZ=zz8^cPO9z{&Q<7{&fP_5(Y}e$sByi8K3jTr>b%mS7lG6VQ8~kDg zfbV8aXQ{)QiQD#e&PMC~K2mMm2620e6=x4%Nb>}#x?>#kH}s)jpI9TtjjoXPf6Nym z6EcLqU9Of|(tHIuX04!XFO$A^FV@@m^n;dK4qQv@5)A1H%Ur?Mv`kpH??kspDc63UX7e%KhnS;fJS9dK(FEC^;YT+0eza zgwK4crMfv9amTPkVWYZC${Kt~^zL~j1l66A&U+b%056kF=*Qb@l_N7l7(NyBtWKcy zX_CYGlK)YdSQ(L!(j>Md@qn^gl`1q8Gs$*#MK!j^+wd`8#k@m`gx7E53C{CwYeQ*< za##w#U8C|3eJPqc^wU{fny2^Ur#*exf*(y;6F;H&-fNnz;*BMXR0AqO&A%#W zO(D@1{6;qRjo>K3Img5Rv;|oyhBlI%usD;WGD2fvFUh|7<*=^ zv>|@4UXgTtn0zZ>602Y4$6+KdNG9D;NHvSy#m=a7Vz@(wRtYy+I z>Ebyjj$N$490NqhhO+)vT9UHJkYcLwDcqF+W}VqW?iJRNmBtYqSD1Fp0swJeuVgGw zrrk%i1apNs=Gnc`^-q?#Oh}sqyh0S8Pt6>r`p#T$GpOHVMDCPFGFpd(ez&8N|6*-f(2^vj~eHmOl+$F5k0s}t7*ejz|_RTz5^QlxHp(U;*Fjum{>P7TkK!+ibNJKacz>kii= zu3&&|{SV3Vvut*$##P1>0ITur0@z{qvy?YHgKcX5l3)csg)11~O;(#?@ZxLb-o-G^ zbNnjo6TlcZYsK_#p(4&o;d%*<8+5<*+36f1{p->Tea<4}= z0JW)CEXD>ikKhN~9K>o~k#4?%O=&O{>-Ov>xbCom?>>Q+KasG9am-OOnc(=~sn5r1 z+#UmJR3FTwni7IfVU~Esaeq%)8(~2^97DPKz=Y%d5n%MjRT`;(HZ|MXEbmSKOgQS< zUwxqM&S`uKcOrnQ%pBGk_N62)&yumXct^p60u-sr6qs{_)CWd#^Bngm+)?!_a#|s2 zO-q+8j;x?~H^5zV!q_5V?)*GywNAecz%gPvQZoI+C70O4L?%2&3t z>1ok~Q{a2C8o;k8l%A?^6w`-Wa9tEn0NhalykBI~FVFx<%D!}V4aM+8m>pa2Ip;d zl6yz3WRncHbH6{Znx6*mzc3-wM@jOf!4|aCQ`q*N5MM--V=B~t}p(A zwYTrmxa}OoZQ(d;e5@+AT+}_!FIRfTCv)uL++d#ovOLe}+}bZF{)6Kw{(=>J20b3f z$wYHc85zBVQ{dl*csmCe{H9Y=YB7XX=FMO@2iS8yAIJRW()E2933F~#a7?fQ-vlt; zYAGG?dAoGx#4QE)4;*Q}GyM2|85?=~w3Jp~tKf*@4GEJEaLtL(M~g<&{BMe6Y#lR( zsRS4qo=z=WoTa;G*Ks+=KJl;Wims6l-!V}ZA3i9{r_Cg7mWb?2GN0~!?|n~^6k(*XOWG$?N=l}#O550m$X4+oR5E2L zbh^Xa3fp)=B5lijH zEeQ$_42l{)dc;^~yFt-0{&u4VqyOu-T6wyUo0+=tf{Wa`cola~Eg_TY8&s`EMP$_c zW76Ey*HkXeg(M<%wfd2%1d(KA%h11Y9M3z&a?)0oMAPSPAmeUbB+i#d&~?9U zCT7iPq{EIMX`9_yWsUjIJIiNkf5bjpI^(A!OQo#&Se+kxL3l4*520DszWR=LH2QOM zbbQx9lZvs8snol)iCh@lmFV<-baU^U|2RkA#&dFGx|y~tbuou0?E9cVa<%oR_j?{C zaYk0s^M}54UP+U(s{`w1@}Sq3*^pg?-Tdwy>1>ijr`1>zwLKv=cXrW3MI%Xd%PkV? zmrE`7j;}x{``jXaz;^@lyj3kftU5s~?03_#6S=f#${SLXlt6P{Wl1Aa+DO9PHMGig zoP^K`^F{o=d0$Pzy|)b32d)<^A(}nGfWG*FS1P+Qh?0jdox`TmC=U0VoPnj#p&Mvl zmkI(ag3#ZA%doAgsB(C0A$xr9k<=4^AvdlEk->M`Yt}07&W)a5Iq7kGO&=2-O+4zY ztkLQoiBlFo(UQgk0s^uGq7j-G;D>X!#w4;LzQ>m_xN;$drS7YvLb(vX* ztGUk77C} z8Y%iHSTmIy4V75;JEj=2WX3T)iE&>?y~1h*#vn8yyOgzjbYsTt7IVmOxIIbU z`WW0bP!m-j&AVLN#o%do#*CJ>g_hH`w#n*PYc=WaRYuoD?^hvYLs#NqA%1d?q$~~e zjClVJ8sjm4l2~VzG&%RAboW@Yl$Fy%QIzRV@i?mUbb0vMKKkNzmD1HjKgs8J0|K9d zXvKYwhx7MGPBP!rBO2Ies5`Oe^{q0uyH~(oTrwB@3U(9f5h0DkC6=Evh&veB^Xnxx zByZ|Y8a8_$fmMKLgvRSym{Ii?7GEy%3Zg~CoJWILm+Q-@eeBN|G6OOkY6YSGb^g3I zznr~aoGrKyJo)azYs9B*H*H_#swgUtOydI|bl~ZDz5L;77V-bRm|DF$AwgD(h|j-_ z;SH%{c%)Ib7P1&|^(#?W(%;m9Z##0=JTC2a@`2> zs-a1$jnAXiL6<7J`|g))bVXFtf1=`|HR)&N*yu@o-0~I%|7mu!mufOgsZFn|m3ef$pE3vV~Vwbt?l#{?-GR$LbQmWQ&;dqBOj2-No!@8!e*y`B>7XyiJ^1aKN8tm zhj@N7*+rgcaZwLl#{E_~SzWPOvOQ&7xy7=Kbg`Q+8GJTUxV!yD6H6$X!v|*MF{mi$ zk8m;|bnw}DZhEdi_wAo7BuI!5UG%Oy;x)^su_pgn98P-ZAJDrHnr<+JEm_sfX7=$H zW)#eZ;yi!?i_jsRFQ~qi0z6KTF$at8ks{jKs~}YAvCk0A5A{Bf*)|q z5HbVQJai(2p4H{c#`_nutuMoboITFyo55;^$W3^>)r|xp9sL zrs96JpQVcvHqgWw&njS2Q>ODFPyEfqoLl}kK!(bJ>%l4@bha{*haXRs%{>>&uX>gf zb##;zIaaTRYzre68DM$zD{kQg3j_PzWnAyAmLkoh9ptqu<5gA#}GLz;aI z@)c$+G0AjrT*{3qICJY}p@po5xdfsS3R&I6x*rYUTVnQWprW8V!?h85{p2rpCT$V# zGGvMtW)b)lL@U*`oywyh_R@5%v&751uaI6}Qb=G-UetMubs%n1Jz*u2 zc2US(I4vRbmD_}qC${kD%`*?~7A7P_z&9b(d9#s$W@}#*o0s^KC$WVk9p8Oa_C@M;*h~0|0}=2|2z|ckkEe&OWP`8QFvteT zE722Y#m~e}M~<)t%}oITI|$JTb?W7Vt1sSW*4N5}^a|I598L;qN_tUcWmd7G?1*Xrz%^h-LFisi9DisQDi;pgu7ztr1l%n`z1L{DS?Mn%-+GvE=Y;+! zdSbwiE6k^P5bmm^D(rmi10>iq)eu(F2E_lTbyh+pe zMfnT0f(TeQgvx^F@}y*AnVv@&)*U_t(FlF zt=WP!y~n9UVXDFJmoS$ibn3N^KM(#UIo&JNz?=Yc3H+LXPk_R#$SZz$v|>>%tcLb|UyoDj2K i)#6}E;cXQ1N}L9odpfN0UP2d~xuJpoKm=qcLjMEk7cF@J literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/ring0_collision.STL b/data/MPL/mesh/ring0_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..9d055eb5fd96a72ee1a498ad579f99df0217a679 GIT binary patch literal 2184 zcmb7EZBSHY6h0)04zPlNO@ZTLBkXQKO=&Xw-o1CilAIw%(Qt5-Y2;Hxzy(4B*|8eJ z(ood+vRnx=L6T6u_P+PNtBh8|DqxJti006)kO2cSlMyEE&-4E5{=Mfp?{l8>oadc= zdAa6-v{Y@nId_jXCOa)BHO(CPdequztuDWCr}i~H{IAd8u8!;VHj$igQa5Cgu19;& zqn~|EHKEIeJBv<`(F0wya`Q4FvD;UeZf+sTLrVpKB?BKDZF@S!L62O?(cMqXr*y)k zzl$X8?3IV^>V>K!PSVlhPZOuElCx#LZp1B{Lw)Q1C|yvV#X|J~H2>-q@`vI}%jWCl zFQ?n-*02zI{40NYdrK4bbO8kzet%Sq^U^BQx>VMkT}##}Ep*Mn6*MJciSQ9zAj?dQ3J#J#4q-t9cu>YNJW{< zYxPMHRb%_IS;lI+viqzz9enjRJr(&j!3g{wz>{+W>JNDt%=-O590FHiwg4rMyp$dK z18U+}5$BS@&FAGv#ZJvuAI>oV`(}$&ZErlwJh@oHRhS|F#zVsy@x_r)#d6IoVfQ^c zp%J2rFVg0}=Ly~{z+9Mv%IBAv)-wyI72Xgl{DSLd_q1eM+GVY6K!m0yo7%yc%K519>mUVIofDyP8K&6t-b~pVl)W+Wvp9bpb zkqsF{QdEMg@OBckC-(tF6^`>6!T>IvaVFwU05gS2tRm1$${X%6;#9+|_%}|w5kWy-66E(7F%yjD5!Rth>CTlw zQMbw2iC@R8_&c|UW=L;@42$AS8^H)%g>N3fyDN&S8)t-Vzwya{S@DRK>n!Y*sl&7( zp-RE|inodV2A~-!WgncpA;&bU3hs;1JYrT&X30rU#pzG~G~z#4UEB#E!oBbArtP+g w>Ux6t;>oc?0eant(4r98F&AsYfA9t4P5?b_hdc|^kghQ*R literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/ring1_collision.STL b/data/MPL/mesh/ring1_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..5b1f6af500798af90dfc1dae266494a26ddf0fc0 GIT binary patch literal 2684 zcmb7GX;76_7=DEdic6s>sAybSt{}OLfJ)zTGy(=MZm2mW1ICCpLO|ZDYboEiwkOw3u-PDT7%9|E`WeC8kF6i@9AIn?>WzT-uHQ)_x)~Ec4o$U zd&+9_n)MlZ%cHv7e8D zZ(%fm-zT*^pus}-Ey@&ep*=>^t#Bp%f;)}dAJL!(52s~;GiXIgma#6>ompmjQGoJ! zKB6Yu!Ukfj5(3`}+1PH>Odi6{PWaUTIJ$D9IJ0yIt?Vq|xDw1)wZ@ZfzB7m&aw%#A zcsy;4cydSQM;!A->)dMNTwD~(d%nxS?_xfH9hO$!Yj33ik!y*`)ME794Pl|~eadU= zfyPeaMngu1t5`#Thj(+t1+Q3cyLEy=r~dHVl?C`OarR+45YEOKxumx;R>!(enAEPk z4)IhyUmpy`J^|1dMVcu-fs6|oMAF;amBaC0D)}wF3P#|U0D2eMMeW3TI(BP0$9-UR zv2IR39@)j^K!e7AU8Z9{ux_$eH)0)P@F}VlrI#@LE=J3JSRM^%VGZ;3VO`lI|L=OG zuByZ6yXmjup0GCnosWA|aL?DDMr09uf)R36B{#B3;b+k-^Se|Xdr%VGrW|dEV2Z8n zKYsk!ZWA7h&D^kl!LcUTbF85=B@GVpa_eQyJGD#l8T*gD0hm)coj%t0^G&`sv9$S` z@^Ml$o09aEfjJyy%M>2w!3Lck@0_T`@!Q$qF}3{Kr3^ClM3vFz8pD1ns#aPe+?0WZ zZ?mq}u`2ckpkqd!cy&FJ_g7t4alJUNGGgF-mbkav&W~3d)bK6LCnMenn!<8Mgp>T7&?~9>c$<~Oq#ZJYf&q9FkCyX5W5LrNj$4R z6ant*`_Vd1BIdwb0$|(SJksVJ&eI3_Dee%@3RVOlxHpox#>QwKQ2~;= zI5AiSfZd}ukgm9Hw#R=v$M4qu`AS*$U@&_b)?&yUNsSxGle2-$@m2}PCm128MbmDVlNoa3r+wazX2au^A^oy1N&TrP271m<)8 z!741)zW1IiZu!q6IEgszcs~Mo?@D9Chug)errkP5;9GdR0_@$tNBhPlS4>Y{C?yf2 YWkksGlXU61wW2KO7mjtuIhGOs08m;C}5=76^K|#u#0E} zBM7Kj-n;jnvw{L^H;6)li-nGYE*eY3YXVEe)vrpso6VaWZ`$R`QUctR?Au$prmf6@-8ck+jy5ry^gLVsX=YZqrSTc_P{p* zTs|4fdwy|9G8|82e=RsFSI;xi4*2gd%~EY2rEy`Q{Cw|ddDU9_D7TcHI&T2*XQtBr3==-_7*)#+nspZch%ClwgDVlB?dn;w3FUiPc~WpDg3x> zdC);lp7h8VmD%57soKy}@eST5VMH-*@AR+8z<`I!{esOJfW%n1_A8 zxm^h7{|=OvHRw!a!hHu;&ktUF^{g7PVBmKESWbnkz=b;@>ZWwoTi*fdoPO~ zekQdnZ;dZ&%v{Ow39g#IO|!hpk1GeOvy5-VJ^H{Ji)*FsO>P_``c=SX!fAk$M?!>!yF^%s02y5V!Vb z*>uB3xo6)T5@X@1_*>nUi?T1c=WD(gVV8|0!uJ6FzNv7@y?le1iFkZvx0~`HysF^fcX|(Lq8~m?b|J z#u3>nRjE|lj4WAprIh@`R%Tu^Bk2740y)~CD2XR)2u4(#1|-)(bxW#aPbz~158Q*; z8{qJkR!+4HQum?un*dHB5%ER6v{1v&yuoa%+m}3BbuD?t7Y`l0y{Ba3e zVIGTl(0|*|NP820D|vu0ov{^WKERsdTy65|^>l&aEzChYGg`hW&|FTp&~|0M&;xkn zj#XXGCQ{4J5fZj~mYA-2(q^K~jtwQE$BD9a+@mg6>2)VcP*L0~Vg>g;_2g+e+m*>H zh6tL7brACnU}pctw7fY_x^bq8;V#1cfj1l@uina1(7+IybkJVH@!~v0gE?dHt9{3gL>^woUqAY5Bwg0`%ybxpnE*4n6OTmoLC33@&SxV z7^zl{Fr^+kKVj>`91~}hdf;2#sEd8+^qbzojKVvkSdVwt$I)Wf1*%V&R#0lpe39+B zo3xVMq#%CF;hLb-Sa-1=19YdIVi}9V=$K5MX}VOWc-oq= zf#KR>+(fLxX0D~qx$~5~9tVVJfU&}AXVj8nd)AtBMJ+c=5Vj?}x8Xk-fR5@>(%YyF z>aj72)MJ*p>(*K46tl6N!rw3MU;wxN=SleX8|>G(5MlSh9ffZ)VpaW%`mg3~>Z!L$ vf(Nz|-$-6#!P;p~YpufoMb;l|(@iQR#Jcxw_BKvKG7_cYk;9v%l}# zXFonPC#+0b9U0*km9#S6ZCYI9iipT0pZDMM^LHD!DtW1!uNVAZKMVBe>HAm9lZyki zUuxpTv6@om;C#)nC#irnM?Gaxb&uJv$49fmoC=nGAdZ}f`_TrlxGquj`GgqT>}Kj` zv9Z#!EdJe^D&p#I@lOdS0n^&rh|8!Fc72U0pz!WR0?<%@QM}PQQr0B<%9T$Su&bWM zJZXXxBOYI~;NCm)n8cA{Sd>eJXwOc?!9;`4A5;Zy=s8ISFje;vRA8nE>{;FOw^_ zw}=`2nvD$|&)KYsO}yJZic}r$VsANq!FSjGWDByKWM@+HdCQPI{p6MRQswmGnOe$w z-W+$a+0@C(y(CK-w2j=UKg}|nEoA(>^Z)?2%C#~-W|CGi=eKsu0Y>0A0mMxISavLb z)9&Q$OmP&h5c33(TIC=*edp7OwY@233Nxryb@+Cd$@R{B`tavo6i4mtC?#D_w1A4C z{~#e-Y^3Sm7V_r8jrut{`uNFhg>hp1{c#fWjC+OI1n7}IL59V3ihU`L5=UY5^zMtS zZ+I>@edebtF?_~g8Qd{Up6NAM;wKn^^#<_Q&J1DMyhPj|kRWk(tTBuRIGkT0ylXu~ z?eOLDgNs89#hK|mHoHO5E=KGA7F0rbI zep*Hf!fFhK;|rOZV{OqansT>4yZM`uviGPLWNJ<)i<&fu%{yI0CK}@T54TDgMgxp6 ztrrvx$`t@TaL}nwpm&ocuCP-Sh8|p}Y5U2NFOQ^l&g*YSQ?KBj4Cw zo&{sIdkVMjU8$?xo<2@4IrpXUSze%`E38UYi9RA$MoqXZ49_>3uyZi~m|6WCJV9RL z>6(=+)UbB3UU5Ev+E$QW+d^g5peTX+Zt5AtV#7}J#LM{sYK~Cna;@V+u~_vTHUof z*3zHarf4rB=iA3j>L!j^7g=M;CV~+-AHeM5MKU!!ThPX84Nn}*rpkGgHcJ$b>uK|7 zNmcHTV_k{t^$f8-wp!WzZZS;~zh9CDXqz=T}$M z5L^}B3;=auIBWV5gKakgzU=HwRpjY+OO7&m(6%|Y}W{n!6D2Y!MPst3EvE}1UO9Vqu{bCr7#`$Kiqn30R@i>9rTS4JNYm;*e6 zRX$pBbF?i9*G1#x1v2oT`K@N9D(pM#M}XXg6O6x%jF8cxEjlOv z+YNCgxIzFe@*^3tb}Wkyc2#a?yg#VZXV{rk+ORc5bE)vz%t3qaw6i>8 zoRwl91Qo=x*PN?-xaFF){$GD-UtOA_sHB(64E9=;sz08%pA=m8V4v|36#EWOXN(5; zw6a*V)MN--W)#Km!ciCv@XU75?xUY0O+N>&9V66pymAu2dim-vt_mY?M_$DN{P~gO z4y|eq9EH&Ux5{>EH=>i}yxRkn$$&Y>Gan#5Ka#HEH--7hW;>puc<$nf3UL3jFLk|= zX>=ZHP<)O#$9oq*Y-<7?F*Z#baB883Rf3~18ld=J8RC%ZUi-fKWQr#ocCgyruL=va z`yuH<7Dp>pVKlyp0N%OeNRK|ACm&=zGT|o}q4uiZqnWgzA)ouTk5qEtdr3VOaCQ{Mwc{LkR_Z(4TY>Z?c*$(r0A&}&m8g6;Nq?HxFhMSxU1Gvfm_d9#fO7X; zB=8iqr=7Mc-NhZnE&%v=L!u!)*FtyvTxZ7&VsES8)sn)>Z6m5J)I0c`9Y4X_D}EEe ziS1JihYmzix%8HXE5T714R9uBeZZ0-CK~;fx5Sm;9R=qG7?kd6XyrzFv)x;na5xI1 z0V2=Eu!0L#`H_#83HJogdCVrj;}=%iV*?mV@>d05Wng!yDye#CrL&6G8LzZ0<9PqX vQ5da%H|Vs=+?|>+*kvHcyD0uXfOkfKce|{zGS_g z%3hn1?zJp?)e5iqnHek7GqM9`1#v_2D`wq^6$j6? zks)Izb9W8kB{x)3+G)>InI}K`^=2}4s~b-`HjM*Z?H!b3y6e>Pv?vXuudItK?G0fc zzB`St&$&X3hrVZ@ulKYu#vN!@uZ=L$+q+xU*=B`Be(Xn54jR~);B4kkyQPj|U%q2Z z8>{=hQ~DzJIRmKfdn#XRFo?QK1uD)2XQ+*Fr0|&>ye^I=JT$5H<$_!sSjYco4q`*DwmF|iB?zp6qCvI9n#?pf3A$K&>drbgk_d9 zd=kLouv*>rmy>B%+%SPrn2l=!c-`4a++0)6gNTt1wAHY=<<7jNZH~0vYdVP#?tJu8 zBYAY*hfE0Xk(!zk2!QcagBstTELu;RRWIKZHaO0W-}mt4HSt$iV6iLTXuZSif)266 zT~7Ss@(H#&qTLqiAD;E4mJOj4pCx~2CIKle(%mVEWbPs}aof}`)fi%JG3=du{!(M6gd4nc*ToZuPw+Z^?yVlXlo&p(1$64Wy0Q9Aw zBSqagbVb`IGDg{5O<R`l9;g>T>pOwjY6e3v{@nFT69zOs{rGC6$FXNBN)h5MeKe(n8$| z75~8utq14FEEK=3oj^CoWa@ENI37L;U}f1@adp*j+3-gU#rfhowB7B`8z-7vLoB@x z28vPGD_X`!`yEA;HD6wkx`<*IVMgiUYTdjCcl zfXOp^&oYGE6$OV?WbCJza`5Vo0 z^R+M4fv1Zp{`1*4o#er-#ca$wxk&ORB(r#{R(m2UwE)swgXpCDstV zz&C{%_#}Yxa|)fb-cz5vx0m7RjCK6LHnrCtI-*M~G1%%b4a*W0FWqIPQD3XRG5xG= zmkW=NFJkzf@gxGs%*zzzl?TjYJbtcd|#iM9oi{6b=tV1)v_5f&>Zu8!i{{&LmaIqntiAwba46d}*CW51rY z)A$4H6)PX$?3pE^D{6rCRu9Vf4`$#V0;IM?=|8FJCKq-pn)e*fD6Afv+TZWt#hdiJ z`IeS}yMWmM!^tqdW&CqXO3bO$mY884aD75iRpbNnPT69eG%q$KL$>?rnzAJ;H2O1t~06(i-_Cq5AI6<;yDEny|%9s<0Q>P$?w zyO`u;vS5wk$*EO(B!#F#iyACMA zyR?~M6lPl zwzWuj%fQnBzw-c1V}?d?EaZ-Xm-TIp?EgV3fAI4Q&!H zGMr#1o+_H10W)wsfGV%y`tjRMB*Us`c2Ug0o(Gsdu!rmp5aecuLb10o3bO%jI6Lao SbH7p>60<1o4@O~c0{jhvjAjS` literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/thumb1_collision.STL b/data/MPL/mesh/thumb1_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..97fe1dc9c3f061635a35021c4df2c5d8f8981dd2 GIT binary patch literal 3484 zcmb7HX*iZy7=GF=q{x;+QWQ0mR`tE-eUD5EEeg?QlF~9QmX8*b<*LS1Dlw*g8AHUB zD@}{O_x;|3(ltscZA=T*Or?E{(6pHE=W~9Jzwf!9=REg)Kll0gu8WC|i;r6Dv?MNi zm6OlPsMU+3;ygwU^BU*mrcH=+@*D#H>u;jr^pv6lQcI(jc}HdlkINjz$Cc&sJ!V6y zrxcJ8izX;X|6Hh{(GH^7`pdGz)jkTqs9h_hoUsWk#LiP16nK}2)2x-mDq{|TD*Saa4lEIJYsM%hp&f$bwi4O5Y>c5t#Df%;zvdnhs&*5MD9U~! zAIMuN?>}Nk_*;d$yQt15H_+nR=bFGWCvvFRlZ2e9m%|rljt^_2UCKln zR;lOs;dtW^bCwOzrzy$o%VwR3Rl{6i4gvg3-PBU67Jci9M20!BJ+N8cx#zCD|Fxxp z83C9RGeN!L1(H5=J;R*fIWW@z1xJIKd7(L5wqu|k*TwAeJ-SBR5r_2X$JR&sQS6`m zYICt6cey<4nLx1L05Y|sR9mABbk96%1+$Cwz&Zis-R#d6{yUi-jBV86Qy9(baq+?v z{kh?DY4^I$6eI8{Uh}W5kE>z!v8=EnjPodFf!AZu;2uo-a27jXIZ4E)u){HL02Vb` z^;(RUN&W$9Wgj3;cbt`eZyw6HF0KSne|Dq3t#BBtiq&wMV>FKlYuPWBE;nOsb-`@m z3=6TtK2+AdBMMG~pwV^Y#TXmKRny(DQC-8HN<}Y2sdwuEb<>h|GBwMSeE3u=fAn$^ z>x+&G?&h}2-&=Z!4m;X~DNcP22=CKos5$?kX}#W%q>#QFm)bl9Mr zj0$3dt1KwqJM34irUB8O!qUtPIh*9iO^dgSpFAt8nsiuqsLc)GoE}&Myv+a~Vk)G& zH`1kf6C-JPSx+$|AYMq%70Ae>zM=&))6`^pk?dK0MdQ?Zp$_^Q(#LXX5Q*B@nOzw( zpW?m4cgHgUJQ#0J7F_O0KMj~gF(;TS+#6uE<{CL;Q!9CVvz$Fhwh^-n2MO0#i(FFk z3jQ`3^tYc6V{ghe3{Q)_%TIn*yF>EX(k9jChA`|t+>h_^!!3VNG}bcrr-vn+qIg=Y zEWndyOLAg+o2pnv(1OO^BvO|qlj#D%Twx9Ye)SF^pF*tZtHU!W<{k6KbJZ!UTDNk! zGxaj}<=l?%j(rR;;_V~7=?Z%~INqP(FF2`j+5!AAu^T13qNIV(gE&1fZ|=-Z-1EJ5 z{LId_hONC_{z7_w%u#jh7D2zWcN05cohHb%H^I~51P2i7fbKPpQ_C)eQ0zX8z?BT| z$BbsF)F(teGi)Bi-EsQhR023P_Lh|6aYSF-e;KzQSaVznAn>0I@+?1&oqPF^;0+?D6r=OnTM)z5Ha|&W@cs*(-y^t&m)1-jdIUKv# zF_=RD6PJtPxjb_+?s_t}wfGe8t3lVlmFn)VVOz6|xH&MpcqV}Nt)Om-aaZ#uC30@Z z8HJq>u&?H$zIsQvQevFUA#gHaG{6Qro8I`{nEK>=CfE(wiI@e$`(eC-20pzkr9W(! zv9=h2D*@>5#L@P1IqJ5p`2-{IDc-wM7dowG9&Kj#6pX<9U={!# z?lPsl4~Ehn7Xo$o3+{m{0i52Ms%*Enl`Gm(xZe!eyLh_*8YZVImk0KjFBuT{3*J;d zsmo5Rk`u4?qIM3!6nDq`;F$nkOW7H(Mji@w4DG^y(gs2$GB|@#N zM#$yJ^?cvidoavoT*hq}U0lX2vs?zzkX+`>zjx2SIe*W7_WQlh^SsZyhi9ZDr_PU$ z(TQ7zR9 zc6&(Omb%E>o;IniwmWOV>s{rXcMa-|@p=M4=Wk^Cja%h9I-jzD7NpcKUn&h7MHat0 ztyTw=NF7TZ$$=+tR5rHG+I-v5j`-VOVUc;6bXQZHly@L0ME>PPmPZ>& z?9AuV+v=|5>1981Ue8p3lY8>n@naKN{l{clb!o0T>dP86z{iP{ZE_(UAOEbLdNAZa zHCDYlz{sW)KJVakHLR_HI9v(UuH+U4WAyIEGF5M@R@cB~dyT+xQjYTNp80skhW4LSF`O3gL+XlMI2sFrCHrJPe2)gq^- zQba?glyuTp1Msn|Wl7nqZ7eaJDtky+(ZcMz+jthtj)KA}`A=IgzNk6SGz;Fp7Bt zNZ#^TF^5OfX>5Zsi@YJv@{GjK{6eb!rM;X`*d%#u(US*3I@x(|xuoyX+wR1Bb0|w( zl1VcQOo9`!`*3Z5t!%q8()}a5QaP65IS72FlRf(FRQvbQlj)XDa@D$UwRuOly+**6 z8j?D%j`cg9z_G8e&X^H^W4AiVIg^+28$mTT%p!IlcBP%GxXsEP+gotZS91p63sXz$~^Ng0#0fOl#cr8EcG$geTpT6toFkVGP)Y)=5o zeAb`;5fvoNU_G=XQ+M{(qONllPa43~hc32PAJX}to%sy2ixHS?6;?A&eNP+MiHH*M`1#<9b3Mu~2Z{q4NcqiFAaIt5o$K7Lsi{^Y*9{EexN|&FqT2(1 zoOJT`3om+i$1sk&#VlZD0WS2bS4<>I& zz~BTl!zQtpdnX9%MQ;x3IT-H`%r4GjfH%#a)|d}j^ql3PicjGe zfQX228bW3!G%9MvG$F6>Cc_Q|7<06bW*ORz#+g4C-X%Eg@O}g+ywzFDt@5O=YRnXW z2|k6<0FL{PTOV)np$;oT1q41N_K~-}6)iauL*s(K74j9Q0p<|E+rJ&{UNfF{NS`3# zfAGCHj{$haYWw&H*Az4#^oUEl6pT{W7P z9z3mKkK$Cro(6cbtvwHa6h+U}^%7pJSaXa97-vhR2DwZL9&tj$onwA5(*Wl8Poxw5 zed&4#6>=A=DW=bWIm^|(pAF%8ranR@;w-_53gC1zo7`VChOgY^A!H)vP26hM=r!s> zKeO#qOO}xBc%ty8wrf7`koNw3lJ)HKEa9v0HV|j9t(vAu4HeS8*I7b};^f4s4X`%S js1@b()LJ!V2}zAJSVWAdOHosH&XG+U#2Pr~MRxxI%Ja1^ literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/thumb3_collision.STL b/data/MPL/mesh/thumb3_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..373c2434d3387faa788b274ff9db1d6b524455fc GIT binary patch literal 4984 zcmb7Id0dWJ8@^MY)=A2zQV2=L=p`Se=e+04_+*`mvZXRv+DIyzvNR=I%uJ085iv%j zvV?|sp7$Kaph=d<)@Ln*Ed9vXnfLqeKHq;||Gwus=U%Ssy6-3dw8S~d^P*u;LzbX%8pym4Zrx^PiCdzBePZoYCT|)q|(tW26_3c57kW^a(-3hl^0TE8Y!T;x2~*j-RdCuAvW zT^=fORBL>87y{l}iWOTYNKv^Sk02j)mRi5QAVmnUQPdc0ZH9?oz1##og`>jJ0z}{1 zt?`Qu)ITXos;*hee9~yLSJ^SvhNMmQQ0vY-Q{G*8qyP+FVa+CI_zUk2J87ZGX7Z%? zh1zXbgVOIq0cm6BtT~+TOVX>+T(7!gy73#frdh!3@=r8gRMQ^^32uG(0~YUw?ISp`SPGhZFc``%An zS0|~>-5)D$i=L?W3%to+H%*DR=Lz+xO*SbRTCBh;8)F9#cCqH>%i7Zyu#n*laX&EM z0K&&lVb>#Td0|p6#Th!aHWKUMc}L!gil9AV63)Fx||vng0ag}C#q zUYxu**{C{4nfo2pRui+8-L&;ZL)Dp?r%A+&67^H_NEKjbiygZc__ZkZ2%#8(-@}zQ z)+%=njp;X3T;d@74QAzB-zgO!^ zFDUpXfQIRXhC^*%^GS~1u;pcGB>pN_2WNF6SY7x%faI1;x~0lqRIeQ_A@C{rjo>qm z+~+fc{*m1x5mg&N=8x~F)Mxe7QnTNx@$X{%9v3&OxU&EwJAY2sEH&5K%~`~@G_5D8 zU76o;GY5jZCObo`XE;lJU&lQ|@;UAr?g2NsPYU8M`i=e}*w_zJn8flo{KOsp)N%aF zhO8%~P3Mt{^}~N2!8ZZyPETRM3l{ThQKl51!px8nQ>hpGV^9zFysDC(AN_>1`$Z`G z9GVZ6zrR90rQTQk;|D3F?zc%^$N{CoHqpqd%Q4;cAr7Nh)n!+Pm73=nKpthAk3oU>RzP&}i+T4-Zgk2>j55_CkEq5t6D*27Dn$xs?-F6=RN0`Jb%o5B6fK%5S zsqJ&B&uE#!whcT^Dyq_tgoNKv@Ox(AHNkC4%xJNWYa z4U*uQD){cD6yJsY13Nf?YxP7Lb0%5nPOKGc3^9Ug87Qs9{k`6 znK`IQi5oN6Sl!S^cG@ouFX`*-NP#^ZyM*iv`NMsw-PW60(&2?t<~UpI7y!iwrcj3- zA@sa5k734PFOd<>?*i$;)j!Z}C5aLO>k*>?oFitlPN_xuk7HDhodNp_);~aXasyqq z?-ad!G>~C+;s~+2j5BKGLAsyo*YlNDVBRw`C7uC(!u!hZB}dK+@Q*CMh0 z&U!Mv!OAa#cF?dhV2&BLzUDgG;AGtHYGNfs&Zjc+CTEs1F3?nyongpEJ=+goh=Tuk zDR`daiSs`?FRM3vtP2(Ec9}A)BCJ|jgK7WjLpu%`!*=G|3cT;&T4CJ)RMiC0IL9e8 zEqR_)U7UxU`L41{^wYLj=9B-Gf|ZK-ir)j6_S-~eKfg>rQ)eM?r*IE&ZvZBq7|RsD z8oufG3(~B`wZfeRXjvM=sAfjv`kbd&AJ|cGga8%C2e7NQgui#{C;2W`k*p8v8z-r0 z`3P>YI9l3duv5#3{w-VS+SJM7u}2-p`oIkL7_y!0AJ?juHB=e7+r}k^1|&@rai+B# z>jNY3O#qgS4{2>q3H=ZjB5>DmrRD0LYbm6%%y9{enVKrJn72|JATQw#agp^FweR}QqM6OcN1V=PFHrlt&<>Mwvna*uA7`krgI>( zs&^F2gB}mYr|_;WJN3$qMRfW>SN5*OSDMb4yLeIqEZ??_)|GtD5>#)A?f4W%1B}0L zgIYV9YWojGOS>rUhpfS}Pzz?2c9-{e@fA2jjF4UQ(u%?2_i~+Rm%mVtrwsmYguGJ+ z)g&5Pf6QP8pM2>H8*gFq_eVu?kRhoogGK7*D!9-1l-zUmXuJrqFmA6c`3Ah7<4ACX z0DT`U5Om=%y6Tyi9wYE6{B;jdFtC@XuK0=_=>3G?UvN}7CxChN!9tgB$NJnIW55V} t3cn3dHY0~Wy_X`&1GA<72;oZOoB&R^=JL4e6k)&fyox71MqtMP_!~Ea;0FKz literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/wristx_collision.STL b/data/MPL/mesh/wristx_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..d6d5ee4659668341a722a5c2110b83778bcca44f GIT binary patch literal 2984 zcmb7GYfO|!6uoJIBKX8=M6jh2q@a|Cionk9uqZ-BgV3O00mEYvP*5pGgWy_%B)$+q zv`9f$5ucPODrLXjxC$B zvUSN$DOsB{oPsv#GLv;#9zI_z@pJn8n{A0sUT*NeegWp{*zG&{vuU%Gl+oX1-Crgq z-}jQs-6biZsf)!AO_ui=-WeCTw6W{MQ)LLtWB}!1t~BI^mJYP2$+LMqDi^wj9Exsb z+%keZK0cuO_G%5WeW)dARa3~N@D?-Tz`bZX;$TgC{T08;;7-yvD~TP|9%i@-qXArh zKCAw~Sx+0ju26Y~#YmyG>BQT+hFm&(Q`M)9CySIbq_BR0lt42`Zg{J?$Mn=!O7rYw zdiYMEYLml6*1Il<%xi36?Zb{NI>nb99;+t!B=c0E1!^s=Q@Tbr)2HdaOik@$h(ca>+_PwD!7DsyKd9W zQatC$UP%khQ@!zCz{|8DY+0(BV;0xUZf9A(LCoq!7Q18E#9}W;8R_fy_plrCWvxr> zc=Vh|0a5U6EBW=Dz3gU}z{DP-Q)X&*1mw}mlkX(V3FZpx1n}fh1RpzQM{TKwL>^0L zyK{?FZKg8>bJa6>1q-dVAVqiIE2vp{RCyMwQZjtD2vgzNBfe~tq}pV*-qvJBeBZxJ zy1*YQ8 zI57Z%E$(YhOS9yc%hM=!AFje^fIXuI%@MbyN?2cp;6%(%ZHg6X_$Zhe^_VJXenF96K^cll;k^d>=L}SIEes?O*#DEMzyj&p-PRl#d=^b0OXbW zk|*_g?rR;WUJ+y>`5~V2$}1i!jK*F7xYwkollFPZdDVduo*nZeA|Ba%Xgt=Y=P6Cj z!W)IFa6fNE%;MQi*Q5=hAfEb9PC_7@^S3M}`t|t>|*fk&$s53d4k&iE<6i z7}Ghud%ruEA&itU&8TR`t&nRj!?=9s`?vP@?>m3r{p`KgUeEKawNF^alEo=$i3yH# zQWh_C9JL^EQ9@#hm%sPOKu5RKWwRW8-QoZGWf)i6zB#7MB@Jw9+alsnyMeCHvM}t8 z{70&~l}|5IKQ^SQUdnxbSswIDh9U5LFEzm00nvP~$8}a@+MP$<`IBzzWldw>AERTM z?$PZNY}f!@A}tR#VV;G~wDmy>1(+IMq%^cXV^;d5{N=TBd2(~UoV1`93mjTN9jg4; zq%HN7bu6H#9(fr?&gjGdRP_t_E4RBWqu@tn(#Rf6e`Yj2*=8o}i_ZhNu&fLK)dTjhinjloHqau-ai4gnip06D8j=f5T3b&c-wD_4Fb?N8VJn zJ+IkVLz_d=LV76A_ggdjiRNnO0pWCW-*)-BT~BqHVF8^O zc0eWN|07*Cw`I;tzK{Vnm*~iuJ7H{46sOu>E!11D_!!m{=c+IQ?*!1NbvXHbM>)Ir zn?Gr>IwI}-raSE$a8rsdu92Q7gBW$)FU1<}O1<0dsr#6H62Ot~`;tAgC-MIKy@PP< zU-q$;VoZ|Ro|84w(2J*43%f33xtq=#5xMar$lt*M+{-Rl{Y6EGv}cqptE_O8Fha~D z(Zic8`&PxL?)v6q`~@TM*#OfVV|ihlH*@sr#xdjG_IOD91eh4ErthJcp#aTs*8CIg zN!I^dIN4r#iUu_dVIS-(1h(I5IYJ}l8wT>=jxi69WEVcl;vgG6GlbwTCyN{C^(0IB zFj|)IP5?Gbx^j3Sv+dhs1Vv#qRu{myXBxii&msKidwY$e_aka>vSDR3Qc5s;Lk(HB ztmEMp)put*({6j0uwl1qj8XMJ>cg)D1o8ND>s5G_;`@eP-($;OI~isev|y&ulj$c9ELB)(04^;ml12`&2gRN|xT0KoxTF)+>Tgo3rk7Gn#|V12 zc@xE)HX;Ho$&Bi!lHbh90s?DdOni+LrRixnpLdA@d_FNz6IMS^IUccGP!z5+)+Rvc z`?*1dPXiRs&e?*OVAURPE0brsr?Wt-^Tso}J4`1Qz2aEmCqODDbyEAeXlRAwH0kA> zcF9cHVAxq&`af)6Gq_okKkPbdOHU-9ZpoJ-D*f2euuBrw%Kg;g(yn`p4K|J4jh;AQ z)^g&1cAye1B`8>Hn8ybK?@4cevSB;SKQ~5oxJXAVcTHr=uN9AW)sL*YdCX!Zvb`|M)AC*w){XznsP+nk5;}+W;MDR!KvpMRZwG8 zL79EUf1~Q>%+HO!sVIk?2<9kexX7zjF%i6>He<waiZ86uwwvdr!M8GA9ZH)O%DkOyh_wZ`QKW;({~abqa7w7@T!i|-fV0~sA1xZ z=T!g&mQxhJ)GVIiwl8SWm|ptU)mpaw?P=O_yGY;sv6ihlRwIerUE-QRlztm&mPMNe zb2sWlXZ25EOGs&yNFRNZHpRE*ybyMeV za57l#)d;K{YV<~G3}0d_>Fh?R;m zkGq}%0=p=7SAetxYo1@Ouq_wDg{bD39Hq9GoeXzZ-=TPN0?_UA;G-^o%if$-bG!=Y zB<69Onsb^H#UHp{6Z!;p36Y7JC%w6BrQ&YV!YZsatXhl)cy~L5TYc}qi}S+-_rVB! z(*R#bPUj^BFIe(luQk{+u+Fjm0j5t*=ey8`Hi<(Ycr;BaSx`GXaOXA}VQj!!kYQydlF>U1*2K0)e)w{wM$)@qS7K|1V zI;EUt@6Y7NGb1!O!_R6ov?Sz}K6q$1HGVAtd|4OC=Wf=q(l|?ky$^dLW+lLi`dX=r z=WX^na)t2zz;BL;heybM^BVLWLwXxu6S?G5mFz;doixYtJ{aE4}3(Br#rW`vbt{|=~!1kQMBxcMFM!iP~I>*`;5#KJ)(3Hev zaI<%ZRCuPsdK5GFYK_t?9-qZ`Sp6pSbBq=dU;mm&>_dAh4`Lbwwqu54j{!InGKa`6 z)pCQ7iAf>+@lj_(cNm(%e|VEa-M<(8?ztj65MuNMGE zRVZ0Gp&!pHSfjy?gB2|1@t0FNF==M>Rqs3vo?dX~c=iS8;*w6X^_*^gv|5;burr8= zMX6dcJ2XI9uz9`k=ETl`(EyiMuHc!~fl|ujCN-W#FcZc8G5%qi;`7W`T^X4nyg#t+ zMAgQRaptb|P0EKKoP~al6)bkn6Cp`_5d*8oj!U6k}Tf2F!H zlj97r!(m?mNHiOw)ERt~*OxK`1imYb23XxxEA8^}Rw{h53Dz1`t=QH6@ESo{f4@WL zod_U!g2dV4TL5TS)*6&l_g=9vpTY6mj$_A~2N;_dsY>{uBa2q4Wvos-Gh!70{2KLG z9qyY$x{NcZaa1@G5uvQik{Vy>h})DL8PDzbJQ1F?BYt-$8GpeDvF3A%oaAyN!l|#RjJqX9V2=TqUq4IQ`a(xS`~xXg4n~Oo0emwx z*)Yp^hU?%>Dy$E@FGd3-l>s$Fi-_Y-ie)n+Vnd083f~n*i-_(g zBBZEmIR-d8sifhl~wXxKel(p0ACs z)S9<)(mNd~tSk_?ixK$V05mR^L3@p79CwJ8G2<`--y6X0ZXr@pyN)~xKPq7dz&T+w pz_F88<>>c1q8=M8V+3A>?+u{v-~Hq&V^k%_Z&zV$<7_b+;6Gg6V8#Fd literal 0 HcmV?d00001 diff --git a/data/MPL/mesh/wristz_collision.STL b/data/MPL/mesh/wristz_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..95a0f9b48b50407944651f7516b88b25d8919121 GIT binary patch literal 3884 zcmb7GZB$iN8h)2RDoQ#MWTFUy3aAJP3is@LwqR;13TWPvuZ0L=BH&yQ1d%gpSP@gU z6wRepW+{TiXx!m&&*p5Gi)P3rlp{I98U@QrxqhKyN_@=u`R@5Q=kM9i`}I8U$Kvf< zbFKLq={_5+x!FF^TQYLeGpuu74PFr86Ogwp%_k%f{;w~_cwOd^MsB+vkf*qAqg_e$ zI z6jcHXyT8=%QQj6~Us6#@dw%FJzpz|oKbEg2j=|%Sn~RO8nQ5f@&`~Mrg32-++2q7; zt{Q-O<_=mu#b2&EeM3O}qf=$;oTJE%>0^i~L1pCWZc)VsKY3%{5pfOP30HXm~`V{-U zV}(5T@h<(-&ut{M@ohHGvQEQniVU6`Jxcd9XLFZl-w2#bmsGamQWUFs=E*Ss0N?c1 z%9AIa)boee3!Gz~&wgto?=<$?)w(Q$k0sYm%7v*j`I*bXwEv=wxczEomn1hq8CWp@ z?=Q2+oyAGKW70jDl-bA&tJ2vzuL=pHMTFD7ucY5+ndsQR&lS|ZS+SA%Gor}U64(Dx zNlN!Et>d#d=$9Y8NbxJIN>NuqQ^v5Ot`fR)%~TodwPlBmSTE&}KZVych}vzx;zqpU zi|P3^i;iDmU5SYL^JnE{en088Eo(T|66Rmze8{8E6nD3TFJ0m-Fo^lT+*(T-U$(OP z&3jaUWaWI*&lbBp7@19xb_t#mxSIhAV~G@p5)Phl-cacK8LoLRFKXGDodR0 zD}8CnBK{7Qeb0|-2ZB=#&gW+C)6_C|dSXGmzz41pv*b*gKTF)Sh5Ds7 z>zG^2Ii4{9RY#&&TDw)gU%Q=SyV#$|`N|Pj_29`)JkMhx$DNANV%LuU+amck{i}K2 z>0*kz6Z0=}{!ZX#`bSKg9`-Vr+pemt;Eil{q^Ht^XGz&%m3?R1#8&P7iv+Mcf1lKu zxPy;%iDmbWK9IfWWUr21DZV$p>K z4~lcw@yQ4lc1YnHr3^E!70w)28la)d!`|7jN1mBhD5xE?CT70wz0jr&;TiIys3HM@ zU*WnLeSUj9^=eM00Cd$=Ye}Pk57s7g z{0gH*27^|&%y)_$)`RXPQ=B25kGLWLBb`5JnD*MR{`^j|zz0TSHUSRF0K!r5&%O+9yiBjka6x4gx!au5`APEwc2>S*%bLh zAi;m|M8(QCw!v+Mzj94~_)a5TJipp+E66kxwr~n($qMcL}}#0W3c%w6=1*`E}D14PO>`<6uhwF?SUD z>&_ZheP%bofADt3mH^!TQ0R$3yVi5)Rf6v;VTYrO96+ltrLWgJnH;BD&DaNuiiuZv zo00j`5HBgIY=)3ILJ(X9fQTW5y8pRNTAp95;jND&#J&LzK2>Pff+AuadZOV!I1gL} zfciRx63 - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h b/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h index 65bdd330b..95cd93ef3 100644 --- a/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h +++ b/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h @@ -98,8 +98,11 @@ static GLInstanceGraphicsShape* LoadMeshFromSTL(const char* relativeFileName) } fclose(file); } - shape->m_numIndices = shape->m_indices->size(); - shape->m_numvertices = shape->m_vertices->size(); + if (shape) + { + shape->m_numIndices = shape->m_indices->size(); + shape->m_numvertices = shape->m_vertices->size(); + } return shape; } From cf5702c0be2ec2d9aaa0e2ab10bea9a8a0547cbb Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 7 Mar 2017 22:34:43 -0800 Subject: [PATCH 13/66] update pybullet quickstart guide pdf from https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA --- docs/pybullet_quickstartguide.pdf | Bin 487787 -> 494544 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index d81dbde85dbff870cac2e9294335b1310cb546cb..7151792ec2641551074153d9735d34af09352188 100644 GIT binary patch delta 145337 zcma&Nbs(Mn`vB}P-Q67BaY7qodfG74&8EALHp6DlbepMZrkgP}HO+LlnHc6h*z-K! z_xJwu?vFF~)qQ==eV==0nRYmlj*vxNMve!>D}cq)dY1DCOBno)kOm?G6@Ws4df{Fn7RDlp7Am39UR0JX<40&hb4S*yDIiSWf=~ zEcivtg-xx5z-AT@Aut#UH5U=G6f%W~2!J6FL5cql1;PI%fiDA?_-&9FOKO4?Bp?Ko z^A8x4Sy2?bbNu)lab%QK(Ld>0o0wg}G|BCdQC3WVfOAqz=?WAPgiE5(Cu&roG7xGZqQwv7Q?_)lcC!H@Y=y_7P{TTa zT}Y@Vf)Et!*xqBLuVJr{;|0%~EHU(eje(G0j+?e7%wXSVxPi-`s8@B$VdkSA1tM9; z!PmU->mX?~Ov(wrZixs5w5+G(2v5o$Y>CidlX=mxbE>~G_3iVD$(Bl5!JJiFN5OMB z``}vE{B7Pt%yV+DQonSo>N%rson>BasCFh&9APOzHM&fgc3lT50S0dho>?%)^Ex65 zq!t`Ip}IgQ8^OR8{1{4!d#1c1ylst z0B|5^{0Kw@?}+$CfFLjgL7WJ}Mq!J?qJlf10kIK`Ac!F1Q$QHOC53=d!4J{Uac%_) z3*R#SMM$F46A0X1gAibZ9sxn&TRl>6N%UI|R6>C}>_1HZU1Kf+~WS>xkoBuQjv)80|gLH-D*RSAow5x_sSG8X^HQ&-(wM+|KLoq z?$kg*2rjrJmJFN3EXOcB3!+Ts1Ys|8CV!}2Ls?f?BLBwpFES3Fp5V@DFhAr@EWhBLsyO^xO^6vHa*w_DANm&y7a^d+M5F>DB!pms zAK}~nuM0*5=D7TK@f5fnLXdmgu?X)I1QEQ)Aq@W)H%mxGEQFv%)Z1-lg%I;j0AcK% z&$EQIB)69RMcyX%KV&fx72Jpj>n@xS2*T7mmSQ4ith);R59Ciw1?MA1!@I3sFhAlG z0z#O6N9|9{fPV|Vckw^CDhX8_2`&o4+B-5;l7EEq{{x~Yr6NK^0W5^bBM=OMB4j}S z3Z*CgU!niO4@nV1AK(cf=%LVCE%Ks0fM~28JA|3*F@)4i+2J4X_aw8;& z&?x+$-QYX42Dv`*twmrkLh@Zg5oRG2XpmdpN96wUwmUD$fwyjhMDEH73_|qoou8NF zwD3R*ERqoIPgQQzei zga|%DG58;0cr^c;g8$(2G?egI8XOeFJh-!Yo`&(Safp7r2Nls$-G)*4c6x#Yz_+SJ z5S@5OUPODBl)vTjFW85UiVOk;1BDQMgy>k|yCN3?Aso5m@}avkMgaPM;L7w=@F99s zJYgXq6p;eNlommZqB|C4dSi(!WdYeKBzSEuH^Bhj)aic+k651QtZN z^-rT5a{O=U{0GT&+-ITS2%TR1@Izep~wJ28lp=$!-Le;S61i|U`! zfr9SCk6`;3ea(d^354;8W<#tJ25uAF+lWFC)A%l~2#5@PkQ+#FztV*6b{ItX@75pW zrh=>UpxqkL5cB_m(1R)A!yv@5?6y)NcMS@Lg9xSJ z^x*sR)!(Sx0}sK7X@DrszbBpB76&8Za3}i^47@)I{KIjNkcM+ZDY5RD?)o3@1F^xq zI}|_>dm4;5h9J0aiD-y#Z2%)${k}#2!AZfdp;YivDEeKmLj@3v3v@SruA%q&`A6S9 zbVz^-9w>lzKR=*|PDMxqAxEFgj8f$OtB)KA2;v9-{Ts11`2`X|k^oJ3cP=MP zKu`cEA%XSx3xZeLo}s?uS`A^qS()$D&F3;h`%R+(LEz~Dk#OpX+D zoy)|>_)D04nHhi1yB#!nSpRG|WCr*wmt%Tdl1zN@I#&tLym7uHHh&&orrZ4ZaDSg~eaFjnzs5_-#aaImzR-bVsXgTWa;d-DUW=7j^#pFO)3LTsgsdGvpq!}D zLCPq;VQG_5$jc}oYh+YMgOOAw%UMrW$qu77+yu}IJ6>^D->WI*IJ<0Mqx@wVb^>jk9=F}XieTF`k`;WNx8r@e#SIa9UJPfv)H>3 zupOiz!2&xh-}RG<@_gJjx|$tFG5vI0+iDf^S;m7rht?nPYb9IqmAcV%{oe_tUuA7N zV~};9M!B`~7@)Vxbs&ZLIh;wt-mc60z51aZK%if@Xt3ka`5-D#Jxx%!5(90hT;Y{b zRuNMDlkd#R5>-4$fhkXm3VW>|B^EQNYy`5R^!kP*Y3SfuyWz)GWmvMA*qaW#Wb1jw zWi*Z^<-A?VR_nzR4fVk2F)IKiWqjl|CbSN(l-pGo)GB~mHh)|O{la!1hb^PX=F-0| z`B7(KE?o1`@k1VnW{}CrtIs!lTW_~E-zQ~T9HO25f?nZ?HQo%U-CSn@Dfxp180$%Z4~&ozVdIXH0oyFs zo|{LbCP^ip3&@x5Ll0D=Qge>O+fN3HijNGE}vPF@y`SHBmK zIs2slKt8Ecu}<}AkRn@X$EyVH7UDoEmM{Fw_Kj-iZjojqaPE)Wiej&(<(_qETWDP8 zLM${qh7y;H*9PP*^roZ6o0Fp6_I>n{<;^lm>OsR0b);e`T~$eS3m1~=+0V81IA?e{ z*e3nnoB6s+T%S=*A4iD}Cd;OVAP~ z$l7xu+;Ki?hx-F7I-8sNiH}`HD%>vu>#Kc+3>*x$<4#_BPk#IS<`;><85F)1`lff; ziqd@yT})xuq(RES2pb%i@k4-MxI$KpCG9}YG$rzxs6x}^V^`&&*3Mi=Q*Dc_Rl-Yi zf!aUMT|D?qjGyzCS`ffap(MT^xTQD88Ld1P_fW*9w#P)WPak)Wj?MCKJXUphF)RwlH{OrN`aOcv`8BBf$e%>5Q%D;x$2?2l>!&Yf4Xn8te$zY z2n|=S{zP@)t9)qtV?G%QWzolIdt#_XjjLv)HSx6$ZRTnnlOm!p>aljL(W&M7rBPgl zEU}RC3bKzlwfVDewU{m)Vjn8w6mDOj=~Y#h0SwnoiH}O%hdxot>Cb{hKYNa!Ohdv( zpaZji+S%8)1Rf;0g_8snXsek8FpePO%lAsD^>ySDuO6BSJ%6YeJQJELp4w~Q*2%|= zj<5xfMND>NxIznN6|_z4Kl_40l+d-RD3he-I`Qye(u7xK+xE{|p@+~7+jUpRnO8}` zknSJ%;d6tTw4q`}TjGEfA6XUd-!jC6BN5*19Z@sKCo>L<(#|#`1@pO#lDY-5iu+xd zXKR!fX+<|9ND{7J`6gc2uSK>X8M3d^K(3U*c~i!OQH(k;5XfMR-9Myci&@ToR|QSn z0L715mW=gdudkeqYi8v}aPl9;E04puUhi48+bss6jov!f21`Z|b30Ph!NG z;#+-nVneH8kzMi9ufK4HP?f|T4aXQOl05Td9`fgl=mq)Oy0Cv7wl1a*c@wBon;}(6 zMg+j2D}A&3OLf@WF5s6LN_rhlZ9~qdcq+ra0#dWb9Lgf2o}l7-2f8EWpyy~e*9;Np zQ4y3^@Cf?2FrvMwK+)pK@;m}m{oK=U(aq?U0dP83m=@?uXypZENKzNAc2SCvNbf}2 z$cNlb@S|$$VcFQFmP|J^uxEs9%j0!_hB2R;dc9EdiDK0z#-G_nxDDhNug?WGS)GHk zmslH~ygxvT-l@rppd$LtB#lC)84T?YqElk!Fw@pKfqzrTyG~&yMggSgKT19gV(;4) zo=U-yg?WD4b*rp?o!=_0mE+@OfHJk}-;4WJ>@2@jxO^2 zPJ?c}<^!svbYXht7k2`v((Du&hdtLbQtEXw-gkQkF zEq*OltD>oZ<+vQuY93&5OhX95NK_WSC>W{I0S9A)QF0FgTGG=Bd_|OJ==0A!il;(3 zoF9883)*S|rkuY+l3$E-zGeFj7Yq&P%!)R8#3LS;*^O=zB@O@NRYaY*^p0}AuBbpL zz$^zwS|`!j@{y{q<8rNSBpC;_Q?UrClUym@CzrXb;m5!y8t4`CrpBac0Ee9a#5G7G zhfpSFMf;bI9~^6G_lq;Agr4_<;~XP@P>cNY2PD;9EielO2cwS()o&>$te;JMbRFog zD+YL=ajhr`@Cdvs2TyCKRxF=ybYe}jh~tUF0{GfuA5!xo%ek$Zj$)c@dN5wqWsB2- z*$t-F7oE5kHsu+Jxv^M?OZ=JR6wR#{hR%l?w0V2jiiPM>*_3G3EwaBsz$2k-#m4Uh zvP*DIcnQC2ccobu=c7hR9Qwm#w8@$yP*&(#jx_QX-JJNdzT4(MKW%H#{LX4zm?RJf z+vgI~X0mscw|RKVzv5=7&zZoH(-LI5ILS063{93lo+opWp!JMRkk@A!c)#+XsTCvU z;)^o=dt+!5>Q6B$wvlr}=Mi49+(%{9BaMUBg!U2IEYC$GS~IW;In$jjaXvYBiMqlT z(B3pMkO7ufuJr><0P7$rn zi8D*~YOLa1v$Yl*-|0Bus$hs9ABBO}OvR`0jUSK(;^SX{uhr%1m$d(jHEl3Q5XG+r zjw4U`lsF{^HPCt$nNB}G<6AmOOy@+D4;yjzJar9xhq1ALc{nnT737xoj5tAon&w0t zR%E`sh(SfEmZ!?T#!67frQNnF76x}N-{WciP9^$WUtad-6x>^$4iE-UlIMiI^wVgs zSqeQRqhqpr8%3#3Iq6L5NXabZIw*~u-H+0880K|pWfaZeYhjR!WG;%rn%-VyonM}E z!)?;gFxD0D{_N^Hi);uTp53`wL;Q{3d^nrFwES(FsfR(D8S@Ov(c1T+M2GC0TC9;- z>CLh|K)4YG=$D(s9xli5AgGfoOr^JF}V`k&kN?P9n<5`fR1kuHRnA~e|N^y z2gNt?A#?X;>;C|i;F93Ajz`&o(lHc8;q zryiRdDi0@&os>LgOtqH?Ut@-0k_J5Adh!}M!${8ZK^Sc_3F-q`J!MJXWzRPxJ++5_ z=#v)Zz5e%U4g6^yUzLNRo_=C41%RXKFxM84C_x3_tP07Kbx9lt12}4rC;+N}#A^ru zr}haIAc_Lv0E2osJ1F-|Ii1?nF%8fNeYSie8-oJAc#fkOJ&>ygs2|*TgGg_ zhFBvP6M>u@qg<@UE0d6Dx%d1QI62|%#L>cphbjc7G!p!>G76Vy0UvA1gc+YxQ(z>$ zfZcQuY4jDBOFt#XM2VqTZ>nm06;+gC(c+JC>SCz@BRh}x zDs%~a24gvQ7Dvk=YyC;24|r6iW=S_8^)!dvQ*V1nqS-rYLb_E(^3POrK>B1VmR;8L z!l+Y3%Tz4r_vflHSX6}L#o>Hwt9;dvJ&Z6YKr+%}W9B4FSyFjhLho$)(@uO6di*uH z7{{O0M8X2l_3BFxBmYNLZ@ueJbxnSfoeTwd<91XT|C#asV~&m zO!;Pr_%r!U{Tv5=#lF)nG^NvZLzX07`0XJN(ex$Cg^mHVT&dg;Or;3KJ)TVVC_9ebH z9HQpRvNnF+U4N#a$sD%wIeppZ({Avrdbhl4Lyt*WGc6n(U7UAR1|mJfkf;`;-aLt_ z`ZM44a((e4Dacpf<$+(#+ek+L3$rMaVJWD4w5weO5QL6B@Qi$4ZQT2%2vQOT_FGOg zgNMF*#BvrIC_Ie& zVNUCr9*ucXGcVO9eP4(N(s|PXTZ@XWx?dh!#(u9nj8??rsO4DK)~QiZ=N-?sSXK;- z5qAspOmiurL~Dn5-+N;+zE!oXiq2PXr=qOthslL+1>KF+1TpO!R*GzOnCI7!@5FBxL!7*kheK#8k`m_Ekx!{Iw!=3Tvl166Tzp7r-oI4i2gqE?IJrG* z^o}p<==q)F$17d!ZDvd}0OLz4uojTdq6Sh&l<{7Y>`o-jTGv??y^L9F>J@z|`PHaq zR&rD@i*~c>kMQf8KagETEjd#J`XOn&L9 zcR1B%j8HlKS>3AOBOF!5Br8nR9AYOL;WEvVGR^bAolhT?vS`(3nZ9bhBo$n=q>88i zaGl@SQ#3AK`#k=S&u1gi!}RU=MaN=Yq_cDMF%#FPxpHo*OpBPcV>WHed7 zRg@RFd>=dvl}Oz=(y9+|TlCG2xW<&v_Vq3Qym1y(wwoT*V1vf%4SpfwDV)=m{Uz@3 z>(Dt@1iqj1W}BLX-C`9iBe={X!uL_rL&iGvNJ%f5wwufk?ZdPUF|(QD!TDqzbcLR?miBF9UFz7F&aEvfKeR$dTmtZRp+>U`~R+@ z!YMcFMJ*L^2xvO0uZ6A1sBGJw^T@3k`|Unll(DfUXZlC!5X$V$&caR5b_o5a-#@Ux zHGF!Njxg~$I8g6>&(aZCUf_M0CnBf zrSmythyFW=V-&B4c2!~qtEVh=d;?L*iu9OFoC(q{!M=U@9lWadTKJpqoc+3!W_@huykm3^|2*Nocw>4!Br&X1ii{idRNe!EboxBP=ZPSFuH zaZS;?vC+gXS@&GO^!OTG%Xx_+VepN zO;-%1BSBuD>ZT{((|Pfa_nC_Aeid{NuMlA^Y)yidCT{*o9>!$FTu78-cCQ=A({Nt- z{z5ZUmb5fVTwj@xJ@;jR2H8*ZdP!Cuj=Xi24Lk#~#tVZKt5yfy8ssT&tljw~#d0IM ziq?+Zz-!FXNDqdjN@3m{VNFmfS$x;1vp~t3sj4?sN#e_we}X^#QgoQM2#6&WBNOoI zljsnJT{ViYR;20X=zXVEGgxfsH(*NwkuH{thl4)L4t{&=@>=rcM$%93;IV77IcWpZ zIfs5u!k8b=q6?y&zAmoxp*!@4cz@HAkd@fm*B5R7%=k0!YocjO!kCNMT(omp?duX1 zRd|+7zJG+`O725ryHS^TUAwAkW?5buT17@aLD-SRfO5x#`6T@n^NilF;60lkGJnJ$ zKG);qCD`WH=$&{@Uo>ZzF!;2DYIgq(tyU8bva_;X2Av1Dxiq@p?s}?VztBiR@dr#P z(8JZLKCA-esY9&Cc`B27eJ@(yTwi-=mAVPKzl+KaeOamOd6XCDad5d-{f=7qE5}lv z0BSt!CnLWhdgE77@{l8cS*3(8?&_a+Y;WFo@ho=waa@ZN`^|nd6rXvC?@WRI$)bw9 z{|al`IUiP&R$jwf#QbUyy7!*5C!lc#1!SK%`vQV%+}3R)Gw+;i8Ma=Lb>v3udQ2i1 zeuKJM-vIsJbKKppZa|0|@QIBN0ga@0zg~bM?#P1?4_j{^;vpXHA#UI!ZsaFcNB}qh z|Nm~{3*X+v_Xh|hmPrEQVW|5SE!Dr%2;@}BL)Jd?s68B{H&e?$tEK0?0`gRiwRT=^ z2x)9|;vc|TP^n>rM>l82_&1AbpI~%9ZoDo}TAC}M0IGh-hFq5;d8^7*LfX#BbWf&7 zOX<*0cP4gPMN6`W^Eg_Y^`AQ95-Ya3ndgR;ss@sg1c0 zg%V0nkW)n(knc>60AyTN6BWO`$NVv&GsDn){%hwq*icuQin`Eb2R9cW%1v8-WJWBs zW}kt|RPx$R!-3PH2}a=_M0nzDq}~%8`#fo8*h)2-{%}B%Pu5>*ED5sm`J|oKb{~}T z0s8%`39VcwFWURZk+rqC?mn9_WMU%_Nwfw;9fcT(e*bh@Hw%; zwfWMq*dW<3Q&C3vDYXtcHNPHO;b?SR`5KzF&~Soy?aFU=XIPAm;a4YVKK>9iVbyc= z=R-~(UCiAd2rCWyA}38FnX-0Pqi~R~+j+tR&k*C<&f$1#nh2hv z-5M4HEa8flv%~a78^TnZ=)v*_c_+Q+VM)yFt|kgkgi4&c{XXhNP!d@{Wfe14u>;Ly zTMj?UM)&E-GWo$&mip3*@Snc9>)@O4y|(sJ2^zs{V|OJvv;wPmt4) zx};8L=S_iKBK3~iqBVy47|r+6MxDm-x9mkT!F=zoV~GTMvpb4LA*N|oO0u)NfX4X* zxt9}%4lb}?qVSRTsuR1Xu9K8N2v7W#=ewox9rN;E?dOFM4GQ}v@@7o(t82LgDp&q0 zz&hQ#b$Q0shAyt$(&f~W8nX(^Pj4pGWw4$k$*t;ZYkWs?lqPK(6XfT~{YmY07zP-) zzN#v^a`@=Y{vCWQ%IqP9U#$^B_5GEhvi!vA@5;?d5(Nko`@*JS!ZKiLvw zdVKpbSe2IViEN1Z)GyWNJ)()}(W-JoDSn&dyr9UC zqP`hep{}L%y26n0fP&7@ayA<4)syR zSzJr8llOe^Nqt*{>{&wg&N`^=~|rxaO$a7Gr>P6zU>qSa7Pe}}{_|K#QoiGnKT2|+ z%xavd8#rg8!%mH5v0*R)q+W^gRCX*~g}gKWBZenkn~t`dz8Z&n>D0`WZ)oMM~?Dp%s;@RP5erJ$|I zRNG`b`WI0?&SwOyJcYM@SR0wwRD27wIgbK8CAkLTG4!b+iaL}U3K5+^FtnWo=LLCpuX9MKUeuPzL_sICY&@|`!99FDO2 zse;LtZkHB9UgX~7!Kyb?Sj|UCc&yA&6*p3T3dRT>h?hC4k*I5Hde0a@b5>T z@NL7F^*6-%qQSSf^3vgmE`yTIUB4zt#pJcM^kw+!`c$sb_9y@wSWWh*?6~nM#yak9 z4&xt{tK+;JC)QB+5!0v)54hnD4AuARa@c0qwd&KXka6{9IrL?t9X~k!t4;G~YF?sW zCfoyfjuf&FBX5CZ9`A_m#*iybG=~~Gm(eUY$o~QTrFwt$*WPx3_f7wU>Vr?I@sZJc;MqaK3r-LU zb@3w_r>D!m-}x54tN+m01ho70n!AUcEB1|X#oGs|_L$fkPfeA$*1@q`G!-;XsJVSo zv%zL;Mp#U)ZKCsVmao_atdy{`nUoE1=6w7`_h>MEfa*N)sJnbLGo*ijpzb;?v2=zO z*M?wJi^y;(J=n=hCcR0`xj5zZe*TD5u$NAdGjWOE5vuv}JybkkqH&G+1lLC|zVCB#4lh+arOR{{CmJnqlp0-Bz-GARGy(*SJ?AbT@O3%(E_>ZcO)nt1ly<&LrDs~|)p?4TG zA;Jb#xk#yG(&eK?@!JUvBY!+=jbqKB#;Fo7HO0*$0~}lCigq*R$FQGH?xu%M^`VBz zW1m0q`y#&)pCqaN8iA!c^k`rB2A3$HXy{{uEoT0x0)G2jTYMZ#vgdVQxWjE0{U3)w zYczi)c2DVau8k2aM$ba&-@Rz$8ytFS`f@rN>4vuBPT+Ti;P%%4?VpVKO3-O(QZOw=ptk0e1_#q#3M)V0fU zkVGGRo>HL3wUe^hp|~SL+od57h0^nI{OrBNEM2XBNKpN7>Ss9moA`tH@INlI2B=&K z2k&(Av03$a8+bFh-KA|(ydt$Oy1Xi~1_%u8Q6(uZZP_jq#@m7Dh8=DeE8w;dBAbmu ze6gF3D$mrNUj1=U*&vh9`kCgSmSsSB87UgDmB>Uv1-s}p6na@<*<6`kE`?{=P3L?0 z=NMh?xwqYmY6Wp8X^SBCR8y&RrCHdQvKy2W&W^0a$R_}`e~;w}$^delzi$;Fep(|U za`$VRM0aHX7lI~R8IS}^OD3(i{VB?j6ctlt`pbwcxh}I(HoP|8hw+&24$@QKOkcDvrQL9Kx_8|C_VAb$ z=F^nS#`n1HT)U>{GhXnFQSix`Ap|MbQ*XX=eT;u*u1;nH=GTD%PL7~IrqHTKySb`& zGwLYHU^_3sOPTWxzHho-oLIGweIWIzvbb1hFsvQEc!ht|K35(|Ihc;ArqG;V#QvCA z)ze(8jkNHXAoTcg5;23Ruv9rCD2M<}Iu-Ss&XRW7R>Rb3!hTH8(pgHV0G2($A~pXb z<+LYDUY&tn-6{sK%VhQ^V*D~H11^%-+9H7JQnjv%*It_Cirdr4GwGFI&0~8y1J{_V zm*kQgS1g5&y+Byw)L_=#ktyQu(dl)J-@kYoe0i6uC~SpWI|M|heIW1P#WMO953?(@ zO;OqJD{Zz+stfrBJTq=!OYRlXmRV)h%FOr4ch$-bDr$ZDFqO4^Fp(v{ASG4gv$uOq zXRin^0DR{caE&LqOsfFV*>_z=4*AL0U)*nWs0y9oq^gIiImd%`$FCIY>b*s{(+S}{ zqB@|XK&7WLq;HjXj~>A^!*+m+{k! z9mc*tY0!zC5+4^{QL|PvIT3pP=T2BMK54OVLb|@8w{35Al?4{Z;6=tm`rjb zELN0T1!FW`LrF3Z>51l(J7QFvqWkwC>7O5M0N52)Ml--;VANhA!t8#0FF20Evy98OQn9TVxF_wm#0KdIRftZWwyLPEZP9$^S^{2lg=b`A~ z*~xITND5KNcp^l7Wp!gk^(B(!lv&usYRk`_(r$R*+m70rj(Yb8K9L=7L2b6j-{sWi z6qn}uU^b;{82r;Oj-_+Ok4w}5gmFfpp)duMwNjFO1(4^i$g$Z~AY`k!A6Ej;r6>r} zk@`r|Fa={JxgtsI$M>IbPkJi5hhzZSbwX`I1=jj_2Tuvi$JA06G+s_L|c8e`K(O22S(xZO7)VSpEf1ALtmWQ_$z-;|%9e zxSRlGcb4YB%D>)?#0+ueUa(h>dD+vaCFXbw%uK6B(vAc!ze^>3-IN;3glmsJmO4|} zqYK-2e4mnj%|(E}y1vEuc#uI0g!M-F5X1oCq69xRCSC&4rPF?q*d&}`c-Br#$W)@B ztsU_mTyP%KV=ibaL(rF@KA3iWoC8RugAh+dU+m?GLUUiyZ*5gzXo!11>I7G+^5;G^@ZdwKDk`wM@T3lXgW8 zx|Hp%QTMsrv^^aLKe^5Sely4_d;`|+pf;XG5y+Bh88<2hZdw(-MeOnw_`}-;o#LwcQyKK%f)~Cdo zUA(22OYZh2lSAi8ZPlelJe`n-i(QTXa)U;)^!ZPn8QP0Ft;Z|oG2Z(`uTa*86+VNe zohcuvyb`^vR$6f!@44J7>G2M@UKnd1L-!UQDwG0p*v;?EF<~`YJW+}yGyg1(3nMw= z%mzL84SDa&Vu@c3;hWak#mqKO&?X<5Mb5X#g${4poB7b@(FGqZC19OhvX>k3tCwolJ$5}Tm8(w@var}7WgX=ak)71H60?MLX?_p1M6vCwTxoJkYWJRf zhJ0vF%trkRKIA!!Ufhrxon~mLB8S%(>QvzM_{3yx>XA8{p(3jzx03XahE3MzI~}>i_jZ=f(MA)%aC8&QV){nmJePB!^pboLClveav!U zXvEkXQBvLhVu1E|lE`beY3UFvm?Zk>qskX74&%%#R_`vY#(s`yh>49_l;LtcqM2Hx%&u6S$Ncmla2=!tVx4o_zP=QLEdCLU=9 z`+=Diq@iu}8cL~2$u|ki^WT0-sg*vaKv&Her123Y@@)f##DW$ZjxlEo4`AYsb`&FE zl!=wJ3(@1nQqr7aX+R@^lI}032^~9Ov<|G8GiD)A9zRyGIrNR4{EZ<`^iTHres68| zmrpt7z08dDIC*-XS=7@dd=xgO9?&U|bep&Wb$fn%Uda!b(V%76B1~JSsCmBhBW1TT z$m8@mxfpx*JgFh+WqDgaF(=I9DS(FP60TKJZak!F)K}-9?E4_L4)+nGwevgWfy8pg zw0!$vtyGVl8ZU0sS~sq#N=0yTij|H-v`R~rr50?Z!FQiSQRT(0a7KT+wYo}7n8wCCmVte@CV z@xOpu%h~Bw<-e5b8Gid+v86Z7Qoruojn|=}NR3UDIj%kRl^&GmV9raL#>sBhY&Zv( zT5*i*8BxlF^0xl4>GvAR-zaqiVCn%!iU4o=l-bHv^ftXPG}`=cSsq4?J58 z04+)kI|LQ=QRvt$v13gzt(Skwlz!Lh+cnNOzHIEbdH*6&n}MY$tUUh3{x6*z)_~VC z>(~t;KiO*e&jm-D?Kgag=~zFo*d#O9hxt`P4auw7hP-UdT#Hg-CLrw879p};THD_RPoRIJ zUht1w*G!`3Pqfnh%t1queI;d6l=&@H#k4g~=R}@*?c_x+U_fQwC-s!0kU?Ed6z1HM zPWwU|kFU8>yJ+*zHy9RwI6?4pd&Y`hWXLR26}_---cF^HmNjQ!LxR{xVb_Y&;*vSO zO9(HS`de~Y{2v_*r3WinV!8E!A+mdRE-Ufl^TL6_2_KSCK3T3qKIzX0O=QE2I` zS<5ahc+B>BI-4WRHESz9ymX*6U7Yel!Y#|sYuW{!`CUcVs&}59ZgYPTBT9@#qmg*~ z44Jjph>^xheuN#Cj`wrCf5q>@n{LJKDP~89jPd!C-h$l|3YAHgWe^$b1Ko;Y5`1v` zMc>*{A&x?afm|xwLrjAxb3AEk@z7G~16vY0JwBG@Qsw@lG8LdnmnzD!4!{yabBmOs$&w7F%3}BX z*41Gd)rq)uzL`f^5SmQ6nTWE>Wm1M3?|IGL@}q^n9yVtF=RqjSK%_8+0$wJz(3Qa6 z24tEDput6CvN*#R5+3)aaZ#ayp%C)`sgM#Ip;RvUtCQvBg>tZzalFRsm%oBYewXU+ z;7qnuXkR?f5R>h(IB+$Z6MKX)au_}kD%sPyFqu1EZ*Zk;lJTmb{muFg3`sGeD);Y0 zr^Hl!K=|FOKH&Se%fRq#I`-Qax*hJ`C_=o8&nuAFZUE5#_e<^F3nRGyuNOw{zt+|p z0>ohstKCP2#-JfU!u};vFcOvJnl(E1DvFC8fiR%y0tWP_XZ{p1{#dc9hNsv%Pw`a4 z&{LayE3B?n?fbQwzQ@HZEF-}CnCErn@Zlc48VvFMwYAiJ1UyGADG4f#Z%sG4S}+c1 z>f&2yk+?o&s`tCj+zHdNq$*+jrME2q+IUW3 zP9+x7e|>W`^`~^WyMCtn;&M~=)l@E}o{)2gIhqm50-z|h#Lm#h=8qUXfnQ#(MS`07w=#a!9jIp%o?LGn&L5vYoUi$vd~h|1 zE3IVVdVPG-`3Z%t(a#xD^j(qHc<$@|JGC@Q=ZoXBetJv>UFkZ8P}{TKdB-y~3~6Tf zOwm8<`|v`<^L({LzMFvGSC-;9@ERC>_(l(-crFl?VgT!gr3`#Mz<=mjvoQ1^T;E#q z$rjo5wnWn9Q$m72wRPQsTQj+D&b-?~Yfk2CFUpQt0>Z7e{dAg`14SQ=J(xPQYvD7* zpM2UZx5{ARt15;pXbCone`}|~Bc-S$< zcccdiNTf(Go1>=%rTxE_A&OtVpqmjt$rHONi`6?@8IVPf`vf^zCF5^{>vUk@BV8DP zl>FYTCcvKfNAHrL2Rd7XE4QL+*@Wvk#*=zyQb4@1uO_44{dseG8QIvyvG*v^7Mzv0 zP_a?1)ngNf4Uy?@n;3mg+)4Zd*7=7K{JU|xmROfs#P}_I&!HdhOfxkiT+!f(m5og4 zT3HniM{4;OW``8edK(2`n=>H46o32Dv$e4GPs)D1fNJ}|W3i9DB!kQtWEL&;RI^vU zs^FF9mXF%1J~t_xg}t1t+tw%ey0Rv5nsIivIuEZ2kW}bV+Ge2rP<=yM1A8rdadYyc zPSDAxw=JgOy8IhHIq1nJ8?qvY^Z|@g;?aJ$vZ7snCTDg0Q61m%h=8ZbS)GP#8r4kZ zqc|B|)GSfZV9Hs8n8vpG$FDg@4EUFV^$K#|AC2;I4AX^$KYNw;4UK3`I%Vnd=fC04bR0IUZeC(aHLQWGCn{ z^OwP;AP)>CM%Esw&1H>o1?Ni+6FA2g-nf@05no7a3A{cC4-@h~`Zy#5kNT*rJ{?lb z@Vv^#io)M7#gdO8&(xO8Kn6RJ){Ur+W!W38d=gl^81{(i(FrQI{mWEXw9H#@4g4V_ zxSy<@CCuO^iRTJJvHZ)9)WtOK5!>4#m;y$xASUR;9)f*R~87!j*P=1^c~}p&$#Xbh3>R z1@^MK0Wk*4!GwcNM;=surdj&AFU81Ky_L=yQ|U)6Q6eXodjP}e2^vM^{x}mMi><7h zsM9Pu@e%n**=W1oHYQo)0CB4!0+YI+P|^Yomc8AA-Ztf)C)O08){UiQOY;Ob=hC*` zvPf$9Dw1!^-pNoBEU3VAUI8-J)RRXfJAk@i&(E)L^l@FlJ97NX+9^%=B$Ge0A`7`g zWXWa^lq#|A0sWDL2dWcbn5*j7<(t4B%DpThfR7?Q^2wZgM=4Tu5_{l}dYiuPJ&c!u zDBf>dVf= zft(&#{Q@q9W02QraTM{Te`$L^zJ5y90<0xFo(x8LmPI>kwFp2udXqtj!NmLtD?`Zp zE%W>1+VJr562ReSn>0WJhn>!&B5-bN3@((wbXYY8eI>V@Iq}R!QBx8P>+!a{=CgpF z#W8-0<&CM+4VV^x(i9$MErs3k7*@9l*9N_gs;@Ned@ea0P-$M)Rzu06&q%?@P`eWLV=ov$@F zv?L&6C`~hNOgCJFsM+zcSe>)IdP~d?*Br8Z^Ov&t=f7d?UrASSyL~yj0WzUGR2H0B z3p5@^g_S3?4(KKRn|hra5wRl)f?egU3w$50142onsu+iRKL$IisCL`pAEOo8_t01g zNA=B`XU4?y7tE!%N?+3rL*JI;)3-l~7s)}6* zD}{d>EQ7MR)V){+nvM$Lo+k&hQtl+e|uW``4`nIE8U zJn^zrdFv3hr{i<5;4f&pWDM%(g14cC4D|ynW?oFiLt)-#yFebTpP_Qni{GA~zuhk! z0~;sY=foxXZ!VT4BYx|6W%2{R*Lp<%vDIa9Kt|wCe|g4)qz6U!iboBAhG+Jc<1#Fc zxK2NVqo7}go{2rt`8ptTS{yY(R-cx;$lA$idm4wbjEV7?rw;8zt{{$bh)&<)rv?R> zO$%KGfwm&cfblYIxb2$t8qtT7&IYIosR65ws2p|Dz}c$q#pxL-9|vLg5=F!`t6`sc z{sWeOJn#Di1v&c|JupNWSrZToRm}sne${dP6NB1EGNI!0FdG<~rO(6E&B&X|=rS6B zkI1BCN-+({A5@?mEV{XK&M+dXqoD#6%LEckkTWHszHb%q(td;`)*1Yrp$TtF6N25Y zIa2;O14iX~n8nx1?!&<9eLo>rJT{@O?7BMLq)5~;C%;*hV(i4xeS2M_X1dq&DVx_W z^BZ9XF@|+BW20IF#H9#6<0=VTs=m@+bJvRO`a-;8XQ{lwX&}C8As}K0@Gt{ZbRn1s zDkIKJIpuIE3wdJsNq)Kc>M@H)Id}bdKLMB`g4pjT8^Gt6@nw+CHB@PsK${e7DJ^x5 zdpdZ!SHN&)c6%SBh07sMEVI<+j&!Io1kCuq51D6?%D8r=QS!D5Zm^WOTxe5&n`<#; zHFOj(u2K^OLGjDUx8T`l8%_d-E)d9K%tNyu(1Uo+SR_Ram_X;3!dVvZT8Hh(XK|8f zzGNw8YovdZhe&+z5_aWg@1JIATUJ>y>$AF$5fJUgnlicP&kRvH#)&eS(rS~G2vb&P zZ_lgnjDr|@lSK^L`t|sP9>=G3ENK3H%3SNzO?Cv@tljLw;x}fWkBSAjQBXLHDmje| zblNPP3%o&aK#)1|bV_;RH2JG48GQ!8P4U=2N%Z!pb2Ylp`^!o4Su0KY*isKv3Y4VZ zS&>p1juFumkS$$V*2GQ9f)>Bc@Luc@{yEdboT>jYx!6#XstUwU?~z-*hyQZHfl9IkcSa%bZ`}uo zu()%g4?19-JtRB05(+Zu>=@`_Pd@80|INo=zqHhZp?Cfk(~~~VGeVkY>XF6XnG2z8 zun-g)y6XyAlx&@N?4KmgUbma*;FdTo^Q9ZlFCJ1ng7KmIUMm6kP-lh&Hm6sjpU2|d zKcCeq3uka-LB6UA(;_lE%2%wj=^6s1u8xwp))M}?-GB0WQiJa^gXk7VI&?;xh8)fM z-9&yG;Wb^uc=PU10=IUsLituzkt1wJa4B~)KvhiaPn+RN+0ZJN2zObYll`{-aRr+&;e7`ydgNP93F0mq;%Z z)*{i}Qoo+Z;}ibn{QO`NeUZ0Z9juY=7F}jsev(Px8EqGS_XqBfvTDzaUYSj2eAdpy zE5WAD4%aJpY|mE{ua-PGt!gwAEOqj-S_`4D!T8VMX9);E%6j&lno{wUOj?9)nS0DT zSZl8l+osCbWzbGU|8}jsVUR+8S{!0Xl%i3%vH@Nj3hV}#_eufTV*FP_M1KXi;Rj}w zhfgP*IHXJ8l*k`5^P}E<-x>qkOJU6qT`O1-Vnzb)sbe1mXL*CcVCK#w6b~X2s4BuZ zwb;=Np0#!Wmjzae`^8peKd$@utf*vv?CaL--}g3#S5A%@5w(p^53Bt)$9ROF*@RYT zkilY1r|T{2Q*y^+f+={a%B;CfUwL<1$!(w2R?WyKZioA?6M`{0smbv4O!;m}S{q@bwUHqj{bxIGz*+=X1F>gJh5V z4w5{@z}S-7!Vs(T{W1o;iiuTc*t`Bd!L>IZCvKZ;Q!i= z<>ZwD1nR3UyT>+mpD0GHZZ*TLs~|{SuV&^ZPh{f6~5`h9m7to!bBoS>Rwmx!%WL16RE` z)a(-lgnO3=J!|7+BYebmD_!9zrXM79IUy)8gyGe&$0pB4G$`F9*?$HcRgpU{_a08i zAvd5f{PtU1-{)jll*>DyczFRVOmoVnh1de8A^g`M=EoZB$8F=sA?LpYQ)RpVUxFzU z(|;QPWcELEZLTy$d*BR!x*2%luL~+Fqot)<9|l;I(M3NxNnzmW>}EO>U8oN~J2hLB25UP9 zvHk9r<|A0xd$KZ2{n%D{vetu|P9|P2Y2ZBUCvB-uuE(~bWUf!+cTF3|m5dP)I!H7{99gVKw zSu#G*NsDLo0|#hzP{$#?1TDN>3P=pNXyE>XVR5C1lbE`Kn6+;A*WrNn!5)8WoLJyz zThkmSg)U%z5WYpx&J72o@j4VKxX2yPK}fr|{w&ovasO6;vT%?9w%00(aS4JT>wKNh z5@@m_4Gq$HOeQnlX+hmQAp$)Lt8F}>dG z>TQPrj-x98`RM@Q^L~ot(BXQN-v>riM(LD)ydH2e}3_T4- zD#D)kW9l7`c3ihb>I z9cLK_!h@LB$xY$hnOjCt&#&G9Y|_GcZWTB_ix)7DJ<{$PtVSn| zMl&x>a2`XVk_QA?;5cZd9(rm(o(7l)czO+uO(s$wwwj(Xs#tNlm2*aGW6P7AwHbcT|7s8zblD^1!+y*Elg~t%Y!s~EhxSn zClzt1-Hs`HCYl$FgVa_WZ>fLZR3nRxVtx+q8b;4SL@B=uCdm}O(QQoOcUgle3fmbb zCOd`%pl_Gk0QZ*(Q(h-F;&A12{$`l3!l4IXmaihp2fm!><2&>FFyBEe6E0mWwJ`CL zZGKA1GTzZ0J0jAgP%P}b6-|g z+6!!KM6y7))Cmmy88W(dv&{`1%^#z9PyERj^esI2ZCkXh7;;j)D7I4vmu`*GRZSM0 z!17Tc*mqm@Gv)Cz`ISKX?5XQk5M z)g1*J*IL4Q2JV;zRuoBJGTcWUzQ_o85iii{KNdV*TpPmLLE^LI148r({hO;8JCdSL zK+jt9MYrue6T^17*|qql?|hTHURO#^1};Im9;@YWpi~h3aaa71JoY$h=6GxY0%vJR zq2%7%&)w%&2TSGv+~ICy2Ycl(L$iUWi{0QEoTk540DFlU$}!O|Q6>lPVw(r(kKf&u z_V-TQ5kPx67Utb7H+>Sr0c?(R!QYI7*72-5U)dnzqGG3m|A`Ap@-p&~oYTdMy~%yl z5^ph@8n?eWA|wj#$A!TQBd^uBR|$F^56AfUQ_RR=+SV@FQ?_@9X05lEJNV=yY(6h#( z^WmV8kzt7W1cx77$buc7|R(Ac&jsYlkB$>U-A*~!NV6O0 ztIcB?M_Syo<)u6CAMfi`eqO6di=cHt6?gLO|w!zws9J=RwnUcHY986 z*_uESfg~_I;5M!o*)tHCFBRz=haAh5(kK~m zw@QrvxNe15aFIY)MOlIU@}X$$*d}gJGGa!Zs!K}=CoX(U_N>)sp?@@7R)MJ+GOPQ` z8iVV$SQYZYX|+Ufege1g`{gRA1xAqGH(;IV=Lx8Q&OAg!MSmJf;suQkI(amq!F1Z- zX+>s1u%?I)%TF}1M{uw*kbA*VM@k^|F$y)iNS0zy!sN_9xMvh?y1Ho_P*kHd{qW4N zrY80kI%sB2FiKCL7=C7pYh%6t40aOW5cApV8>u>tgVBnAvJLn!Zuw%;fBUA zm1PDX7iSuh_`N(WFt&mx;cflq6*rRMT4##vx@YsIu|J~2aUur81u@;(M3Go;d#f)>?K^#~>y%w1SSn%h-M2&fAiFp(f2 zImlDd_j0ROUI_yv{rM9}H&pr(#}733NNsue5x$MR{7HVrp>KO@_ScH9>{N;hTKBMWAFN0~VeM zvL#+Qft&f9#s@aVLe-}PX&t!e_8y$w(Kz%vIz+Ef@Nvv4L_?z~SR;vYAX~=hc6jEl zM*d~xl&9n~P6&TSxN9hXAv@|`l+P6cx(_8gEn!pVp7kVag#TOxJs8|4$HqqPLCe#` z-7U-?XePWL43XyHjsm%{(Z765p%Udf?(p5SeVuj}UGgO{-eimoC(ikc2g^S@!Qw*N zlVC)hZ!w8-T71QsstL0RK<4x7N%Ph_wh1J743Kf9)WH)Aw_%wG zPEflDLTQ>cCFB7&*8h*biu63$YR=Hk|jTgIHHN zlaNV?9W44Jsk2hf%8nIzI6ISw6u<7@to*$F1&W){4vG9JWOV}ygCXCaT}B9YS6<ozu;#+dNv&?v>dRd;B4~!rU9?Y)`@F|n2MfdzD~=%1mBTT* z>(VzFd?273oHedwmNvbLz7Y~1%kI;50l>j1O#fq!&iZ4l{$p>+!uX$6nw>we&i|WZ zU>*QG07$ifC^F<9Yl0Ecm;X+E&D;;FkVN!OP>O(c-<(gUnWyb3Zu5EUS2oN{$QcZY zAWiulO{%UTZ^e&``ZL=nP3nneRbPd-ofIR|M5E#cU{F?<#RlHaI*zX?aB;9+FJ!I2 zSW6@*i(^}qQm_&Hij14|nwQ|>`_Bd7rkvw|DlcxBe&LDoJh!r}oa2W!CIQjnx>$6N zr^Wz3Zl#x_vd~_KycpEQIYv3^O!WwgE$Z^(JR6tGcOqUTCHaT9Q_)2)YsmmjdF<0N zlBS;m2%8Y|5`uW}hK2E++`LC>f^^^qL`mP5-{1El8Jp=YJ6_3OZ&csW|NbQ_rH%kp z#@ES+ZhEeJ-9XOLYUFo%5~8f*YGNylU`LNCg4~GdcO+kijxKf>0Hh+!FL51!OhiXn z%k!L&kC*4ti50+a-#4#PiTq4r=&+fBPnkJdUQ_C*gWN6g-yv{sdn$%o6l~@~VtqwU zzhjISVQC6?`LDncA`!cU+^7P%rp*A6yCNwiFKd=tC`!od{HE85=2l@7&09q=T8MHy zDmRJgINT{3Fo{D)BKD&G=}uj9?zg!@!{m-7d4cE6IAx2MC014kZSpe=WLxeT@guI# zh9hqSJpZPw6-#DN#*vTSj(N~VhKuq=e2kLM0D897}2{fqrs?V-bV z5GMh$oPKn!K<&V`k9aTHOG{I@*<>H_OrKTM`u<;Q5p!UcwS4QzpRs_YiB~w`U!gNB zM&%}Na)C{M$B}r#OekTsn3s?muXE0<^OS?7Ef4ArAl_xLhI8V^C4kb_w{j zHG^*$`a>4j!1&)9a~+u~@MXd@)4$yjyG&agBZ_LQ)V-a)#uwn3$zZv;iu09Yk7rq5 zyeB(#KFvQRaJm2G1?)Zr3Gnw(%F_cpxz+b~|EVLZ>xPhFNOdPy4`f=tbuVE_mSO|_ z#!Cjm=L^r6Zv*TpfAjnP)heja_uxM~KOm+M@7Bv5yBsk|oi?{cE*;NM_&ch(=g^>b zJH3>#D_qO!;DumY@1$IqeA?OL_au5b=sZ+no8%a}QkI;EmC|aVSS~O8jG{OezMx2j z!6j5&82~1NMjg;dq@Bd6dL1q+YL_E(*wp%%-%xg15&#HNkXO`X%;0gfs!odL>Fg_~ zWiApVi0_flEhpZ-^MNZ>NFaH=#V%$3pn{$csg&K9;X;vPb26(8ATogXCa`5PJqLDm z#)IZJ=Q{|-%CE{%Z7N{e1^-;Q%}KMv@zIdW)I5@#kwW3JZ7CLp%>EuK`6S@`yYjwW zLSB9Q6$jAF;ddc7Yz!x{E^X7wsm9ydpb|BRq;68QrM!FMxQvXkI5)v~3yF@6UMnkF zY^%tS8*xFZ*!^{erus|j0TP4?s$783C0V)gIM}g;tc!?jPnD2)cU`!VbS+cu3sLe0 z*9B3IjpId?EC-2u8P!X*$+1$r`;dGy9r+lKE(Guw*3?GTsgh%2vU;u3B(lSC9f}H( zC`p+q-n34i!bAHs<}%W9s2V+l=Jlv(ZcLeh=ueQDnT;Z9+A2=T90$53P3Mducb_4s z^_r`RQqr&B=Qq{U-b_SuX}Jxz(le#(D{iA#FtgWs`T3hjow2EF@n^%FsDA;~v?ctd zqvU|f#vf&>&LZM>PXM#pZ*l@NRr!XH3p}qiUIL+KSMeV;zY+CM7fO0a@mIU&$js$S~w z?Uv6Z*I_!}x%cN#EZL2G+lnJsT4{UVbrS&P5FQ$h^wgX{PnqTo0CR4rKQcV1E5dE}~hCl6}Zpo`=CgH|{l-yPrlZxr3Md>dUNJv$R5@gAF zIU|o73<&T9p3k|~Jbxm*UysyzmWGK3V--Mq zEq@Wy7lXVy{&mG}pomDZjq#v`AoZp1&|`IdI1L_1u4Dis2b6y=G&j@)|B_VCZ#?s7 zIo3u?xKX4Fk|@X`;6_}y^E!<7-^|5(h3E;*fK^l zzkA~se%exnG9wMPCcE{8biCuRDaX~Zb|-ee`wG?yZSp0jX1&6DPRO{lUhStUfrMNb z&4Xg?JCuzpDpKn5K2rd%_&xp<&*WQshnsl_B&zsHq;abKau-U>w}c+{YB=CyTHc!B z&)tgGpU0Zt*H&4Mcx59Y>v)gg1Zg7rOb97e-JHikx%@!`x)+kNmUAxVVTjXw9LrFZ z!pXxfHD9_)klfRYG`}#YBq__gfxAoN1e)5*n-f;9R~>zM5%=+-&FB(CE$IQ;}i5^k&UVS}ZX|FRRd<>;$lqs$aGn6RY(6<0!bbOP6DA~ql zh0EuW66!FD32vYF^xt|?O&qyEbR9=JqPK4^Xa-)m!u`5y)>2XBZf|xcFR=(ZgMC=98gQ6CYk4r<0W11}W_HqB30L|N-7L}d@%HlW~zUP%0Cu(EsQh$(f zYg`*le(aimk;(ZGUXmueekJPvhC9HnwihnB7qY@E?%y#;yG0qS-E>=>wIoqOx+OVn zzLvT1IhJ)Ri&eF4&p7LPzP7#RX$Q~F>&R(ZMpMr%kns0w=-CBuzr1Ej(%7h)+mCR; zUl?7iy)@>=xZ*Oc&dj5bs2-EYF_B#VUad1Rec{4?M|TZfa8mI5m-6=SpLmG~-V2|j z_eW1x7HdbbD6LlcM^AjmEZ-V3r-ichblf_T`cpTGyW3Vt|ynTDCpd!pu zzH}>g|MYyKUREQ=r)X>!=u+)u@k8wfn zL<$}!IpLV3=b1J4hFCVjVI!e6R44V=qZwQ3!g8uK2u26cBSo6>7S5`#B`=IQMp_yu zk>3epi8FC70fhlyGtIii$iVeLEsOGEm;JcQ2y1a9NWfiLqZ4HA&!Lh7LbZ^GMahdt zF_mm99G3y4-o?@Y3p_nk|#@rV9hZKMkf^rMo6VVBM8k#m2>1! z(!wwURdH7GJDhI2b&X)8N{!xcQ59t92t$wQTS@&s9ZY8J@lEk zYg@@RyT5TBed%;j*{80vqkBPDFO7t;wrcB!yA;q~3OUKW3)@53_LVkeKS{$r6EzSp z4JZLh$TlI$!ZM+ivLMVk=B$R&#Y zv%s3x`2@I`)92+vAip47fpj1wiI7wf?~_XxRFDW8_OGB!I>-+l|;6V084Pj-q%>F z6(?I*(auU-FB#&1qX)>W*a4fdB)Pl0zM?E}xC`giNPO{uu>&Ly<=q0tFmF{1yy*}x zfQoNaAIZdRGi|Ktn=WveXJHMsW2HLSusou4>y!pS1;P4@ces_&sXBdhocq1BXm zi$;ut#e8mawr1Ilo-IEng4<|Ert2rGp(}iAz>g+~j$i9ng`>01caXxh@C;y>J{IY7 zw|79k1-F-3rgaI{x)$UXl!`r`WxlN^%vp_K#N?HQ z>4z+LDY%ZshD%*MUe)gaMa^gYZKn1*BS;y-iM}1@LCV)7t1U16hl%iW{TVQ6gWC;L zlP6g{8#!_X`(UOviuJiR#}B|QRB+P9smH5vB9f)U_iZOs$jKIC?OXH>-2h~uM-LI- zYh~2N!$SSa=JE%H`2yC9Q`QBj01t2>Xns1rpV}u2{Dr-_624yWs;tsOHDqDT_n-6% z0zQbtLi`XK{u6$6bjHxAZyd-w*!T==yz#vXelJh-O>~C^^JK(+IZ(`i$~Pq^^E=XSbFrN zFQ2QA01rp2|1=8q#}aQfabsAfRuo1EgS_bv03l2#kEy;GiNl;0q|*P9bha+Fpxlsf z4Ti7WvUP!Pi8T>Qnhtbod3E+VOi=gTdt&q_8r?q@#wFz2U+UA94KsOe* znBX>hCSf~}ef?#?XNiy%8wytlKB?Gz+lXodm+@%+@iKv8+Aj$r)$8k9r=cp6Dt_ssR=Ehxi^NvJWyw* z-;E5!*r*H63}d4h%=gbD+!4ZLv{hFFfVQHvs7w$Qp{(CTr8CBoQ1XFww#^XDC=xJX^BmXVYZ!$MwzD;~|LQUBK+ zKSU^}h2BsmF~Pq!Q*Q&>gXU6HUSts!?)da+uQVvNEmawgtPiQFw0-T@H?lv3OJ_70 zw>9@0qYh)()1v+GXJ2we?Yg=HV7m$F;@Zan(#`l7xf>>DbEB6@+@xI->Xb!85IVR8Kxb9u)i>cS zXoaywRan|iLlDz}4?ka$kfWlj`l>AM-kN5VY7#zgx_8)taqcHe@%LO8kA|sL zU_?iSl*IQ;1e-hfb?jq;tu~<91p+efRUD}0U15N9dqktSDA7;jlK?>+B)(=fWj5r} zhAn8WwkLINBGQL@7E9~`$WSbCY05&Pd;L;0Zjt0M-ViWRb6-V*gEX9#O06(zA_n^F z8pRx47mR=xq;lw4yOORle)_S%%~SaX?s_yIF7`A%FR*vtyb7Pqa%kqmn)bSAuuFKV z-^ybQS`|?Qa{chakArTCh{G^U`0FRrGCJ<<%S>#e-ArWcoWBJNpi0za=Q4yPngm)p z1X8olJ66f6TDBsRO-cQrfKfyLCwHu~5>+D-r?|YuFGL}*4Ak12Qut0&;D@%Qt6*dc z{cC+wfBcj$vKf9DvcV0ua2{9Za>cTAS7g#E@s4}ypg}DO$nt3*z!6Hs%fQIOFR`}T z3~kvx zgf2V^_=<^KOB!C4Aeq72cS4+c=V|bGnkK3i6_o;oMLGHe%*~;q;AB>aV@y}DjHQC< zh#<4Qfz8k9*z;A{wmXATn-W?kA`s$@xh^Nv8k!_Vq>PW1MesGDnt+9%A|Uu6q89y) zBQ<8q#`j;obD&qbjx4`-9f6G0^CQ%3-^9(eP`k6a2yzGm$*5A9)){&CeN)0zfei}F zi)aB?X3d%eki8ReR<>~mgQBWjc7Vp1B^om^<^FtCX!?Nq*4YfDCbQaSO3PaJnWVY9 zFXJxDXysz!3WXJIgz!P)pqapC@Mug9d)v9Op!6As15o4$*85XDn3kp;YIfJ09adNA z{KP*E%oC1$vd!`nwsdm1IYx~c`d#tyCKly=@%L%~6Q|RIS^2!7CN7)fUl*Q}5Mk%% zB@HRY&gVw!AI@H2rlaBzo!E-p0@ZR(&t|>0z|xxL`Z#Fxi6}8?NJVV_Y3dphA!Muty#=4L)*bZ4(WoYcMj! zM>+F%AeJE6nUfZJ=GB#y-;M6=Gyr=gv@=8&YJ@B)L?yNMpj7{eIHmWzO?F!_u_$4m zCaKLgh9^&l^x|QIvi{*%DA`!bJg<$@jhX5Kz>$@?V0JB=Ti~lKf1dZrsb}IeQHVf& z_7kZIrfhS4A*J#Nu#P;QDFAH4#?*+9uS5h7D|`qQ%RsE8QCGi>reu6Y6rwSHs=tGf zS)qMX1R}Z;DKDBkj?Ot{JmXBEi$*UpAQU}FSnRH^)*s6VSd2phbIAy4BH~Ts=NKRY z{1ww9L=+EA0Yx!@o9o3yMW7Fn=VZ_PuwW;*PT~kGrDhYgS|sK}XP)TQ_AaS zD`Xtf)N9ZxQYOA+90n!unTI;7Y;F~%TiH$ymfg(L)RM+(ey0I)lpMM;=p#Qg@&5A(urZUDD=Vs z_(zl8EfD(a=^+87V8+8nK2A_-gj$Xu_CU`q3E<_wf*BbanvB5!{o#fhfwX{}24z2G z#fvb~55b|5G7HuXtR^TfQ4;`p^c-I238+u0n7f{%QlQit`Q9Sb9o?Hy%bMuRlTUuq ziO@X11Ae%Zz1-gyvt%fGPO3tYUgWr+(euCSxbs*F zuncd-skh-?{Czg5zPO^!3Sz#kq?~Ug*IN#$zNUyokglvD0I$wm5ME5idN>wy_Y`F^f#`}1 zB>||jb2C@-v}B>y^eKRB`aA?ew54dEKgKl2Mcs=@YTn$nD_KIPM}@4XhuVsunR*(Y zhp=^r2#(*&0fnPwDh2te-F&wML6;sB)0Y}`kISU6u;kyLs8p^$X)Ied8Es#~T)eZ~ zmuhbk#=arYUYC4@YtZJQiwtRR$Ib`GJKF(VP4?Yxr7=%!oxcGk8=}reLw&I$q@?h?(OhhMIwcGAA~0n5*7=SL+x91dZg|9f=>N18+n=4+m__?%*W z6-}Hp&*Es75V(>7s7q)5XEOcir20qbuZQMxF37CsQKGaSg@)_e2@(@A>`iKZ=$nch z+{d`=o)qBv>m%0sI{VQ(7GE&AXv_-oP&5dI0o5eySHfN|40GxlM23o-!Rvp{HQ}_S zaJ)|m#GQ;+PIFJ=I@%*E^875v3c%;bQ@7m}h5C3H1e#HDuqY`$UO zWu+ArVX5S@ld3+urHcs5ol6qPwA*1RoNIsnfMT%tB%s}L2ugF!{lCF=^*rESKn!U_ z-hf{s)seqe-j$w7?&0rr3cfDh&)aD9Nj1ZNV@F3Pkex)qscAI`TC};O;x3+VFZb#u z_y&GtLNXaWs6~57q{kYoGPABmEI?L&pVY6FL2CdmHF>H61gXv2QI$M=OxD zw^B^0LTgyBrBd!8RT4%)2pjaT0PV#{uHj%i2fMJBfjKlq+Vb^kVi@?+E4VLPAJfnP zn?GRQZWyOht-XN}6-frOhj8Dk^4Aj+ROAX$u=HSHa@$v$5_WAFLx1pkQvSK}n&zC? z>5Axu^1Hz+;J^Q9N9`_#`dgk*JZjVo!^vt;F!sfEcXG~Wv5hdoYrrs}0R#hkrr`AY zyU@E5gif6`fd z!T#&5AeonIFvKVEICiZzfRV@ zm*JsrzJOR`+-OzY!ZO58C46as$*i1bZd4D4CTSZQv6{{3Xf>?9!u4wD?I_b!M4pgd zX`OnEKUAoCs00d^M#e0$ySwihyZGe(_*(q|6%%^a*N8w4jLvN%U_-0y?FMPZLREw* z8;Og#^XG*MpYe$VwN^`aJ+LR|J*Vq|!1LptZF6rVAKA2*D6@AGHKzWxPvQ}Fp%l9-uc&bOq8dBEsIe9L~?6}dow(8l~xi2<+7t})7jE&b^{|F}6G$4KfOs`~+8aDdcRPV_6vkSJY zAZ!D91-5~bVG$oR+S`@B;&wSvC+||E;+xzE>)qmQ&?Cm|D4Nvj<0nb~At>#-krIVJ zAPM*3uSv_HeAOdg2gyp32gjFlLQ23tIz`fGz&A5vN5 z+Mt<0&!P-G6>N!cT!gV4OR-HyZ#La zU~NgC!PEqsOn`94+`AFK@q9muQjL6`&P*bVB9@Oe*TnZQql~0pkWOZz8;hZE6cDEz zTqx24UCQ2%<#ZTD&Wci(OwB(-ihEQCc^DQzZu!KPKz3on|5lfmvED&8pw3jMx_6RQC2lN=f;Qul&7Eb zl{9}YjRkX?5jW%QxrM;gYOvG1)RU$OTdL1VH4h;lsKEWnxSYAw@wrny2GO}kbZhor zN`Q5t?LoD2s=nCji~Lr{BLG+5)2~@oRF~zRo(j58K&%y3ejr7B zWfdG9?vda4vbbXW`Um|%FKosv$vVSPR`q>+h#ih%G?fze7If)u_n;9_&1WLCmbkxX zEB)N_^0Fxls3a@wn_22Hh>d>3DwT*qtbfV_oh@3Hl=D;>H4ZQ?y4uyJqcse&QqPyF z$JYGW`%f33-D_VPd5a7OKqsU}sP`RF{BPHr9Fd%HkLLpBgiiGKD)3qz{JO?1!!Ka; zD_QBQSDP=UBKME_9!Io795WKVbh$lM_KNmdr&zfMW7jg7H%e)Gg3;nP)tbNJ+ zBli#_JoRGhmdNhp3jz~xnZ~^^ZH}ie-2M1*b_~c;VNj`2k+pa=z_S9xRbVs~Mz~Uh zi0YnG$vV{lD4!u^hLp-}ZWNuDF$Sw3s!xm#wIY4nmC>g14BPA@#qtV9MD#S}s8$rS z5+sEKA5K1+`+-nqKl_&%WQAcbYh+_{m_vqX-IoR#RHi7KdI`c>72ou&ot*XR#w>llYEy? zZc0f_DNHJxzCM!xm9M>&C5b}q$TYW|oM|M>YimSHEIAhnDEh*!tM|R1VVN_=%r)YQ zEVhQUiR*()#p6)M9mV8Ggfn(%JlgADolb-oM6M`Q9BpcQtBse0N}(Lo3VQdki%uek z?UbQn{>aZLLWn8%*=VxZUDNapdAzLjV<#o_M}C()ybU%M^k40nB}|Ve~GD>bAvD8oo9Foz4g_5 z!en5>4wU{@kZ{S1pJxPAy^CgmBO~BIslmq@4>mf_iosNsB=krkRD%Qz;bBJ(lkzaT)}#Y{+>;D_Mkek> z?(n)uP2u5pK7aEbAe>y{uioasWc9TPh0Npvc(BGZ@lA4LQ8Upptwg4__HhzT7>m5h zFQJz9%Wi1@W~ZSMq*7WZD{bDj-no!okkx@mHz|=d5A=Ub)pES@7kkuhmzYHG=?#)I zRYz){T7p7K-4W?O$DBTZor-BN3!>uiW#aiL)O2F;{=Lpjf=)|#A|Mh$6M=X&;3e*p zqTxo|Z~TA_bNc9UDpvg34u7BGY5QMvy>oOW!Mpbx+qONi?a9QpCN?H^c5G|Mwv7oV zwr$&XZhq%IXTA5Xb?!gCs=L0ss=IfsE<8^?pXY@I)SWr+Ny`jebQtU7+*iBA!Ye*T zb_VB}FftX7xH(AfoUe~jui~vsk-^A?yF$>UFf13q( zfLhg{u>b-#{)*y*$^=%rEVCv?czbECPr0cYU<;GYPHn_BIdCb5Ns-WK?5remZVbPo zQb!-4+hrz8J6QOj5v|dOgUqYtBKqtVbIXw&uJJi>`+5e+uH)megKE^Kc3n06oOG6~ zMXvRw_(~;S&bUG+3^IR2cRB&rg~rNWk6^mi_j!e&HIjnWcKl%{e-3FcD&jx8_Rp}A{d(;V~hjqoxa z6ObTfbRZp=^4d%sB;^K9MyTX(7w){9<_-z^gOD)7A}l}+2=u!pJ#KAm+3L+!;Wklc zsQ?%HT(CW-1zB$Dn5>p}xY#>`cLoWjhEyQ9oqFmOTa|H{+SyQC$ z>8!mz>jae{mqq%eXC-Gtm6zvkitYc_28bq`!XC{y%jTl6nSZn7hJ73iL6Wx#S+O(o zGSN<2;K|&qZd18am6rwJxu8jrCwW<(8pfcGfyqbG6ujjwoX#;WJu3_hY*PGuyq)Xp z6rF}7bSqCqFfs*;s)eSK8r64<$~rKRR!iu#QB!w3OJAzpMSQ}|b5tkBVg1@22Yfm{ ziFaNJLEecao(RQZ9P_H#pDWV~Z2urm1l*1Qr$lmS&PQ@{_hLN%e9`Z?zG4GK9h*`t z72hAhS24k=+xb3;VHoJd@|4+L|6S-F9ot}I`@8gdnl#UGU3MYih*6_axL30@&l;#0#3PQJ>DYO3$N*MvYQW3Kaa{H_b#c&3#{j zJQpvK*xl2Dr1W(6&h6FDfY?J=3?}0xRSES5JKB6sl_QO1^%{xUbY0K;gQgolmvMfv zz<$#cl$XBF=yKT0VEb)Pp{_1*g&c8&W23sH(5~2O2ehZ$MDJ>2aa{=#0rKrtlfb~A z+k+++c8U%|iPCGjEM?xt1?3gomPE34o8)j+lU&U+6W={IvhX}k^4ZU5d#h;_&ifQR zA$haysK1IxShV;(o@$NkrBufVn|U&p+0}P1m7_KW$&LB!ao5N*b34fZ? zOO%a&F#VY1f*klK9Sg8sJ!`$NLOH16%c;xX@c1X_N zRMs!B;A&cHeG)ab=O+m(4d*!}5mZnGzMqAL$TJ4N?H*|)E;K!V7&X~mL(k-T!X?q2 zy5I7{VxXoTN98N-J>hX0p?<>~ESR!6w|SJ0@HWndBru;sZ8A z5u|d`ozraypQz9d7B9PB`m}-o{6%g82*iIjg*o!v3ktS}d4Ro29|Ux&SBA`qoqnW| z4gPtQCV2{hq0vy}17Tw>**Dun%}>}I+I2==&dR2u*L#@J#pV(#kAeyjW?K@jlr$@s zmFfEA!vU|ar_5r%Ys{Y=P(drC4XV4HMpz)~LeWCvbr;YMR$Sx$?IwL&vMk zV$K(+^N{PgXT5?997nPMuj`QfQ+FR;`4tkrIhavbRtTM)a|*LrEI-v`IAkMQZ!&wg z5`Jl$H@>WAf_>W!4xWRHbAZ|DIr`|pfnqEAH?Jh7<*e_DkXLS+EP0RpSsXDqetw(m zn^Ua9u>slVU07sC_e&SjU19lL&hW1!+`V9e61eIFo;Uq({U%RKb2F#}4S->W9`i!b z91}M7FLE2hjXfOkdPcTB(dO@wp83*ZK;PIDGP^<;0uwQDCElhMW&ic<-ZdrZxXX{U zx1vjp_TRW&k=E~>LA*DTFguquFo2?WEBBWRe>xuR>ZY^Uej-YE4kLD1&6DF4tDqpO zZBAtc4q|6a;pF!BQRTQzuO=#+@#S}6%g21f3ajPW?vJRHpq898JmV%-q421L_ zhj;@!J9OAqEgzvic{1g>D}!XI0Xg{~$|$lWd^dD@7{q8!d<7nbwOoo4+(JNs8Mehg z`jpW9A_7V_$mIG8x$%owrAI!&O2O9L`N6Jn zy?J1hQshUOODqJs1g5;7>6d2lamZy0}?HGW|K_egz51 z_p<>9w1cwA$TR_mDLqKH2i*ft`(atY%B-YPdX5s+j1_IGgW-A?SdDN+kO*VFl8%@u z>2y(fn!HOH62L}e`8ckvg^&j#9?^b7I01jqj}FtW)(6G0LY_UBZ#qPL4dFv}SPC8{ z8V9$nQ34aZfn)4EqS?9j6{|GVr}Pq8a&e5CF_coe0{slk_Si0EWkRldG9OH;$4e49 z$)R8btwTF5wq$UVjmOdfXs|6S5fdI^$}XQOC)q681CU9umw8$@IZu7YKS(wrFUrLA zRA}37(KLx8`fU3O>qb;&RAsdeBrz=@O+Pc5w}Le{n;)<3$aUvC7XIl+K(H-8;E9IM zToJ*(%#n`5{iY{>X>hg8)N*b1#m4LSrO@-XHE!pLONc&_=Me4n$z#=DRH2XgVCvjw z&lZde0hlvliGV^iE48(%j4H^+zmM6uj(&R?i(f+2pH@O5-asF%2v9Fj2dHOX2f0RO7(hz?5__%cw27;M;#96v zf@Jp&NH-k5^l#v)&%w&j6|)&jm#s zJw1DZL9N+513f$Dvoa$GtCjH#@-$%?;HnUK={qdrI?5ykk5p!t8+c!?e;)uHO7$lr zM@adiF))_?Ukxm86GMnP6&d3#T7s?mGQga5#e()K&u?<&fjXjoD2h`$N?9gu+?HSJy@__we$K7w_a!>pQ2OnkUvZ0T47A`_ba%C`SlD2pz9U}H#mKAK zKn2WZkO!>BHW^SoEPcc6h3!!xBT~du80}{&V~`rg9{!+Uwn|GFIt5e4NUWgF006Q< z4mTW~&!{J?tDK^x`Hwj)#tG|HW0Og6DW$4?$ei4(1j8AiQoFP5Bx>_=vk9@erM4NZ zP>i&TX->M!a;!#uTb_h@w)IbiXHt)NS(i;`Oxw5+0SZMG)2($$J2km4vFr-2d-QER zc1iYAoIdX{S#^HHvz25NaxiJ(Awcc`zC=k4cbKlfF1&a>Pe`jgAhS{oeZNx@%UBx2 z5R{kH{G0%i9!;wF(MUb1thj(OlaN($h@H^;bLApS4<%N3Hej4{ky9aWB>$u|)j4*Q zLco|X*-}zRLI-mrp|#?0{{u{GS<{B2{dR64Jno;`vcL8mKQeob-3rvxA3!tq>1gkM zzeEk`w`E#*m6DFbaFrl^Uy!|5j5(f)$x?Rb2(rsxN@?@{j=D>-hgsiK_bAb528*@8 zk!{IMw}X!dX6+mqW#upApKChv4Pjpu3XoVGXRNY@XyG)Y;>PuxY@&OAx7LaXnd+VU zhYL6TL{jD2XM;>iW0|jf}gz6B^t9rj4woCvrO7ldH{peX`0mtgg zSsEYjook`JK%F#0oP}2a*wu8UHQ5IeTp+@n$)=BbcJdOp-4w*uHGp~^>EnU03EbvW zp#sZK#>cQm+Q*RRVIUGe-p$P8Lc&qCc&vD~NIBB|w}V< zBcfU%c=kV4!k=hCa8AI|U8ZEwo(`(;7$zeVs}EF8{h_CpdY)-r=udKI*y?>pz9N7D zd<&ykDscFAghs!kXgsTvQcj>}oo}Wk`GTGhM904tE?m-e+yLx8+Mo1Q{Gy+ni&u%m zBM}S1TJvrvG4q!L)D)SEs4pv7(`Mymn2$OI?+y(2tbyS(G6%%85>a3o$)@XU?U4eX zXM^O6F~n7&`txock#Lo)Zr4|mHL5#0$+OdCXgCjqu!dR_!B`6B9)mJ7SK#-8{R!GJ zmQlIYBC0IsMFECG4>gt(^#mexM!{8diEb`eVIji-qAI@(<@FuJunwx~O6S2r21&n$Wd zs6=``a#NoX?XCeA3|!G;3?`P(ldyX6IVz0zuXc{P3N5UWf^6`RaLgqYreKPbhqNzK zmd!h52QAeqZnJhQB>23cNSUS?3%{lLn&8ar-KRM7sgHLdxm9r+AjMz&5kY%I zKmJ|~Y^64Z?S-|Qlc3uKBGFgMDo*))=1Uj%x#&9;7a>9IV`;b@RhCvUOmr8lsS^Pu zPyV;zrwWk%6!afJa;Q>xHZ`7Y58eOteJwL1cyu3! z9CB?YNJV%K?+$DNyS0GBYG{oFw1X;ZEa2!e@3ZMCKr<}TaZb*ln4o^;k@Xk=Q zM+5RRY_t}1qPHQ~oAYMCJmof2DKS~9mnOh*j|RSAgw0w*z>C+bU=1yarIEY~Xj)i4 zC5&E_mHEB#xqv8Yl2&2i!S8Rz^-v6*YaKED-ZB9B8`#9eHiCXhB6CB#L)VA8Pmwsz z94mo)d)t))^o(w8WpO(yoYS$8nEj$CyO`uS62#+D4v$ zboicF1;^{FzL?@*(=};rB?D{eFj|Kji7!O6@Z+`ueBFeNI`VlXKOp!t@#b)fZ_@fC~*AV zdaUz>K%&;Ukf2#atHNKh^lMIeSE3%%S9K1ma^i_AYn8meL{tWOUAS)&uo}tmY^B}q z+KJ(9=FCn0m>?bB4(k_byV)u#6)82XsZG+#6HqQV1jVK{W~;Y^>?CM8T#a;e|e zE2-t7b~=N?$?<42*{z-@YHd>a|9Yj~<=nNcj`yJHgq|g+?hCeHJRWXwdnA%hgDNFS zI*Xo%`!^tOHL~w;r&!38h8X)3R!#7g2d*Jn>LyE0KtW!HsapTNmLsvP4_^q{KgII6-rvjwwTxVLqtp`kS2h!{soM`1jPo-a%r8`RX&QBJ%QO+Oz$i13TyIdC%UOZ zH}X!0)UTq3FW!UQ7y37PqAeupfhcW0$T4RWgzn%Phl<*;#9?`y9t}4zo3&bQR6drU ztXbz}A;dUbWu&vZ{bT70hS3zADC+H3;6be;(@E3}C9rX_E1KOlx4CUW6Ae@XTQC8* z(#Z}JNs6A3!TuxMj#PlMs@rW5a30hX|`NfTQ4HoOj?jQ1$oS(*3jOB^diK!(dp#qUp>4a0wVyH^(R zBOHw;Vrahe#txW&J^1Dv>ECIRtaJz?2;mZmpV1xntdwX(fK4c&4sbY$_d*7OYbFwk zau*v!+Q=DEN;k?wnxfBK^8GE^n-sU5xa|!A2CL+bO>KG(-;aB|hMP`E9Q+2DWfe@J z`!+bWV=5Cp;b{^Raw0bDM3mXI(06ONmdk-2i548R>UQ;Mj}}H@ZU4fDtYwBxjc=2w zPWrdl^wig)eF6UBM+x>KUIFR8#})y${C8h;#P5ZUq0_9(qHqR-bljj8#mpT_H@?JI z9|nb91OED{V~TFyA=Kwwup$w##@8!t*mCb#doj+)FzJek6M_*Jn48g|QXx9&YjCcg*u5_sv3{pJ`=-R9@gFk1$;@oOS0WW}{9lMm{+XUa>OiEnL6%&R}qM14**BH4a@4p5A=?eZQ{}nD3 zKYA@50n8k^rKm_7%od`mr0IY1B~`zFU+S-hH%juybF<2SZ8{gLiA#nY70~!UlK-mW zd1MG>CHt7it@A$$1$>dUne^|w{Lf83P~?;9LFy|yMpaTvO#1TW7Y%5WeOFT8^4}#` zOPPqdWte{9^u99R%umIeZ#brgcFrB-{it@)d1RzB(1e=$sXI<- z0!WpNL)ZA|KYByWv z$aSsX41xl0Z|S-+m9?h09BS_Wez#$1O0IXw5mJbpzx#y=W6ipvBO(x5C8RM(Qh=Z= z_qBOx(q(;^rFA-3&N5ozpO{dkv}LK|p!2UDl(MQv>#`g7XK(XdcU{e-Z8(}7l>%%- zhXJwZWTB{d?nL4&<*Bl)sk z)$z~_kva&&wuof(5Yx(&Ghao0HrgQYJ@bBl&ddDwzWVVmNX2n;9h?W+4b{?*r4?oU zG^tiAZs^JaO~+o=*|^aci+d-CziB-ransH_vZWWDldxXj75chBFapgemLI^~*2H}H zJCZSn@Tw#6Xc>_X>j`}ZSrm;hPr4e!=XZ|yVQ^QRQxtEg?O{cv)WB-};3tzYbS&`3 zfVWTXT+fl#b1kp?5W=#5q={7D*((ft7KWLXD?C|KWUeCnQh-qQ^-o5PKAhk^s|J!P zKMl5kWi~;e`YzgiWeJ|u*D%0|E0k$c&hza?%%Yw7=fa26qLXQ)`qFokE%H37Nxgrx zdm!>gT_|;f$Z%OvjmRRQs($q#)Lr}6Svp10UzlI4d=u5!8rcYLWgZ*-_xau^{W-H&3@V$Dc~BI*rENX%MSs*aX8O}e6mlT1nR|l z5040UWf3z-_3Hf;qd8Bw4?2xB@6 ztuW@**Q%hA2Wr!b1J>YY>JBO1wXz(V8O%%BU~tv?IqC>OaCy#-g8zu=^OYlY{X16wx`>3BpfyueiJk8ApXX{{jk(`YLl2^IWiEQ7 z3ca1G+Uabvxr=rY97Aj5AA_C~o!75ZU`#H)D0&eb(D-!*SP9@O^ZbWs34xcE(Jwt- z`VpZ!rM#*TQ!Xv@^+oUJc-wjfwiQa4cwj`%H0thM01aeivieglMv$0{)6!sSNODVR z!To4;rHgxJw;`qE<0guKQO?IQ%h`NnE_(B72c+=YwEvFM6ffIiz(@dcFlzukSR)~> z#dV`#%l(iJ2=l8JQQf_KryD+j<8|-`{^dUDh27cHp(=&4*uB1->7+8L7&(JBtEqks zdD7JVYY~wGGo$a~{50=eFrx1*K!6_l^jk?UB`MJArJgUzD`spQJ3IEM0Klgjt=9(AqUaHGVOk?~t0W8HDB=x@eh}8qVl=<4B}C6MPru z-3oJWF+zW@3(s+uxYJ{^Rn0DQ5MPv2xIel8yw{Bxd$1#S^qe~yZ-AZu&=vLC|6*Lu zc5O^=Uryz4(KKov4s6;hEa289l;1LcxzS^*DZjMHm(fGwMUKOJGzlHoj~2L67uxMQ zPqgdPd0e#Dz2$wwsVz_8{zxd}y#dw;mRIlER?E4Y9oV1|@ojsQ_2Y7NhtKE(sJgiT z;!MCQH+K(%n3N15$3|GiPM5h(#TPfdeveDqXxR^hx=o8;30K3UT^m5OW8!Ng%*AR& z3?d=ER|51W*bD~T+LFuapeiPdB`p(xKC8Z7RYlV6TuW^4l!UWnftcSnC*AhnWo*=G(t4hql7b=dbbg5AjPA|O+ihE(%k}CM-aAtOBEl} zzz#3rRaqgnJoS9aV(SGt(C{w$)7-&?rLr);rD(C6+r;gjzGq4 zgb)D;_Ge^B!E!j6+;I8V+6h-3AzMo_Erb29{^XlNXr-M$<;MW9K-U^z%FF+EM*IIJ zG5w!F%qqZ;*Y7~g9KiZl&~(5+rQ!k;jj08hg$A{>Eh?Ujkhk$vPEHr##&lx87jSoR zr=U>(OktPP&0jSM@2LK{yJZi+5Zwx{9sSY^!VY4d{Nm70A@S&jsTyC9s!;|G=FwwDCwlm5L*%4XUq}OqBHOW?dZxZerZPqHD70^g8BMn5qtvKb(P9jPgU!dkbZM}aGu53 zHWiAn^fJ|EUYHeC!i?CUN}9!3Div;e)0O-KsQwNr33x;OHa*FC6fb_}-|ExkLbl1T zw*D+#xA!yyV?e;7`dOM;qQ=vb5;^L?UV!;aN4wrd6aW0hY<>(ks7VE5M~1L5Y+Ym; z7E6>GA?K9bc~tPNO`#%^PIVCJlN#RxNJ>QaJhQx@;KA|D+FPl9T5qIBv|?t- zdGBH7e(Dw%VdPuMK!mgJ(G`W z5FeVI^3@)kz4$;oT0<@wT9~7KXuU4Yj*_qb=m0`?qaWQCZ#|K{o#%^bNASF4UN>J< z0Z{&AXOC@XvL*@F$Ys_X7|0Cw$sZZ1PgB)sb-dflJ~%Mgd$l*rRbJIGdNhu9yKKZIe5CHsxgLEUgI(P zw3QkjED3U|BRXp`kTU%(cZ)VQ@5W z8IW9EK4MwNcspFtVvpOC*jM1fZdDDbmu=j&*Iomi^+YrGw_f6Yc>ay{ctEzU9Z;X! z;E0|`-Xsw4qV}Sj;l&0?g<}6yP9D>L*k9>|>)W+X2k1Nf!3um-m8W~JmGxsMBG|VUhS4SD9s6@rvE&XUO;iI zdd04+r7V_{dCx^Yo^&&avK}kXv8O@P-(tIxXcL!tmpUszawZ3&pU8qpg;HH{BNhJ2 zkW~e{VPF*&#D5CytcG5c_;u#G3Q`eR9l0PeqN(Bxi&t}+yHL)pqMcZDYTTsunt=cR z_mXloT&AtmGHJD*%)gE_gw%fbX4^GQ?&L5LrAog;iZcKyL;)x2lLKEj2Ho7}NJALH zE?X?H=trO0@%>~S50WRQvSK38GI?s+GuMsS zdz3dVKh2YCdH{H>XLCr*pF|DGq8?n--vpTcd=$;SwaOcxHsR_5{y|%YykcF}sUB$P zN=cq^D?Nc-WT-NVXCp=8IeE%O4^i#1zyg2M@}HuY-23L3G{Yiq0mpxejEur zi>|~s?(e&6k3N}Lz@iG{X_rJK^_bGHhLNL!NQ^Fqv;umLm^(d!wrW|{1c{AF$%%4N z$|yzrDjVc6q4TElbU(au?<9o>UaTSddDFNdGsU~KO45CMnl$S_1!m>8iJD{2T()PY zRCC&(n&CrS4EL!%V4JIk@3CtJZ#~n%)$&RYv@@RlA_HqzJ=eXdhAeY(b%T4m2=5GArBnP~8#uQ9xilD(%1} zi*NmRSOc;v5Ijk#ZIUn?h&mcn2{L~QwYXLZ<;s$9&uNuH%CwDeM^7Zbj46XXeTKXPDBccPkz%rL{N>UmQZw;>!YFM@2vR-yT>8 zA}<6`+^65FPy53tC?L1sHNx72a`-wP6j0&tKM>4beK}*B@UH*(A^tlyczlM*=&=Vu zxCW54!lCtx(rbJX!N4dQv9M;JRimXB%%@V7bu@%uu%~tBwMemph1b60ozgLjIW(om zcBT{F@RUD-*VZ-dvNcc0oOOb9{&f#ajFqD)xa~>^m2Izg@PwJNx>Ic+He&lFFjzi2 z{l;2(T2QE;2#)HpK=W&Ho0AobSgNW4Ujb0{l8w-0hJ%)2)-8PBXJMvHhX4uU-UL#M z{U-C1MGaxi*aPO44ms**I7&Ky_MAQp2jM^OJU?JRoxz8)t)2+nGGU=@mv#6XnevSf zc)-=nd)93@w?2w#HKHDiScf?*KKF^@z#e!QA@!D)epN5%zf4q*Mf;es9^0gZ2K4OF z_fy5wFja>+yS5d%3kgIzS_dxiWU6In{NmdVlWSg6j_MVe2&`z3u=WJlC9%qIJSiv> z6|8G3JnEp1A`#@y4fDEOguT_{I~C+9X$$@nH>sXpiY(pOX9Po0E)I>Uk@g-rY^=5Zo>NDT zW&E=oZg<|}80Fy2p5nGns zGrqhyzyu>FG?ghR6d<>kzkAf9tr>=?Ye0cFub-EVcuPw2NYrumz-b4%IKf<%GR4&T zu%`ERZS@$1`EqUbN;o3I1a1g>f_b;F>H>{?a2`k@ODEX&ztymSDd*I^j@(_h;YW}g zV>bzM#G4f<6c!jGC9)`S065f#(a9N<&!#cXxKx*xE|iv94QDCy{82x~fVuz$7bq1^ z5*tD9{HY7^+&H$08hrmaV@S1;tqF&(n#|cvh4w)so&R4Ba(I>x{#fZbrPIL;|stxWR+ zzBxA5cO5?rffQ!0X^^Ig>Vv!FD+3IBE0kM_#@IombFhZkU;7xMq`itDetK{qyb~7; zzKk!~I8^UQ9%2I2L(9Ak87`d2J>mCtXvHF-BK>}0Kf{^Pa81%}PMUo1I!eOXr&Uan zINHSmgs`Z36@U8!48v;He;p1_60WCdoAPZSw2!9V7O2&!b!Ou?3^cu7lyhuB6GOH9 z6{o)p8jHPl^j@m)ns&=u-$AbB61aYLZqa{vcpqwt9^Vu1ySOD!?9P}C#JW2J{xXKo z?A1t2(q{M<78#nq(l=@Y`H1o|;thu;tVS! zLIU4P@k6)1gyhs1qrTV|(u4(Ha98I91XA240jF+9@a}xXN2cLz`T4J2v-G+IKkK$U zUPpOA<=#K7(us{6 z-l3?L9O+JudLwyGx~#hPL>2~^QzLQ*L|j{Q_VMO7A>|tck6TV=R0NO_75z(e*dn% zTg|#BM6RZj`|`9QiJHISBF`qdbUi^^AmCWm{r;sv7*Y8FGKzk(o&8Q`i7iTRFhRkb z&Hy1oU*Q(v^f6e4+wZPU-Dy%L-VJwKO1@qJO~G47Nj`GzV*{I|@p}KbGeKx~b(7S< zob<{6ClYBWyU4hA!*1TVYAfo|%`bKz8bqm*n5v+PwB`{d^nj!hnAltYs8)j)bs|`d z+eECAfEyfQ+7@I=qfk-QO&bWmPr*ts@Xx}hv(OeeU@S<$92-}sDxxWE56 z^eP`&<&{vR<00|cVc$X7W`UPX{M>4R>snDv{-Ho`Jm*h$Q9%LU2%!#_CVWm5_9Z{wwdig8mA|ZvNsd}yjAUhu3 zS~saWBzcyeJ%!QRSlc3JhBn8CBkv;)F~}?nMr<-P=(W-yP-jCFCm^Wx;a4ap2(U|fUU0A_(cp8qsD3(LjB~um^*hFYB*~m<3OL_iU z!Kl%fJWVvUp5z3tOpG7B2S|GXv-UW?tC>XC!KEQIQR#p(RPkJdJN~aEX_3NNxDq>f zB~WS9WF_Y#XDhq$3gidajJIb(g*JPkpr}q`*~?jfw=jBBfApcC#~NRR<)}d^snDmNlB2ZtalK^5pS__7bhg{ zRZsF;rM|)t!|{nZ7*)qd?;2C*e-0fRvujMh(IiB$d=m-w@ou|_dL_b|Y#W9KzZ%03 zVrsZc1dRZ2p#GJ5w-SCq7a$Qa=mf#k)KM{c|HAc!?T|r9gIAzLi+6&Ax#N|tffj5g zrwLr5Bw02K^Q_VM1YWX4I9#{t$LwqVj0sA;h?>$2!S(NG(30i48(}!LY6t9o>hC{h zyFpO_X>oONM`RVjyxe?)vJxu8g!NL6jVG*;M00?|$mUL-z}HV1HuPyTX)`P}PD)ZI zVE?!qYuRrC@I-Bck)9YL{1dc>&EDJ&+em|H1f+T@yeP|l@VloIK2TAr3F%*<0D1X% zXc(p#4Cp~^C|PGRw~w@AG_bWjEzb={EAK9^F5zi=;oBe*89Q0BIp%M6U98 zkmx9vvZLofop%8^Y{%}KdYCBOpeHJ-LVAFeOnl>BBv%}dUId)j34?y=B7JF#m0{sk z&%2neeevsg{VQM60+B_Sy1ZjOLRp~T7DA6Jfjz?^?f-+Fhp>_8F6B?Q!;~iJYW7AY*-7vf4>R` ziK;d{J;|upH=P>@1E|glqbLQU9C6Bv2?uCUo^c&pqFT;UpZBdyJ z3`b=$S_I_sOSkBoVhO?O^j&nNV3e&iT&M2i{{0isefJ7qoDM>SMdZYmD8KJ~O__y~ z8FMp5Oda|Gy{@Ls^msP1j=Z4V;ESV_|F>3gI`WBXX+}3|VzcdN2 zv*+?~N2~M|o~lMZ`2H1&8!154a4zZIZ+w1DPV@fFXRprs!8pN=Bx9|~bJ&UBU;f7p z`B#IdjRxw2Ro;2KpO%+i&~G!}nWEK~XWX?Ig{yJe96r};xq5)m*hCJ@w6158dl{!( zXi6!ct*EaZXwCX6QqPY*U;|e&mgej1?QeCDKR*bO9AT^v6{*B=qx4dL&$e@o_par& zvyp@m1d)LVD*@u@FG(x~w!w;4NCLKzOPfG>|GjEZoAR{)z#&21^FzB@5B zrozS(5QKbK?W{1>A`PuO9`yp|%hxLq8>?G| zO6AVKp!fxtUUx>A?8gz7T7RhU5X-nx9l}!AtANX{-f99;h@TwVo~_c<1U+b?Pk@Ll6}R} zAblQ`6U8om3ac)n+GD(P*Chywd{mHS>l#%*FL`aW0g^u)bxC1;?4w0FC9Jj6rm;*a#{Gl; zr=3T;&k_HWVE6Y^+#n%WJ;{js1eVzbGVh;n+RTh7{}AD1tNu^Z2H1*=Co`vHtw3T?Lld&xGqYtQiPceKCp@=cfr=lceq7}4)cir!Pl~)9R9vs z-+W#fje)QG>nY1$xQw;GeUZKMg>Sjzx}k&qjlaQnJS|;(++{C8;nrnOU)D~rg1;Go z-Fj`ZcATZd;NKE6ppN>-4sUvFT6({&W|;e6=b(`-I5xBfe{Y+u&fY2|9$nOMNUuvH z!y%1EOBzmyd4V=J3?{N-TfOJ9H+^($p<$p3;SVcLQKQa>o277TLfvSKE^td+N|##b z1nyjRpnDu3eRAcBKx@=Cy0WGF#;?Q&wusQmgp}PwIPZcKke27S?(?c{@h2D4Vv}=P za?TJ(1P5XW8;{DWUF>^=QZc}NSzp}O%6I)8_m=hYoU_-1VxfjYx{UvnqAS=Uec!D+ zMN-viHBfg>8$B2eZoBN(5J5d<~+3X^LD?hlPHupjMo$89d z)H~8R(-)@-5Q+*HYQ>2v-G{QN3qg*ti$_~@J;1lH5S_a%JOQ@|-sJ0~v}w2V*Z=5P zglj97L%w$JOlB2Dm@pmYVLmUUaj2L)?Dal?_9f&=#b92gD2yhA>J~h!aw%`JIa4Le zrxbbd9p{m`Oho)yugTrR&i;_eSj|w#s|8vjPppd^@D*amhZlibIS@!@xX>{VlaLl7 z=Nmc0Uu6fVivNbYd)*k=hNIR1ceUqQ5x|ctsuSky_?|U~n_m^jqfo$b$*JPRhnd}S zy3j>)kKlT_7!oYz{AJI6Dsw_46nnBLX0*;3;XM6R;lY1eaG7fJ+-3LL^BH5g(;<(0 zyP;hG@CDrc*5dgvh0obXH)e$-FcwhbcIU@*jl#}cxm=mT&sV!&`3r8IH{Uu!m1E9} zS1vGTwT!dG?nOyZ;mECi`E!R_LQc<>{PWw&@=_alXWf;*b9UkJNwifWMwGM4UFdY6 zc{3vLx_`p(QExhNLb%1A*{}aLhne;C97*T_c$}WnAShUq7w>)sEytf6Or**d>K5@NhojQwj4d`SQ2xXfvg*dONe^0v2&aPId z6lp!^vfl9AM~qHVsVZtd8QD0!x8vsTtGdw`LFW zZM{4Yy*VXhC~g}459Ad;vU>;UoR!(5K;&CrO-Kxs0A`;5gt_W?uviIA@|Xgk;TcNg z#r)Q>AYN}~#T6t$GaWpvSHhw@H`QB_!uMXFL4TpOMGJw0CM}YCqT!Cfu_k&OeC5S0 zldWlVaB7s;c^(Ouhm!VML8um4OvwT?f@(vrU{r}nTFi;zh_khN;ud`?e_2H=(j@IY z`m6t6>HnteCKXAm&6z!}CneQ2hGFsEJ~E!1r?{WMM{CrtXuHbRyDgd|eWhl=nMj5- z-c@U4`P8nqV^d>ZDSzNW+R$t_2K;4%e{AKdaps{)*rC<%@xez>b{6n;4J=z{VS%9g zCu|69N&t{~I`k_B&c=n9>o1MFK1_0N=5Nlh~8 zYeH3&axXTswg{%j3g$mg{pDy!%>sKlR`G7KAd>{)PN(|xWSprzCpg{}> zmfZuq3sWMp>u*@>Gyb9@NNgA9pASHHpICF^OHi-=s|i|JO(YGM7`(bwTWU$qI4(PT zBj>Y3vQaagA~aPCwKbbB&PAd}KRHTpUKf>$U${gjfUcyVT*0 z4t5Lup~{3kcwu;dKPb_W1-w7reXl~)txbJBO#HDN@YHE*b10UxILn!K&;2jo^;QyK zg`%)aNb)MZGZuOm+ixn&q}kw4u{!a2N8x+Q7rElcN(20K1RIcvWnHdW??8NQ9k*#{ zH#|#Gg9Gt+abv?ZJ8L zQ7^6J+wLc!@9S?TcR*-cy1C{Nip5A27|Vut-4%Kz$%5KE*{p23CWHFKRhdft_brmT z@Pr@eb7cEh;mrUEb}(MD{R>j@{&FIc`t+i4SSEV`T4l}xP}Bd1tbdNKyb0Py;n=oq z+nU(6ZQDDZ*mg3pZF6GVwl(pW`+2{!*7Kh8Z+CTd|9W@t>Z(A%)^d)?Pfd0~b0=6#mH;QBsG$neh%s697hi2T zE}C0NWy2u=_r=C2h`~0w(ejqvD7bGly$z?T7-<*^8O*lfQYe{>>D*%!Ri6Hn38^Ty z-GQw8;X1Y2f>uj){&#`179K;-qhFN37S0mp{{nW&aDBn1j`8# z!nA7BPv(TT_KR*B^F^dN+uZ8l`k}*i`MA%YH<2I~0?5i@wO|IF#BtdqEeSH`nBk!G zcrHC-DDYqEUd4P_osQ|35zm2r${R|?wv$uLd^U;YhsCj>H<@=|Q;%8kr-Ym?YMw66 zcCeVx!n*YzBhy>Cj}&Y5v<#cpmn;Fg-9Z)Bu72OIPmbh(ddoat zF3gnk1G2gbwYgd+PwBjMBauvaXTT&?(&Hy8s-B-83$zoa5~laKy&H!+QZB}|7aEzD zcWvh?QGOhJv~X4HbKtE`26dZV9B8>UwhD3enj~!Rh#UxpGmq^iZ(7k4!;KGS1E2UYTI`pr#|% z8~mmjr_;ZmmTCmIb~Y!?x&OZ2Lp9u)ZynExv$P&IKhln)n({Ozq> z)#HshuwP&7O;ySa&qZUR^6|b81EC~2z;jH5FFhMEpos3D46lH(R>lh-B*)xIYxGU8 z&a0>V;k}~1rhw%68aF@H0RN%~5vaNRw7s?aJM}_oaiL*Sdaa-E< zkG}hh)N)JgablMD518VxZN_?)S9vmiax^cktLiRX@E;#}SM{qVI`4!A-lzfsD-Uvv z(jpYZ(dVu1KF-X@L-UJ!io+mqK&F>2S!EiuyVC%c1>v9z|6`Ey@bvs~N%Lp?C+`#4nb~gz>09g&FUHDR% zq~ikUsTAl>1;nuQOhcVXRg0)mD-cK1P(x`<-}-E3#~%Tdl|YUmYZ0=xGvLP}U~T>g z<6@HxZvGK#5jb)mARTQ}?pbler>2(cvbewOvtgP~qLEn$eL^_-O9_(dEc9D~NY@lq zV;YFUIE(~PH$pulDCFQX07`uh#q5g_H&x1!+E90#8T`ms8Kknm(by-# ze_vO08)g*149(~p9chU7&&0TL;<0|euM_;qYq!Z?0u}n0rYt1>NQ5|&vBGkvQc`|6 zOpEro&+F3aBm9eT4Mn!*%HGKg%JM5CF_S7s`Tfs?)b~D znrOBEb(#OEa{qy;vIwD;%DB%b_8-CqoC}m!_r2d?aQW?&c_YfarFzlsSh^~;r@&Gb z74J^fAqR9LikN&V*?0&xF)nMvm;xA4M#|*nsi8_y(}3YUWg6YCi)d<{QFf(cELRaalIBP!^Me*ihi-!aTA45y) zpNa~9ABw?WQXlk2m0#G5lrVpMSPe7vr+JtRC_lD_K4WW1p<4ub=JLyooqc(-@QUYV zlhOF{tevYSc>Os})=ifv%$$V|ZOv58oRjV3Wb^W%gjl$r=K#gD+`g{>YjP1#kT5ay z1D#)?z#Q)2+=SuwtGB_#c=LOF|E-dXm+&BY6*Ef9 zPC)7KBp(g*FC4f^v})`HPPM~T?b~*B7<{Z$Y}D|uO%v>4>me9L`(kl}q7@UA{P8uu+-IOG@HBsy=W+j&u6SvWaqokTDSWB;!QYrkpn-U zBhVx9hht^hO3&E~!UoYG8DZ0~2e(=?7SLWLh*TuN8}PYv!U8#U-kr+i@Jg2fi)qEE zo4v7ye7!2f;_JAbt=vf*O~*U>>-Mz@wtQzHHz7~0&gP_C2GZh2V6T8$zi>Mpp|#U$ zyEESFD;BSuD9;@On$Q_n%6}HDIKO$SHIo0!GBRoJHoLjxF40JDM|opoitlLV3c&Cz zeC&qLkvHW5ws0TH>X5(F00-sr5nVM9p}q=|@+?0fc=sH2fp>u!!6VB0EK23IV1s|V zI*+E)N-u7_VywopLhyvLt!AqoJybJXaTuN_8*DgI^DE!&D#e-9+`FWhG!@3Nk~!6;X$eTcTSmqe=Po9w7J1`4QGh!!R9Pq$&asmHf4xBg zk>!m3V1hIh)O2N7Fi{nNa1uj;qu>EK^NPB%9I{5GBT*%}ylHPM@^d4p{)h7O)7JSm zOw%Nia_KA)H!!cp>j-J&U-DEc$`54XpR_2w4yVbgzJxJl)`iN_NEoaEz{%9*UY7YJ z=GP1~B-DC~^h#F5OmWzyibvAcxvphiF|IB_r3eKkRYkMhL#-14PJwNH$qOWdGkDv* zi)_9Qc#Ui%I1G`~rxzHAh54>MAW55tFi@iNc{IMt!8m4wi_Q9&GtDlt{H^6@((6hb zdI#bXw3ohwwn$)RUv#zBC3~wx>Y@~W8m;?`G-ixR7c~6DD0p35BaT|7f~>AiK0>vxbQvj4z$3S|1lqGs)XBAF|SFKwr-_ zOR@E1ea+JW#nFEhuBZ8P!U`6%^5~!A5KL0Y=KmZHKt$YO;SuVVnWIFPa~d|M3VvNw zL&$DP7h^SJ@d&QzD2Af$l?g_wXn2N1;RswKH095su`oWiGngptD-LGxr)JFSY;*9| zw__fzq;FdsF_Sew*x?`b_#91zy_1HGaa)vDB1|f>UEV==Xb&rtgMgJ++q-WMkWj^X z*s?bRynhn>-bIm;gCN9KD`y=@LDw{u#p%m;Ov->szs#_6UC*7h;*~3v+AS=h*loaw ziiSVDxB<6iRS6Uso}MI7zZ`6|OHI@W{^#w9f%^|*XwMLDpxE~}1%YBk>WOcv{uoXT z!Jyia&!$WNj>4IP<|Sb#Nfo_=7Zwg(>G=@^;BZz~tL6dakGx5FdCU0txOzX;{?v$% zTSY|K8q1&ESE579fkaWNxqFT#Bj{gjTF}|aVw=KaJpAY)Yz7%Kh;?Md%uyIp>@ta9 z;^QRpw>c$h-ZbWA1)UGqmndMuJF`6Sw`z#T%-8~$0_<#nipSg|UUwAK1C27~H$rv{ z5QexkNg5D>v`+vqOHw{KSXv+~C>E@(JEyIev8#f&nM0bQ05BOgD>wUpJi=_8%s)KB zME`$QVKy!{h9oCw$}|OCVCw%fkV#sE-pkEKhTi)B3`AvRV<%!}<@#?FD<=yPGdnXw zno|HUBQR@Py*CKW|Azbf-&yudENS&TAU`$awEq($VE(^j1o#{FM=f_-22Q!KqI;hp zXyCTBoHO(or;trk7-B6#E#HXA9tkMFCH@rqa!58f(#1+Tap57Hh-YqxzrTRGeJ`YL zecc_MtxzH=C4={^0Qf&Y6`+f*t&`OPlcR zfyMfKRlFVebyiy!bo8O3mG&MwgILZ8uy3V3+>wuK2P1LVE({pBJFO&)`p(Y%MxiTG25?kh1Wb+oWn zOYp?{yN9wdF~s}z@$o?7H&CbF8{jpfCNX|fz|ZM`z2;DSU;4Z2GXqHq3VGmD{qA>H z2jO*Y^SjYq2JXuN4GW|R$H0)p%fY$yxqmNtx(}t%`RpAa`3J#z|SUnF~30 zLu{Sd++Lk7*EIpF;8uo4@h978r6NzInA-G@y*_{BBn8^%Ex#AucgWrw3t-}qDFH4w zBvg*S6OqPhDcUh2$~K52fgtk8_c4CKxG=|R@m8PYyJ znFC=PHL2rQQXDRUN&;3Oqt+qox9ronhnXl6fAz zJaZIU##Q1IvjMz=BF((6Hh{(Vw5l7+$-JN6HAcH{L=vgN!VTitOJk)1&0YcpH56D% z&xY)7!Ps1~NRmsqd5{IfgNaXsCsPv{>A)sowm=X(it$}Is z@b8gqrD8j^EV(X5Jnfz}a5)l)vK(qW(O%-I4O^CQtnPFZOiI>(>cCN`;9;9k5wXM- zG`B+mq0XUnTm*qeO}T2JCXI~lni}QLZdXTKY`{nPU%cg3fk7|qFX>%Gc$-;eiNi~? z!LnbRWIRSqbd~J<0X*dcPwkJhHsZ6HmmO}t{*N>ie9lL=^s;%YiC7H&@_fjW@c+Q@7?B- z$Fv!f6F+!>gsCnJTM|E2ug=nSF~O!Jv-AwW1FZlvU=)_C0puf(F>^5&MyU*-N;9*X zwdOP5r$QjIpnpL2gtC0WaL5K+dk)LLP>_?N96v5ZAG+;@|FouT$`i2;o^IWRoXM!> zM{!C-qj{Wwd}!m*8KkSKauf6lYFf4!NHhA7i0Z>LVr#WEiR1SHUyeKA!I1$&YI`A5 z6N3?V1hy3<0K)zum9RA-<%dEY6a_*c)v!F-{!oE7xIrshBGqEmQ&ig>tz(x zUP|FL~M-~V130^}C-F_Fc+Bnn;Y zpV?daRtNs~YPW%p@LvQ{Q@cUGxZfetmF5;>n%9-fem5_QXGuGwaOKkL&{ma8e3Dz8 z)G9qNtb5k{QOOzixMF|W9gW%GQ1d2^9+QR+b0t)S21f&R%=?`}JBcw_Zd<;@I(RU| zQk=~LNHV8G=SmvBtjRl3pw+Ntt&WcbKR1ov|6yoYh6qFqgeNmaGLi!WTF69wIbNlc z=PSUUNN_t_G3IE;W5q5+*OSxD9TCB>0%LX0F<>a*lnr*U#Yu7tT9ui42u7)GyhQ5q zqWz6QX(<8(2jl^YbI!=6j)Opk+`y`nIK*iSFp^h9@-`d}Xp(p*$v*@4V{ql_ggmM% zK}#IOI@A1knQI2iSOpp?>3g)qgV9l$4|7ckTcx(_K5EX>OZm~L2dEER8j?+SSdD_qjj>?gRQ zcjUD6!|znwk+8!)HCWguI7Jp_^DXm+jWtG+<*IMUW8N2)T8m6lng46|$D@UO)mCs+ zxS?s?2Da<1D2Yf|Mkgv>OLt6Q-`&{}uoJS|=c)wci~Ko@Rw?;o1slYCvM|uI)3d=XG@t!SjNJjwQYy*-gQ_m- z<8jP?LK#$2w0b*c_o10ks8#ndkxPU)>qSW1#cLXo#H1=kVx=dhbfR=M!=mZB>PyI> zEso&OjYW)Htl-zO&M5>M<{}?^aeN$ndD;i8wuyfqo_pixtDy0B!-85i`^NZDrdLvA zNW`vQoW4-yg{jPd$Zpw2{~gf)zDSqU9czf~g*P@xFZk86Yxm9W$%w76mcZCMNS|*~SCdBO())jF_1ky1B=B5tg}#<8jFlZoD^0Nhcp9rGXZ(RD zVeA)DdGxwj z#!msO5ZSB&=o~D0cv2;?dSn{n zV>gB~K<&t6e`x3;H1~G7^naHuN&$N;zQIc@+ekS|$1}O4nHMSMyQD*OqITPK!4<5> zKtNBEorKzW^T0Nl7tH+Xr_}5QRi=!mAZDkheUuaal?5b3WBz9rux7lLgiqrT`Pcyj zq|wB*dFe3Hu3Fpz@*Mf#*h#B~`bH~7GmC}I z`?!?Mn`Jj$m}Tg6V&dPp7u)-AkbQH00d0Y?>%mNjpbM2oDEqv6tP{ub^0=l(y9%7bZw!{lF(RU*toV-rzkpK5`in#SSVMfN7t!}-1X#v3 z={%Q#%FSZW>%MzwpjLq#?vW>8RHU4oU^7im`i(?|I!-3SYz{d6mzNxxEl=j4nJLJn zQ7cZSZD<@rxe!#y6+;ISjscz<-&W$s&@a0ru=Hlpi%dqY%NNZ}*@D%r0bxN(*v^{;s z65twYik!Ow{+IjqM!DoD5nrGJVqhq%_3#n(ZiCXoScFLAmwxB53V*H6UjM$$fgDwD zonF}wo!V|68M8XVVM?&?O+au9*lk6WS8E4gw==!WGLM;@pd2>_jYl)6l4TzI)#r2r zSfAMYmw(ot8@1u4Gn>UFeb;FS&fGc$)g_J3t7haWG<5h9Z!&Q;7FV%HRicCMM>HGD z4kT8xlG-%wdL6ghgilJsf>d|*$x4oU6xys4usH?Ec;y-UOZg@ zm`MV}=sK|&d6C8+brA9cIX;`;O*{jbGGYl$4LnV))Ww+^mI)Q6xHB-ZVKVQ_9(>>U z4W^b-jYte-R%7sDE3dTJAV`M5vZTMu)DIf*W8&x%`q&jxc zWR76LI!PK`ZYT2K3#(6LE5sB_Vb>$6$B53H^~;{DsTE{p#%hvV?Na?R7E~Eju4y?# zWy}R5-q25wF!XNbwj}uahU%P-FZJ9$l7XEEzW6XtI)&1DKfa1wR$Ml@4S{R{gbVw1 zs1A8z6F#1Z!UUjwd32+^UBpp0G1-6TRGl7z#5A_!mIZV6@+MlyEBGt@%`rdM;D$@T z*P=f-VIEpft^J`$Rfo^xq*_f=n@Df27@UH})s;V?;mGCcu`^H3RFYehgHCs)c`p5= zZrmPt^_PY9mnH_!fuZ*R=68`IRKS8-785_3^vr z+gE)}<{l3+m_S4GM^h#4EbV0VQF6v2=nkkje%kfNW=FYhwTR~WXgQvfZclc)H}ukJ z)<7IJdw|2zVv1FTh<6)b?mTE|fS1}2havsV0)bk~-?Bvhh7_LO12VHuBjEv2{NIlH z4;KHAbM6md`MO1(#*W~nV+gWFx{tM==fl`;|c?7p{O2joRy z7WAqi9&0&M4-1^{tlkQm)KkvZR@RFLR$ah9h@p)Xb&)@kc zxJi*T1p@F0R&JZ+xsR zESK^j!Z8ogCGmGt7!!i(I+P%95B%vwz#47Ve=U*~y=SX(2X*q<0}PV*;XF{r0@xv& z^oou8oLbyT!`p=PB(8{KFoWmK%lF~m7>ijC!YLZ?CGFuw=nzFdZxg~0#tvq|1`}jO z5<|FwsRz~m(NEkaFZAD%a=aw8n8lagnA@65w}|gJYhAjyl)B_$z3pnhLuckmh>;ij z);?0}X%o0*Cgj9w0didve{GjNfIoL|+??Vs9(pJOXZ)GRY*R7*DX|tIt%we(`gIg_ zp;|`WJvIe6S7ShH zxheSUjg3*V3Qad}DvRZEAoa{FRgN6u`t%@8##Mli!o;Ebkf`ExSu9fPNiC=dsGi5wY=xL77D*rBhMPkzEmIG34=g$$4Xbgzv?!mq}3t9n<XJ}vOAB=En;4SYHAm~`%xm!1zpyB(SXNLV41{?LPo&8q zQHiBdanH}A$P`6s_ABGT5KU2T=MJJIhEkUM7Tj$C(=J+aCTUi^6FAeXf1q)LcGh)p zxm&LRz)WMJCtq>9khIo)(p*0I9+qin$@M9yRkEwI!{&XrSM1Z+7Y~m_EHAz39SN`^ zE8LeTp}XA0I99Z`Bhf*nhMz&u>LP@` zql0rS*i&098C({Z&bLAGtKNrw_fEodD1&SV#0pDd`FonWwosG=+x7lZbnlU7KB?1> z3foSSip@lK8{B5+c=a1Sc=e&%h$7@sTKD7sSgiiZ&_x!e8=R@`ucS+xZ)2#)sU#9i zYX=Jfn*b8MwG+KgkPcp!$yWJ$!e*%S8=vx=hGWJO9%E5_G1xua>~S2;e0|P7IYcfH zuywpy-S&MMi@W{mn2&f2SFX`9lTEv>zJ4)bezPU~v*=S+Q#N{k)axlSX zH9ZXq# z|F_QZWzxQiZJp5W2w&NLA|Ka@mkTEiJT8^qxc_MD60_K^QQ7V77-@}t{k21a?$Gfn zQZpZopco%=bA`^63$;j2+^(LspBp)!B|C*x-JO`pAM)SbbrWfFAE$UZr5^*>*Wwm7 zs~A7KBK=(6+W$l|CZlowG^@NN^M_P3Wa7DsGr)T^R6eEsKrRq#^O`07h?=&pz|XByGyCvBRl36@-hSb&VJK+}JeqUn$)g8)NNbW*i z+0R$~9URB*)w`2m&S*Ovh)@uFXJk*txT~qQ;*C-u7g7{chnCt@pd*{JNn;j<-+9i- z-&i^QRbu`N;#+uMT=Sf+Rj=FEN`m)M$_$urEUc?AeN3hzteOWIfKp4wNVrFz<32?l zr%WNPA0SLYyOx;72Cw6`uZ^c_!HUtr)05;yyxYUxt?ALuPv5`i2Zgby4 zs4EgOyO82pAnsI(``0n#Q2P5EyD{WlAnZDrh@bU43ISr%))znVFC(e)z7F!IZdqxZ?ks349x z67DZ@v_#+faj?Bj5gS9bE_adF|5i3)K5_47 zm4XOvc;r`APo1`IQ|*nX*3Oh?cssTNRhu08PF%K+a8^7Y|D955{$cf2Qg2-Z*zDGM z?E>;64&B7w>eS*f>|<(rXhUq#`-GV%Gv zFjSY10QA}0fIZ1Lm;9D@OaKq98r;Y5)Rbl~w|kgLAI=-X8RC{!N1d5=w9NljcJD(9}#1S z7Au>ws+CcL$vOf7tWEX)s7lM7Hh|J2qSQO%8N6S5uyMis3XO9kH0 zZ5Hk!>@zb}r3bX+I#T#k)np0ZW~tok2)>0cbu355Sv)L{zH!XWDaA2goZJYfQm#-h zr`Z~&w5)_~J#XqN?6oSG0N7?bs;qu21U25c8gZ=1!D&M~skHHe(by{^DnN^qXA=wD z+~n=yC9>YW%^erK7h14aBcjW|xcl1k{oXk|uZeW2+DYEzKv!U#2?{fmeE3mK11GNd zuflp#d>$IL$|Ituk~%y_{N`IN>Ted1+CG0PH@U% z4AB4npD{GF@=0k7!lI-N0Q>S0Ye{Z<*I62`GuA1zH5x`Gt`xK;BbHam0%nLtl~ELs zTS(RVYsUoLqV83S@_1=s=&_}laUc@rwf%&pTNeO1_0%24?HNai$*@q5cOY+Qu> zXh`S3;+Lz%*U-MAuYbD=)MlSutA10wFFUu1m4}pdnp%Scl3atC`0~#7h|FG;HKD)HYA7reUbVe1 z8w4wL@LDPWZd~JQB6)4d%RCpY3=GYo6KVQ4x}GUTcvhE;EesutIK7#0wP-{H@iArw8p9(jS6N37`kFtG~>?2~Mgq3fNs_v??{i%>&B2DE#=XdB+15AT_0gZII;W-QP-ewVBlTTluAD zzE}zzhb$_?A=pbU=;#+zckAS{GU%B-bl$23X?12*>yfEy2e52n3=54&UG#{5EX-gz zJ5OXMQ&s6Up@^511yWu431uD`>&Q}@L!*NM5@%}z8qmY0Ic>8qq9YAo6Kn-PbsA){ z3cj&yIKB`g@HGKQG+f0$oBIk|rStLmQ5Ch19c2n87At<*`CFnag04SzD`$H}~S^-P4laY>C(#Ql1#RXLH;MwCjz0 zO*z{bOq8tkd`m~lWHHo2>!nr^khJM0W7TlUtgWP72faWKVMyUxdsIZ z?9^<11{&foq^T3qD)8lpAd=mpdZB%}_!hs31;m!$aAl$-hMS~yc_F9qH$dWw(Qft1 zK~V7HewQkeMd9BQAtK;&@JcYX!|LoJtanGLq^VZH;riRazbzE87x4A(_7m~&`2b+Y zs(K~9 zddhXMy0>@nE4#CGa<;x{*}kDlT&*FDq?jaGZ>geARr#0Z6t#xBGy%O9_}CVI+KfC* zDX@+|%uZ)RC4f}x!--VL!j2pF?#V>2T$uOEp=d*9z=Q7bV1rG}hi35)-R;p?0wc6v z{Vbth#LCU^OM(Wq!WMV4&E<5?JgG{)1TRP1QIrmLIzHp%o$GJJ({uJyz;RC-$FJ{MkAJ@M24O4C3V`#8b(gm3i@*1y^nlBS?3(P& zZU4e)UF=h-V}%Frg2!wGs#-HE2_ILfWS)Ew3k>PqNh%GUz3z46s?Nm>YS3x8Fm=}K zAQ}Z8R<+hO5A*!M-5#L|&3)bg{tL7;Ya*WJDqw;DkiIcQ7IcC4KrHw%TnP9~=MnGu zC06QdOTcI+)2#fXI}r=oAE}`ZH>+azzE^U4Mjk=c_1(F`s@+9NP1 z;n!@L?M#N@l1;&_i?xt`W46eQm)erYsG8%`rD*%jPt@Q_kG6HO0Dr~PfK3)}R|-;+ z3*%ib1<=1Ar#{7z4v~_iPw;iDO&C2(S=;Qb!2n9`h~4C>fao=bmq+l&BM2s+=M=Ct zuA}5*9)x+g`39SSE)oNA{IMyf@}g!4XQUksLvxj7&IrF)BLb!2I95rjXEG>q??wcN z(${m)YdD9@!;T&s4Z5(kYsT#dtYXh~o9Aij-}CkG9{e%x{Tx4uDh=I`#-y1zVv)S1 z2>`~Sq;KP$vZCcU428&mA*u0g57= zi-?PY@lJsbv2jD^_%?~&fS*k+~ zqfEYF8p=^PwG0LLzbn^%;8@7PM&oCM@_b(-9_~u@MWPtM!J+AxU3`)Uu1BlN1E_QQXQdDf>Jf#gUXn za+)rQoW-3OyWCymTkfGH9soePz<_|-^xZa8HBiWJc_ZN57rxT)hgJBR0;S|YbD>jA z4?37eyvcb6v66)|>}7uGQAby;n#fkR`ze)x@_`VSur8T^a-Ro8Gg1Cr=`rLEEYU~% z6rf3=g&35I=l7OiG6PKe#7U75hvi|bo(FFrKb%9;36^`az~%|><9W`SEWn1}nC4`f z?o_9WUUfOMCR=2blFNebm9e#~(n z5yS&WI=uk-;5B!2rwC%NJGS>9(j{E@!8TZ%)431#`F4|(j^5ngz%8PD%vcqljy8pTA8Nw9d5;Yd2V^5Op8&e$np=OvEBdXD9) z2Ji>hD0SP?4t-eIJIA;vrowQ$gbgFt-qOe|N0Xru5BhPhX~)r6Sb*)n@hqAK^Gtp> zJhjeE&pmNo6udOZ-ylG3JToS)#O@AyzMkJ(k~T{6zSBWzPln511a3HE)CefR7C3 zSQUXA^=Whvxzpo`)Brlt@vkhy!vcBBNBkIt64&_5MFiPoMpFA~%Jl^bLE&;>et@^j zZt`*-N3L*kCi*)@P9;b5Y}d0gY!9dkqyJomK;y| z9Q=0vYG=iAnww`_tgFtjcsP~6*DkXgvO;;7-_LYF$l*Hn?&EOjUY$_Az@0JOoFXXv zn~7&`PY=g*Q+4Vam@+_EkC3rdO^UIii6VntfND8|*I~vDGdYzn9oxm#a}G5gFy&=1NCu=fn6R`?kJEFa9zsg3L2|q z8Jk_7QrPC)_gLRbXJs@fXw2|lYMT3KNSAfr${J12r2=3vMr`fmdQDA5m+FjEx;D1M zFuZYT4fL6~mzXkDvvz8^d#5oR=Q6G7n|B}o6W8Cs2+b70$gaxt{!F#M!Y9w!I+m2W z0%B-K)FWVVvkLVjKC|^|->TQmay;rHNVpiB#^=iQ;`_!c2zSti8dSKH=x#z01R9=$ z2#592jRIH-IfPN0U0dW^+Ehta#a7EX^kosCB+GgC#n%`kgcP+k9E6l+s7Le?Xu~@T z-?o)fiU_JMIP4|XBjHZaqo^pz z+AunejTX6~KkNQO^YjcXx}2{*)DP0OFr2k z#3PG1AdTGL`XhpcOFc2L@Y-E<D=JH7xFklKUqVg0${?I?ehQ5!`-Uf9=LP!sI?v_#<0<95K^a>ic$$ggbXP9LzP zf#x=QMg&lBYRKI^ZJRgh{=z%Qbo26c@WZzq@I1astMb(&uef=fDh zeC2;?!$KP78)U5vbRgVe& z5fI&)-H19eA1Or32Qo1AYqXh#!x-mC$VRJ8OHx=+n+ zWX^7NKf+r7qj2c_T%R$);eX~C`d3~(`=9L3s_7?|5#4`e*E1o})tmk{{P}O9|GqWC zm-lD=kR&4te}rYuPbpDRosM9E&`_6TfwXQp zvNi$c2$K7x*X@7?pZS2JHf7-CVgQ_Pl`i`7IT4?E*(~s-2&i74$yaGElbf`LZJLRm zlRV7UDs0>I{yPX3qHE|3MOwfVY&Td`Qy_n8Y-cq5zOSD_RL6Q~{!@8%d#DErIIgTPYhukslaM zz@E8!NdqdWrdb&rPN4;fmB|K4F)uQ-Tg|F)f+RXu?~lUp7vz_asR2-MK&G8nxj)b^ zlwM3^uoTX|peiIVvT!k^S&eEK88L9Mb{m*e*hmBl#b_2suMNL)w?&^dYr;}xe^pxyi%z!v6v@B zZbh9YBy#BU{habP+-^dM1KLc}r?DlNHw=&|3l8~UIQz!EHa{?q8NZ$gsp>WmbBQo% zJP{gt@%0xZPz8*Q7&seF=FpR7i6)?zKT0-Pb;DspfPb8LR3KkId$rpm%M})S6ni;g znoWxFy~sF~DOc+Q*RW1YPF@3<}d2vK;vGZw>ay=1}3n6toF@`?Ors2_xZm{XRFD zk#p5f04fbBv<9|R5yZ#eypI=|1kt-E$;9=c_@SumJ`r?D61f;WJFfx|l0-7|Eoj*r z_o!h<1csQro-?{_S5;_eG&Ded80I+O-UEk5HPkH#)Y`Pawg7_0un#OnY4CwS@B+V% z1fWfcn?G_}QbH%)+qt#SV0}6_3-lLuLmTb5_mK>?izoPio5xKUbnyWk7(>a zyLw17z}M1{J3GX@Pw#Ot}qDIGFn&;DKa=P3td>k3#0ujOr0U z%q{$V1~)P~qXP%-$l!w3T&p03jAnx&ZIGrgWyejV%+Q}wY>2z+z>^k)wc+m2@X!^| zsdlIo)DZmVHwH}BT{)FKNdEEadLUm;R0&#V-`*OnHc`~Qh&{7+eco!(Db04FQw|CNBS^&fP=PXfY<#-s~S zoEIf76o_QQ(f>(6I3QYuH$3?cyj337Y4lztmDcvb)J|Zxbzd@iqSmjlcny8+-EsPk z+Zs9|G$8c%gF+b;L;Jx77~J`GeXUK?ua31_xVdRl6%T#>K>7N*DwU!6fex4$d=adl zVElgAa_qEna@y48TA+A*s$KPp{~MzfSm-2jo$jpEfvsL+zGq&(>rj&1TZ!6J;7GSA z$OgJM0x7(cXpk(;Lc1zY(Jr1*=gAD^7w2Q-@^s3u$(1bTMGwb+9g-}d)q;(r6_G}f za8vUiViS!EOmz-Z(;+6{${I>XOF1LS@@e4td`>TMJ6p68Gx5z-3+#8?-MMHHP4_sO zw$EN4?5p7-cf_(h7tVbDtP4tYPW*i7ld!PovhwqAq7tcwsd=losQs%(& z7B5_amGaYOG&SksK`xiBWeHu@=eqsrbQ3RZMvV<~WqOPTh}uvVJz90g$K0KZCDUj< zYka?~Kr&1YM`n>3m1#E#_O72EMTZ#s+SP4pbDOE#eC9 zU#M39JY~9j`Ivn0baQUciK?II-HYDMcdp?twNLG>h<ph?Ui6;I$(2d2SHrhlT&5(Wh2mj z)@44bq4mb3S+&*BP?%$s{$Qf8u*P_>p?g&tp@IdC-IyR`E2H<>_qMk`(%k;~lq-ZWc#SlF?!0#u z=4U|CB03nfE#3)2*Ys1+x|cj~Q1R*Z`qNpkU`7JpU0_*m6w)aW%P7xXjzraY%EcI@%2ZW@d;6lk<3@8 z=-rA<&fd7m`lS%8&}*4dS^c-27W!|Qni&&8SpdL^{nqnQwu_W`W(AYw>_lS1WGkYH zsMh#x3DK@syBde`rKJ!dch?h!w^H*ocJF-~ld6DRDk6<~%$BNvFS^ciDvq}XI7RNw z_Dh775*awIKeXA0vJe_~1qf4v9o?+sHLk1xxU>qoCSSJP=ilHZ`_R`D94CePAO=^5 zt^g?-{xFG{y%F@Mn%n?kD1naOkmrdB=vNC6P=XuH%)jEzJ`*}4=F&Lh!4evS67rz2 zNN0M>unVc~upX58Q6-fn)d=R7GdI7jXdMwb9c}N1c%z;c`($jc85%eXD<0Gi>kKLo zRtFkV<^66##yVSVFRjY4&kbQEiIN*hR^hJk(BAHhlrvUS>P^ZD z`EVJxIMOT2OAz7(mo6leB{3NI>5rvmFAeXW>g{4l`h-7?{HuH*dqSxqgJW|W9|F*l zgXA(Wr_$P_MlR1ySypzXC6*jwQUQ<=zY&Bn!6JyuDu(m<_WBNdOQD^?}paRS^Q0; zINZ=|Q2})!Vj-5>w)}_G^^2`3Wu&AE z4Q765M^}Ao_Bs*4h|{t8uhZ*+_TD~b+3-~FE;uLG`CEB-p^A+C`GpxcwMSoSzT{Pji` zDXrn1y0n`~u#fj2TVV?hPs{N3f3{%WRX^GIhEo6A^ovT-JGBF+s0I5ijSuDY7zVlTHD|4AY#Dkt!?TP;6!`EGxC6(E z1gPWwIPOy7x|-B}h>q;J!EO(jb~`KSq|}(UErLGE#YYWGd;L^d^dGXs7esW{`gY6e zX~44;MsO)y1W&=Rk(>`pY@+9jjX~0q1;D4MpmFCry9u20s(vAf)XW-QknEDY@;6(Y ziYn8C5{RR^en?(DS7U=Wd^8MEWta+zas^U`)L*&_f%%QVqGlWx=^qKZ;U+$818hEu zHE|~6#f>fGA)00cAD|o0k0sP3u$a)VL+L6h+>*>JOPZ*7rl@o<>i>Ka4GYl(5WCcG zw=(=@f0Zf12j&!MP%Wd#xWvsL=)p2Ruy7!x{XQ@e-cCXs-Tn$V@A)mgGEIR@_r()-dR~8 zjSA7uK0{~I4MdTFKwlV-Lb;~{9Q784FlGuVSTLANM?g06!6wQp3uNMFCGnqFx`wHs z%&uPEWHjL!Q|hf{Syi79;^(mT%kG$gX%3h_Y5X?OpdL+UDNrzov)5#;bx>1GXRf7O z5GIS4%t|!e+qzO$xwTRJ8Y|X%&S`7oH?^p|0M&Ulx#huWucE_Icd{#h#6lu^k%D$) zaLhDtf_EVhI~wR?m=z5tNtl&2HUUyV0dGpvXQrRJycUl9;AmYWC&p;{k~3b3d(Fsa znA*;qCBZzQ5Mzs74rvsYN$JS&y$Bj{&pOTNMl4jahbSJ0~!HH7DuXEJ@HR-j++gnqUo3r zRQniLG>&)*Z0FKIA#TMQ9CBbp{8X62pY46YG;W^QcL)=}k~g4PC3`?q#N%z?nB3n-?xKQ$KnGJE7yPjEpkpLhnr7Dta3y78l*h zP>MS}!W#bv__%?I^@dT6wsdO4fMGGU4zJAViiVHLpQjB@x3W~38j;co>?6v|?We}$ z^?8AI4QiLd!&B;0M<(*-Gc=E&F$aY-#nb<~gl8$l0~*$0#U=^+HPgO!F;wlI>K=F3 z_+qyd#D??G6i$Kw5q9A!^u)@COr@mP(28Zoo8=JJ>t*Y2Nxu32S#;OS+O_xS(^w_E zse&F|9F)ENxl_kUW=C?h+(==WuHvnLIiBo=3cI)wqHw-v~bU zun=@+aP}C!dB#+?TDn?R34V%EmR_5g9dzA(3qHp5OfwlAG;Zm)nSYla5G2)UTf&=m zH-vZ=SR_^{2&zUocFvR}a35P?FaX%b;!ITWUPGn7S#yL^l$wCX4|f zvxod-rr_SJ;nI8_F&BJ4x^?CJBa?Qua6hTvY_xiv&l~!wcqX9(sI1fVuCWF7mZBSj zc#D#xeU2o`e9|}-&HRJAA2p~`&CYm1G)8lZmc3_T2a|E%*F-d*6DIvl36i8pXOm_+uv_nn@S1{huS;|B&Oce<9}o zcXGUG{f#*MuLyUiF5?7*@ZKLZ2&BulE)ShP0a@A;461u$=x)?qp%FFWyL`Ce8f&%_roZSFA|8V7NRVDxUe1@(K;hfJi z+Ry9za322#_yc%)IAFTG+xR)YhFf`;_xGNPSTiQB4}zZH}3bxPfo!;Ck1dEKyKClf~7f4yGW%+7iKxW#;*%wXO# zLjAnET``xxxb1=i7=gz7*Vp(y{GB}d5KFt^OP3tF~@(-LRU(3BC9o&pU8e|Q61$l}CvELh2d6e>X_c2D?< z8!yP5{3UNDUJY;KQ=;>2>9LD08%oFZDGM*vyb_cp^PfTiva$3fL;WmsvpJFSINRY* z%BH5K6G^<8~c{_RSw@!{jvEApBC;f6Qf(1wFjdO0yKc9D=NA#HoMAsrx z4fg@7G;oqt?K{Q^3n31YC5#GzTR z(4@AlCe~}@Sq##QuPqyTO$eRWN5a`Q-O>Qs4gJgA0WETK69D3^39<}mc#}>Wl(!a^jui3aR16!gY|jnDKs<-aUO4QMHZDi_abP5h~;2q(F);5!J)<=e}u|EChfj zII;&c8`_0VL_1QpA6b)>bx+^KPA`&q&D_L!zHVzfi$c9{9kEx0!gO{}0>!W3t^UMp zNpd@Jy~9Te+~7I2I_0YB`dJ}1PLDDI{rDVA%{h|dHrrqa41ujaHAC3!}+%kzb zMd_A0zN`<~m4rCU@jP|F2)%IT$OoXBpyOE^zZb-Ef|;NnM&7vXxf0We*s9aXjdwdj zEtD4{f5s{6w@4S4{A{mE^uzSt|_bkl&5sltRppqq3PRC z{~HauUg4?-s2BuGJJBXLcQzdUvJ^f9-N;qeF4)T_!RECHeQZ~0`UYyAA>!ap zt%f9CT>e{)|6}zS1?iSA&x21=oWn)vP`@e%Zv9`CV{tI2R>g5@=$o#la{JiftC)rU2ThMDCgxD^Mz1DL>gYcK4 z5(-q*{2`FN6m_{l-W+WNlOPq;!G769hJBD*3);@&f z0JlVq-Cq;GnU{R7>4bgQnw!=;68-oC*=gdZXS;>rEliuilpzhxjeM->tjwR9Jvt;t znN1#eR;bSm*~~I{xQVNmECHEnETk+#ZX$tRI6-BHeTB0IQ^J%kI>1b3}XLYne-AQ%8ugFX`M_IulNLm*y-9e*h*>)_^<1X%(GKORlhp<3IMMR+0g zyk9=GbeIj`#}{4#>pS<-vk|eF zH%G#$8u0*roBmhC!%ZhoU(G*~LPPQ)uiewXmlX5-7Jkg_AteE*1o{*R$I7$7F?r`C zTa#R@>?n{@w1PjlkLE)#8O|(`QWzF@{>u(yi{ zxzeTpgPtKua&D;@vS>cLy*`0%(>U}-V4ZZxFe%@5Pe%?eZ%*sox}nD-#*@Y^q#Q@C zC1KW@V-%SIPWH7sV`8aGs-lOpRZj)$J zuFS|DB3-d`T3u#EiT*7SR*_nc-S~7m1w!eDEFY}@XL1+yz9#qaR|uv+l;w3Mpr+7( zsjK6}IOs-m@BFS28r;TkR}$HOVBMFsKzWLKTm1g#@0zO(vLTqu{1pQ}ahe<)^#dHxX~4yP>+ZCI_MO≪vOTDC2T3{=hi&Kvu*87?tI+WH~pzwO$}f=M-7NZw(G8R^xWMV-vPArjmjh0GN^BoMovZOxi4A%%d8PlL!j?~V$mi?S^g>q&9T^D<{J;!d7 zUETF}+q$na&0T4h12Mg_0Nds!kME_C-8IIt7@e0#wTAFySq^e-5-`E~L^eBM3SKE9 z8h>0D;yM)p;g|=31IFW<9vW59vN06~UcE@Fm$}{L_V~vt2SL!`Jje)CSyee2^1dQT zJJz=qd*O~woXeX+bc;Hh9z0ZJg>e}0uN{zs^8Vk484Y)N{57290h}l2t0|5G-v+DV z!`3)!#S^T|4pT#Pjc-e>$5U6!3Egb{dhgBN^w^*~-)`_I^Xl-+EPR|9<&>NqjA$y@ zL@hH2gGK7kXyN#ky8gD1I1qe1MKUJ5{!dvfpF*qR+~i7)H%)v~A73pOrBME{20j z%lERY9ZRw?*TMeON5lG3BbX%JCw~gthi;TW5n`u_m29D0ClQ}AB8a}9kS!ydvtc1~ zn{M@1akkUg50!xPG2=TzMOud)L6MoeJ`daTZ^Eb)Adv7K0G9O?j2{r{ZD21O@SS=0 zgQ`(4o(){nF*-AICm{6j+1d!HQFY92u9wUZGQz&(U_xwSg>?4o%NFj%apxYd4 zQsA?m&KEH?fC~7@cV;5rAZ#e+wuRW)ec4Wu_-o%Hdwak1YOYpFhI_F>yy}2ax0gum zj*rEMz!22<;B`Girw%p&dClUAQCXn3+2k|Ve(&U{G&H5yTjtWU;PyF({y|y6bdhZL zR@ggx+xm5mb+XozUd}05wvQ&^lmOA#g%`)7E|HK2;PCim!8D~osYCb2pgT?LwwY6n z-q~{w$MWQz?o(?j)dfohUY6=e5YQQHko9FBiC@Zx3bdo26T_m&s@8Tt5xT%Z!3h~JIYINfSmU==Fw}KS>jPA{6G4b?yIi_i?*r}`aI)Yx+Q z;3OpQPXM_)%=VY)8uEOJENw-J;CU0AIkrz{C57A4N=avh)oW~MpONQF-sApL+YhF` z9`U$6QWpQeqmxE|9p626w`&y5?q`|w*^c%-{i6YY?-m%0{(J%^Cy~Dx&zb(hPQr}D zbn-YjeCe*Oyzwv)^88|>OW+`+#^Lg+M;4m2!y-y!8W`LbH1dCeF?%%_5juZ*y@#)p zZP++z!~Wr51c5HUBls`z89v@v-(P- zc&=;4)Fetl5(WURMQ_2iXh^6*M}c}q#l3>Zv!v6^Mi%`R#-~Hbf#y<{%n1L&c1@G2 z2iJY0kU!&3V(<|}BzgCR;9JVi1}bW(RFS<1X-}8+;Z#-|8G_vJQO<=*35xgMnn5j` zP6qG_qSt|CeAhD^C!%QFBffJgTbV~cV`%+#6|q#!dY1u5gy|lX9jS4f77`FYuT_1l z#uWGxO(-?Jp191OMs|&S`e8+R!wxxg?(!Qd4oW6B>!}%;Z*H_ zoP=P{HVXsT{`M4g=hokZbkSt_y-HlC$DBA048>+t*U;1ZPIN%BO(o|f*umo0-kcw{ zG9YcHb>%hhhF7Gw^O|z9#I5&w>9r*F$>e2%S7i9J2#i3W?pmNhG(BvFZfDk{#7#&O z`Y}|SncjfwYFcMnavGTpowpD0Gb0jo- z9M%V2cSN1uQog_0t{;KyRiR?4DTu(6Ry=zO-Y}G_yM8xtWrl!1m@gD93?r0lih3`Q zC$aPn3?cJ~Uvav+UVj!C@hjTSN}C|ViM;Q-6sVn-jyWG_)rp%6^z4}G2CgRbu{>}> zZf+I8qDx>)Da+LO+dpP05LfE%+cGF_e_FakTsNw=KwTD}r(_zh4EMl!f3}R87c6k> zi$b}R22|*x&zU+C*9SKx#WV z`p*&bzEC|wES|eBV&-m#>s?%(bMieHKoz(Pr9xXMnQegPC@}I@baghanVa!Q;@)@| z*y>&5SRxnLf4fZuEA`b5+jm+f5p*5!X5MA_l;APDpryp|7u5bRXwoJYZD>P2k6VNU zph7(_E7h+DkgpewFZRu^;VlMl@rrZAT`pw&pJN03_uv*vSQ0setIVdwc_R1+&&SNA zh*s}}4`H>T3Hf+a(x6pm|I?(apmN;&xemGt?al1o&5wd0*nC}&m9`(CDXULYi*?do zdFAYJhJ)n*!Sig6+$QB6*z#BPYRGp{)9zB%D_{#CWDF>$ zxcGsUTDT5QgA*_0KRhqcgAK)`n`j1`y$G13sEVr54}qA_`7SNvQ{E6Zi#j3{AbB4Y zjlkisgig&I^3~mqxEQQ}FgPA)MSh#ydgbkynth9@hTimA;kS0n+EtfR5%%Q5Zm6jQOOY*XpX2_GbqNw7HqkO+dbNYoxf zw#9&b1>M(>9_^W=V30+rzeYpB4nbrfz#Te}7afE|skqA5U51f&SoCahW2 z15cmVnF$F+pB4%Ktps5T#JgsF<+I%L$9oBx%c3R2spnsiCKO>fW1bldhyZaq8L@As zbm}->QROAW-8fFgd|Di%sOp$z2uyF}y3yI+i+>_EXz6UMHG*&fx9iHUi`tjCMA5&g zcCO1HVlORe`ix(sII02qYp5!v^z>cjyrKS}L77A+V1LeCPvTA$J+?Sry@`2LP>c_- zX=ImZP~1Dznk*_RReVD0w0oz77TulVh%k}Yd~dqV-G&o$Pl15a;u3LAK{I8;iR{l{ zu-&9QVM8V;YC$Ic)x8TIhw=akhd>%zw8EzXnx|djJ3}?oGUWhJ{6*hgo+&e~Fy4Lk zXeeNBRWB+sa;EcoD`ui;WBU}NW9@8z%BerCI(hs$mTA4;qv@gBXxH58Jk@dh7L&c# zRs3VR9ryINBr$Vb>^9@5X(GxtLh9G|uPOE6%Lm7Ne#?J{r+G(tNo^dMF}1}$fOHEBJ>A7! z#!8*v&x2S1=Fdhcd)Ng~ky= zJs&;!J=dxo3H_K;$De+V4s91(NW&W^2x=&!wx6hgT9(&{owH-}BEzG1Jr|_DzEPEx z>?3>`3wh=wMPcevX4WXw9&`|CPFfJZZ`^pzg1HFQtzNNyAd(2Tu&~nLNe-{PeRtf2 zhW3jDY@mPr1Y$ZIc*$LbZSO6`PC9L&!R6E>|*h?qmsgCTX{rBrPER>G# zZb4cIxG-2lXyPE!%?a$yB(0*5EMdZr>M@yBaKFLT84^oQldWxSOxDnRQd@Ees+6#{?&#WiULMSN5Z2bBwFipL`+kE2dI9z= ziwK3F{LO`5BF)S<*`DMbGT3zGj#^};&v$}JNu=q|Ofu~s+spgxJ9SYlr`43S|EgU7#V%HK>QKe0OQBFHOFyu^VK@$6#VvUB?UP84S>?`}L9Iw6gqQ zp|{zx&Ts`v8@$@&Fp0yJ~Jq5qNTyj!Gt*XAV)5_l{M&x^�RiX0TP-t_j?=8 zC!a*{+K4#x7mOfya_4h9hUKokZ_zYw9pzE~I=&=jG_*R&Y&yy)+^T)k5>tldOMW;S zPl24Ft(wAiJJOn=P4DA_GhFt&(=)?7B;#pM0#oqBx}16o^3vtb(Wtr*%KL7KK` zP>GjhPeE_%@j()#@g6`0lAYZNv)O)A1CDYtnVL1$m*@tj=(-P!>-Z?6)vidHAh}rO zrybB%*C=pub<$}8%@|oVJ7F=vtWnAC-J>RE8;6IL&iB&OtUB$qKcXnOR$%310iQU_ z9rZqX&-`{o@^R<#swby zBcN4A#TB0X1CZa1Q1?r@xcZS-X62UfI}*hVLb%I8LMfLiKv3m9kMr`WjY&yJh$o_O z3f%v7bm3pb6d%f{`_{U5kDgjZTr1Gik=OUf5gxnm&%?vk7kYI8aAk{A60@mU=>YhG zuWmmU0Xl*m#n_|sKf+>I;hmI=r2YTFS3|EZKi?jJ4O#R%oZZm+?t&uz1q_shU^PQ&-_^KIQvnMq;l#rQ<=v5U@*w7~65NN6{p z*uJ4fpux{CA|*>3!R+;EW7A%p9=AneBcH(kBZP|U6Yc^@X)}<9_{6>NmLOD)OAmDJ z)E-IFz}l(`*_de?FxH-&vg<`rG_O#Y+VQlDxq;r6L%w%JRDL7cJ&;P*rFOCDBq zY{hdMvu6@#`u&9!;nd*|$-N{(|CZsS2WG_w!y4acGtMpo1M#Lhg;JdzSdTBdm9<^8x#Hh zyFk3`OY=GTv-sFD&=kf46S=&BV0fX)?ImBxyVFiH>kzK*o={2vho4Ht#%_rUJS$CW$<9z$-yEbvo)gUCFeomxoXUAaq_=$ z8rd3}3kBRrG+Rf!AQCVN<+g8EvFx1gUu@M=FV+(#1815WNP5a%lBQ&ucM-(0l? za_TbOSvH5lhqhjZ@{}kQtLUjO1<09*S0rUft)H$O*pf~ z++n)4QHf^}cqg_}%i}OMf`KjtQ-N%q0F>pAXCyIAZjT6x7vbPy`0?BmP zYu^TKqn#$UGt7UOC%VP*u;d8*Z5O8!Tv=ONd=lZD3>?5%Y4qc~RjZPqBirfLp2#bj z(dDtS06YM6SichB6gDzEwEt2?_TxgvRrKUibTI$00Q<6x(ojf7L(sgC_H+S z*xq>nk#lj;IOnOWAUflZFKA#F)E&_+zreZW=0Sr$ovyHwGNt-i^{snvA6;i7lTC9% zLt_NjGbMOkm&hTTXuJAy&Th$fBb^i)O0cUC9>AtsJuDj_%gSp8?De+a=39(;l53Do zJ>R!Ww9z>Cggx@8R}J!dvqo;JJTCS+V~EU=i!Lbo_59W#U4Gw+zQnb94tq@Wpys>7 z>>yAkCus&}V&mr{t5?Pmtzako&EDX+CZBw67{-uH$oXBH_H<)}f3=hqqPbPSdVs5l z0$@feiI^onS`3-@oKuhjS*QE=%^h41PdIgntthxEr1n5#;m)^5V%ERsJJ zyq`n~1+GDP8jt{PVCfjW=3CZ^ht_LfQ`EZvIfjy`5_ajXiTA0Q-iDVB3)%Ltg{ zfLaUZ(r2+Y?z{72ec?%u2Ieh?zAVoGQ)Cz&9)oFNdxi0}S8Vy6pb~9fA>bsilW%P4SmMmrmMF#hm1wZaiJ5qio9?N)$dPk*@?9 z;UOChj)jGd`N7E_D5WXc2TqKUZLV#-QNp~nYk%6p9vccY%qUW;#yqHAJ9{TZf_8R4 z4hkiO(;Spwco#F*)Q1s!am7I|03L|`IFfSb0Y5i>cLDBN|Eer#sk|?i@l)tG?Z-<) zBJ~Ow7pg#Y;r9Usl%JG?@^+=)eHVvTT8I%+u`C*|?``0l8O{_Uq5?4ylw0csEbWb# zntc2~mXTT~s}TRIM(bb=R!G6G{OXpqlO?EA-BvX1L9hv=*3oJ#O@L6>id6slpu5)+ z7>gYqtZP1j0|zliDwM@As-b;AZON5beNr$YGx1e`&!vsY^kCN(#FT(zx)B44L^%j> z)iK-(5oVMU{I4Cr-@kCG)0L|iuWI6lQSPSThwJ-~c1+Hs`?dlnmn^)$_opf3+~_ow zj;&o?3+oJJ-AB3^(tsNU3GAmtla0lNPre$Rs_jffQDd+sjI$v46d8|1>fm>A?&cpi zOvfP(-1C$69n*;g4isydz|;g%?>wpN3eR|vhN3ep-gAj z3r=fJzy)De!92AML^xgmHMv%jCQ52mEDE)SZ0V?A#vgZw*8%$a;VvYx=%~*~f6pk9 z;lKHHy!(b3O)4r5w!Ck@Uc)|7Z#Q6R;2?pk3dI;6@^@q5O5- z^vixi#(r_11>aENuJBLd_}xgX;b+0Y3Et3#j4ri4kH6COo-r}w14OoEkAEo@0k!pA zaZlf=l6BHbOa??W*XSs!&iqVJ??6u~rt*S$r&uMMO;)uiW%;o~u##Jpou(m8Jn2OE z%CpNjs$Q-7CHRHUw52PPsXOD0w*W`8Qv{|!_zAL^$F}{D`?~jvnJ!kiO>F}hT|N=x zYdgOl3F{Pu(H9z2eOc>`ephwKr`**xDhGNb^OunddH|69sMePm?6Z!j)OJ7R@0_Ha z3@b$~qr3Hf=v3~9)4D40odo6;mS;z^kCk(&Z~b7-GxJ@t9n9nDZ9JTdz4ludz%_3} z7Fp?xm)RWRF(@mcwUaySc`we}vGypKm~Yc4sCnP+8T`r9J@_|>;kYCBw2pY^F+SiRFMbK#6I1uu|ip=nVQeXe4q(U-MaA0Q&%k4$fY`n{PL7X!k zT$W9dDfKL?{wPB}sn)0b^YXT{yj5&Ev;^M;&G%l?^~gsvaR5mim1<1Zod-BA7C>wrdaf%rgZu z8th#*iSP)=cE(L^E4qMOVK$yC?Az67UTWh~- zjMn)}i~+NfAFDIf7dC;j9}?+xeH2H7*JwLwPoVGaa6M&{ZJB`wM;NDqHOG_bhS)1@>2=irYH`0weAgYEx#I=j-} zilZn)?aeFWUP)}7{u_@W0nB`S;hmTD3K(+7SWCR@?!%y_#F!%d%Zue z8^~?0zX9*FN;@C@4nlvq*vTN;j*r{_sRi3zP+9ZK7F%iNTUS$uz|g9kBW~C>z0|v+ z5?=+9twPVuMH zm*9|g(<+GtRWKFK`6+#)3?Sr0$3>I*yFtTR8qnb?X0J$H2X5&pb)k)U4cDQAwM+Y) z0nxFAv0zA}4#pjernaPpxCd0Mxn@K6!&N-j zw;u_{dG=1h=ekiw5)(4-aAw-L{j+P|0IX`os}L@6zuy~*d-H~V{V{2dO$!K&6A@|> zJ<gbp#Z$Ou;IAxgl^^Jp`IRzb=};GMNMigWhwl#ghP_&;`Sk2V|aWi-*m>t zgH(G*|ChB^-(TKTB+6OZ_^B=E7EoRv0mB4k?>bfL^qI(-$C-RcU^6covgo^BW(EWf zkHKUT8`eZun=Ylu)j*v(lvDn&ouOYdES5*yk-=!;5e%$pId5tr9M6h1i(IeI%Vr& zF*oe9F|KuStWn}Oh4r1}B;Y5g+v)oY6xdGreo2NE=y8yq)KxyPOR3D5P5%VS@Hcjs zGIYa)co%tJ@6+0LDzSNWl>)og7s%PrssUDf#%pv{z-JbYt|YcWi*CkQ8KdX@qf0u^ z{>DslLZImcJb$lhRW}hlz^C=KMbA%OO#-NTuTJ))`PpSmknYKDznKkA1w1*o4~xPNIn zTd^#5GyHzQK_NQ8hA5rgFAJv#40?`%Q-o(B9OifMc8jjYHr0Dq16IVHqzxL>xaaZS zV5D{5^}BWuy{4`}h0KBMHVdkY;f{wkKbD4m0|ZPdCr{qx+M70<3|mERm0{M*?2jH4 zV9dl|R`8=f9d88oD^TN=4G1mrL z2WT-B%Ad(2RW-4E6)#?r*jbF5e<7^SL+!8T)snWpkWOC^UmsnVqAyb_QU#jEzOcL< zu(RLw@*Ogkrsp!+z^IqZ=sshWRdw;J-k9^ho$0elfF`YkprHsK&-`D)f{7}&Pw;tB zslH$-M;v+*wg;T4wi}zU40|XU&d`C-X3w{G}UffpKK0Ojz{j`L=UB<1W`WH><{;YuSE3vrT+ve?iIOfoGr^q~r`f@77&v^VkQ!Wv~J z8c0e!jnfy>)p|tFBah_G1up5?-?}7|e|k+Q`Dh7C z-3;N?!dKyGs#vRm)RdT4UV5`K*dvW&bVJ=i0DkPkWruXVFNqql`CxTXKZRhEZc2@2 zLw1G8h{3zqCBT9b7Ay3Fz=I%Ga)i1mkN3j&ft{0+$oZanY(wDRwOHsCjK6skXpWKb zX;Qs3j7UGP!HB>7oP3ho_CU|9W6n8lIkMESU`y%s79c1c(Sf^H)5giY5SaPcG91EF z1aQhWKdEHf?G?>A(_&dZkz%TJF%`Y3Mm^aHNThRyW5g1Ja25UE^De;V&XR0ymo93g z$qtD@HqpDW#ZjB;BAsA?ig{@EfHMgLeg1q@0yExA)(2Kdi7HQ?y(i{>9HB^0OZiKd zvywBkrJh9Ts{RNBOgl`(HLndYepw#|n5~VR{hdigB6QHVWfa?s@b{d(PWz7IbbZCB zv$nU-?EA3K6JHIj-f>W>{crE+KM63ap)m1pOlM6Yx-B`qL>)&A#%-CNvaVf#R=!E} zV1ie!^KMW7A*JKBgfsR9-=K@gu;ihui&u>YvoWy_9Yw*|nIk5{gpO>0Ya!Vl*|U}( z)q?am1pGwgq?g-@5=^Z9=sua1@3Pqylh+8g^$s>c1s8!Kbyaob2adrD^Cdysl9tQ_ z_TYX4e3h!OMk|AdLxlKAj?+~U10_99k+yNlN39G51q;z`&BL3FaB3?M(X@oP}G?g{D#`H%TgBuvzxz7iuO<^G3!~g4vt4-ta*vjvUvxCr`Na0J9K5DE;-8 zoF;*yD=Tg#g-!;i7a9CtB6EeUdA9vdzR47ZG87pcAU7PWt-B7tD@dZtBM$`oN;I{a zZgOawZ;S>L#57XBA{1q?9fT&;#d%yVs3z4KN|mCt?gAK0A*e2(CW5nsODB>=Q>p+> z3gnv(C(oFqF~NU2Xk1d^96Bc^uRa4s_%iK@U@hUwocyvh;n%zdwKHEkB>ooYmhh!| zJv*j32>J?B6`W9C3e8MtO*H=n;HSwMpQ&Kcgf0kf8prwqHOa^Q2h>!<=PlWYXD(Ll zO=6({4KT()ocp2{_}YUUhq(LCsS$wC|G!?0Irhzt*oW2+P-pr5#`Ab(6r7(U_V!E(x^+i}p$9?AZ!)S86OXKIvpgXmWJ5dmHDB|3JmG0_ z^xmf96IkNm?aP4F9xVg33mVja~gdvY_>T%+cRH-xH}%Kc#)N|xRl7(*6W5#Q0LiYx~tqR>u(uaTL0^83O{z?a2!DL6YqOopgXHd;1&(| zrP9iHLwSP{!vpg7!qq25AhDl3*^VYYsN$jM9mDyh7JQGmA+fg;1J&+3+$Ny*$?o#q zOLUB9f)8@hhpa<;RrJl0=}=knF|?T^Q#*H7r$uH?@+Zmta4(mtujF)ZHx{^YB3>~6 zkBEq$lbd@8Y^!72>ZD_IY}-l4ws&m1la6iM zwr$()`0f7Pd+r!#ymR0Cuf|%nYtCA$_NtotK4lt@^E2>Orv&)>%ACb$+F-VF>F$@H#sTrTIT#X<r71DT@c~Bq;S4(yNA_) zmXC31&T`|ehY!SNsgk(t?Y?dOuI|FfZC}rqCok8x)9o%?l8x5u9 zZB1R*1*mP7?WtO8Ktk}V7EYmbyoa`+3lCOwo`yC<9>ysKhoyC?p1F!$mlPDO*XoE$ zW(6&eC3wSAU3@7wPOh|7mx8Wcxta*|91Z>Bic+V-*_L-Qg35nxYpMcAH^2NvrtHEh zoVw(l+qR`v8KzL6oc6o6&@*>>^>=lG|Ck;Jt14Cb7$9a1q_Wf6q)bliWG;Rt^5vB^?2h*b2+?Cbd)KGhYy>w1m3{O_PP zg*TvhVLEQlT3&Kwy@=&m;7V4-Kq~+piY1-KzGzRS_kvk=lD-i6v z#?wN-U>neO2rc-p%BetCOQf~uoG18pY_gLZFEmZBO)$R_?R==odOTk` z`GKw!;Zzk>tPYhBp?QD^w(aBtHXkUzf;i&#PqpgL`_m38hwq_(EI^6d!A$__ z#KujOt!S(X;%bk92SUPf9dS35efHXv$RODF_|@v9qGxFv8`UxV>}+n{&|LnZ)e}TC zzhOlplLj_yaO^W26|DCe0wf%@mkDQh*2eH)h$ktvG{k>Gwn__4|$zL-)T(FrsIqtAtd_~smI;! zAySVFINB;Hs51--n@YF~NIXeh01!cVf^e^qds&Z+}o^Xj2{V5Sh&ObP`?UP*nYvipT#Umu~`SjS&PjVGogo=Q4*N zyaPyWo6{r8o1L+tfZ|dwkdX>z``qiwK!3!$?<2nr0dtH^ximySvA0U1*KXkG!PGK}mBF|?wbi4$aeyV$lJu}4H(VMIquxzSQ-vRru}n&?!_j&7Jd zi|iH{Xb>*-Bev(!BOc>4Y|zV5%Y;*FRN6qR_OldL;KBnLhA32H61lhgP%@j-_oxZp z3i)Z*pFIJ&eKL%Xmkx_8ImXyWk}g&+Sxl$hffA!R)E1Doq0!P~F$&Dx4}evMlXe@# zm^)j;%A}BIuG~e!6NlofvHYd$iY*lf4Bm9bF|l6K(N}gCBPV_@PV z5F7^&X`2vf2t?CK9ZFv4+DakC02B8dg{ckmZb(8upNmfYlrxicZNI{*+k6+%#*9)E4V-SM8hbVw!iSQAdq z;ALVB)t|uEZmv1d+-<93cH0mW&`~={cQ#)U9Ym}pX%Lr?EBpfHJeYWbNAmreY^7NncLJ} zNk#xoOqCzXA#twAUb6-zUUr}0pfJZY=O918{`g9gVW1^uZR$-Fkth+x@=W?n@m*e)YRlu*A5~Zvz zft#XIq{@w-g1c6Z?l_NEo8Uj^63sTQ1}GG-^xOK^RC;9>tDq}Dl%|=dws93*DaRc8 z6OC%6snk~LV6@uyP?B8Wru?4~8&NahB>NM_OmHstE~cb690KtYT4E^>19hk48l?<| zk~1_?D!11dU7FxuSpOso{UuZmCYq-V5+C?;Xi4L2s8MN(aEcTQaT$T#2%s}LVouJ^ zGfC6?f}XP~Fp#CKjv7|Y>{fnzU1HJi|(NC{X{LlEp1GV^7U zj+li(szUa7IH$=^Yp@c-qu{Eoc;}<2@4lvW`=a#6NqueCA)?nl!++)JWBSy6d$XM# zA74~DIl0!9jdJXx@av~N0(@lZ@P+=_&|K<@wP%iQ<}$59llITQ9!G{6$-7R>N#q${ zdq#!(FX3X_-A>KO+K|}8Y8)05bgLBQJFLr5PX5)-HhbAc?LT56p|2qR^1XKoMpV_>-X%d#+Qp^QrYqzerBVBuA^ymPpxRt~W85jtG9M0&AIg{~p$kTr7swzEIm z4G_w{R1Fz;_Nm%>zl0R}$lonC--A^UnFG6wPgZPb@J@NCI zLB0bZYI|__5rr68nB=aI*XLNSN%+^UGSF;~-Rye6XW?Qd19ppY9Wi8Q@;479py8+% z@7Bymd05V*$s8pRVZ|lCRS{;@y;M_6*v(^tSpE(jmSYn`gL+ath9V(Qc%7>S6D;yG8@O8(Lbn8k+PuvX^2+^-%ftl>N-Z&aoNGT@za#(!LjfGSjJAu2r*#P;fi+UO1#j92yX{4N#IEe z$Ja*`);DIVkc!m`w^Np9{S6<;ys!dolc6u>=~dSW2B1df@b|JfuD(3u4)Wp=VRbu|QBoMx9xE76kyv`X#3za(I)6Jo}wb zAEM$IN8B7zM5NW35c#EM4-7l=QhRD(^2ymb>L@?E1IC8LMq8uVFk6IiKDm`c%C|o^ z3yrr5lX6qK6Rs7gL~&4kN#R11{1sT_GxT5xsL9HI>-*jGe8~xxa2-s*Az6@tg{#L9 zq~%FffJZhc_V5G5@W=%b(^zdpHg~xL=5WfV{-(}}o%V+!0-T+^4X>9azV%JoWLV^M z9P{Xq>1x>0dYaGE067jv96}Zd=Yz2gs$_JjM86?zKV^ahmm^@_HJm2T_%p&ioULeI zK)guE5Z1^|ar?1IqMNwJNf60_`Dj$Z8LNZ`@5J-h1?b2JbM7P$UU4J5IxnZPw7G-n zfG^3=p(?k@8Mrk0Pq}JJ(Lp-B)r}Q_i>%h52Z4zG-K=@%zr9+txs1G(b75w>NckSd zhGl7b{sr>1u`Qfx+xkCS+=^{L5L31v-?{!T?9l}cOf_vg%ruXSXfxA|$i zFHdRQYG<|gyVPcZ&!ea5lFnya;@L4@+pOz?prOJl`j2>4Smup-tB=aH<5{#dCNpCyF6PO3iC2QYr)^vou-gw-$a<0-vgzyMpKnhU(yJrxegN z=>hN5Aa)2y@njAW8gVvooRgi!O{#dR_*TPnT4atWHJVjMw%?gPPZQ&E7ljhoRgNNkE(1T%F=DACiUJzuHbwxPDtd=!vWb+PW5E@GMk}8+1)tc2o0;oBVu5PIuVgy^6J{b0 zZKxu9bEcXA^o?@JnA=5I(XRd+aTz?Q$jDoy^SIPx8oc^XQ`GB6kmUE?a^-L!ui!fD zrL2Q2Q2eFDwkD^jmBLzlMk~@q6Z%@l9_`w^kU8{TMh-1d(F)22PQb8gbS!!mc;aHv z(@{&=e|o9`d+yT$6)l0<%gCh#&i)T&98jTO{~yvlmU#CTOGT8+uAXnVySMT%-7an0 z<u=C0`O6w-cCkw+HAe1VcTXS3>{)gI{X9{dUv-;Z11>|RcH5%z zd)Z8Yt`FDsKQTn;0&h*LvBc%>Hv7l-*S7kfpHKa%&^B7r>l+A5bW>JN3dhN?i>1z) znZc|No|XHdXZZ4R?RzyJ7y=}|?=T|tDZLV}D*S+FU)VHuUO9i3p@tt}hx-MyfTc=BNrCO)7CpJ8uuj(Va!g$ zfY-UqvCrL2=esP74q}RqD=xF*3r^Rwf&fSx;hEixyr1j7zEk72eCkz*z|(!Z;%Vrd zN_R*3APpKBft)N7bsuth}&!T##Dy>^E|Ds=lNSc4bPaVQfG8U{LM_12`Hc9h?Os$JT zKG!S)G||+^h=P;^-^jRPN3s}JJ`1uh&e6>F?86R+J1vI|o;hK}F{1=eP@d>vRqQRy zjZ4=G+FHclY#(Ex@+{W~JC>UJg&A-~6y#$w6{gOk0_XK_r)Ql6xY*;`NXlTN?g>NN0# z0jFyfBYfDr(dgJd7`1c5xv<8}pzw@^$ob3j;x@{8$RZ%vfivR&^=ybHy^vW9q~A@h z1$6RZ@~1nizy(ku1l{UTkmO)HI~Lpu!YrBi<*JneH>W;aCcC8&Pe8*?fKFAOh;b#$ zlA@xhZ*m(a2)}&aA_=L2EyP#=mE{rMTT_i2(Z0-nxJ=A&Tp9^npemYyu#G!PaJT38 z6P2>z!bl0`RkjqlKM)4fYF4~*;w(>{p^Qk>VYvDp!f1X*)3<@~7RFjRqZ1Mb6*$C2 zIl1t`YTc4MF;x%3o)+ysxUiwk+AY6VG&t4pI=L(;V&D&&(Omus5i3dnB;FXnm*J8s zOg$e~PbxgwBN^@^NHGzsdDfB>O+Y>(*7aX$WE0rhz&$9Tf{2kk7)eT{!CQ4gdvaBg zhp}+nHGxey>KCSd{17imfEvY8U#>TB_jHd--3xk{vw!9GMEwB1fo!_$8f&}%lHB#gS`tKe3nT-Yt7P| zFw^9mCIXH=N~ty^=-4Xjn~w*S)1Ukx5ktwfmbPrj>G^@c4h*^+?0`je#i)yBD_^yU zTKYq60v8NO@mozvmg8N2_^f)A7c6%41+J)Q9_&f?lp?@l?`{cQq1P%P(4_MDJh2h@ zxUG35m(-f;{P>MW_4Fb^73BJR1nGsUkc>%nsVqxb#J|Z(c41Mq;Y-KgmL3QxH7_30 zLu8c^92EW~o>cMDA0Hq2Y&+5~{5GxB^m=pJ1)k4rSXwT@G_jZ-Gq^jGovFwyax&yX zU5_ubzXaf&SSl$&Vv)Io0-|IE7ul0B>nHx1o=8cM>vG2u@1RJ%Sv?hMlKL&sfWfhs z%V@h{7ty>PDnaY^5nObow%#uPby=Sk+ow8A0(RT-RMl11)VtOq8z!071{Vq<;kbvx zdm!43d7eVH;D*g!M){KT{JhT`3g3LywEl+Wa|5{5RM_vjkO^sbl(KNj753mr`@!0I zcMCfs7I!1M3Q3bv>NN&{G9z+3c-UY~+mFUPNQs(B*zszG95is+j#`r?-af)h?p|Eq zY$0>MJ7ny|I_N?ZwEUs%hNVyxTavmr8{Meu2|h-sReXVwB?MLIhF&OVXL6(d(89<- zk^>MuuVJO`%%Ii;?q)9%&T21#1c`E&h}^wtU6J-_t!{y=$ts-nim9zt4++|TJUFTU zZF{T973r zIe|qMdc2x!BWnG04PHdY>o-BOx3VIoL2q(-72krz0(6?#B{M^Z>yUmj!Pe4LO+uLT z+?nG;;7b(i>u-2AU@)%c!eWTOH7YFfkCWNFV-7dorP)*-eoT|=4v@4Eka-t-#mvRZ z@q2o)6`!vyB=o-h=hwvw&X~O|`Eq;9DBgg1+rhcwJ>hkYZ^-0{^)ywT#u`gD%D8Vw zTHoc{i4&bg+>oj)!RoMDXrn4zh(kN=b~XMa31cEj4eHzR^jX2TAr0+$)Xa~8-3$WI z+`p+~4duaEeJGS!UF<=>0M~bd6I;9PlS6?9jcxn(h0E}KK^nf!OkdE$RoI-V?~M^r zx+%^*mAGH;X^(AIUaY2-OW}bID*+nfRo_J?M1KRf5~SVC%EvhdmqWgiZ+4NiF9}Om z)<4u?>{0TqsCnkIMs+mcz+$c}FY@P)PDdIjpd*>9w}|qylH+640P^EV!cokqc|7;WmRiJ zjN&p~CPdrHhSs1|1Eiu|CCApQoVvR`OZ7b9N>v{0kyZU1tv#)2v?+bA-aiNswgQZe z`Uw{rcojz>bR8!=cv2t<{)7mHCbNE;o2EbOLiN!+oN{1@Qn9bJ{&k(y0Wz+WpjSPB zDR%DR{fn32VsU55zJ+(rsL_dj4Cc=Itlo>`k;|2J-4F~*2f)2S&*MNS1+%aTU1y07 z$OmcidpNH-t$Vd-k_n~kQ-jVwo~Ia~{bmZ}mbCX)GbW0ej>Y2?!JG zP`VA<^DWsrbeL9JlgE7eaoB0%Fs{MZ`b=ko)jTM?3aD{$Bd|zVK!3IpoiE6ONIcZF zun=Ea-dc2Z>pipA5j^UzUxCLQh_-|+Wqlghbkyfly|N`ETfJfK8DN77894V9Xpryz zUeB!)Pb_vbNH{=^M%!cYn`(+VE#Sss+wB;!S0QS+7&^Z?I@(RjQkEaFt{NXn31qY~ z-0eWu9&m8+0O!oc)k*pUE}?hu_MqJpb))a0Q&KrqxS{rJe76yBR56-g&?Okg1Ur|_ z4zsxd@$81d%lM#sx@q;y4cY0QAl4GN=aE}Xb{qKPbCB3$X{C6Ywv{(nmxFtdDeD(t zHU55hMXi$1uG4yR{=NNz=JQ4KOH{iM`tQ8q8NiS^6{@i-)P|GCBA%CiIL=|l8YW}= zW8aW`jY0VRbeZJJEZgbsCWR^o zV%r*z?SnL<{82FFR`|oDZ++RPmc62-OVpT3-P`PeTycK%OrGuWUv`d_Q}<0xqA|z? zn@0l!#Ud!^LKDQV(SwS+5JH5BNf+ALB)}(CqH0Tf29-D@9~afhxIB3(@GSp`+B-7I zLo$b-j79zXQ)h3mUzFp9V^|kfzf+BtD29$P*B(Nq@i+iTeEQZQF5a14^lLoc516DS z5eGZn8T0Fdi&pD8Ok~Y@1(u#Ti6~|X-SF^sG&1QhOBek~`j1u%mD#|M;7ARNhf3S8c$AR`WI}6Ky$51`gU5z1V z{omB5-s0^lf+#udms!UUP&ALpRZSZ&6g*dHdduB-iSV`b?X<5q z|F^FTN?X9&;puX*Ad8MjpWT=H>p79_*X=_4Vm#-^dk^Q3&dzc3%`=n0meNi$AUn(V zZ~Uh3YxT64dFjHWgVVlDM%=Q1@sU3%rzvE@QIs%UavEp9lqD9NG^l=>2^u!0Tkd-g zl!$(h#KWI=%3pb!y-?}QU``lmSmq@CSxW_($-Rv~ap%*p!}$B-B^HWiIKautSS(0i zEtL^i~rzggHV zM3b6|bpxeTc3(o=YhJ-5u8_j5^j`+dGY;lUwMOU{v;Iuu`}sS^^Y^l#=5*-Hau?4< z9>DhGbVtPv{c}ZgR2wiycN`KBTfBszES-@~E{L*=0g?|XeYi$BB3rm~tes1yKl0NC zWvlEO)D+Wdyt2cK!^W=lnd+XZGYiMIBmUe^)y=f?_Z`;v=b{;HJtf!ID&Co~m*JJcbLBCE)~{yx(w23489W@uW9 z>)|r3DCMsq4{m|~$2HIvyhAjt;hwKywa0{rVkE<$djnHp>f5KQ6ED)R9#pb_@MrN; zQW{;1M7CxR5Jf%WK+aKWRwyD*k}$F4j?B`XC8k=$Bz)8AOs06Fcn|_r2(hNp=D$*q zm7E{~TkzYRFS<-dJ?OSRrPLXm#r}!3xj{v$K(_Ea+~!P^MlneuJ$!j~Wb8q-M3N|L z59PGO|n*svXaq6!-1L*L<5Hi`u(s=gXHgo zvKn=UZlQb%m4|~_SxBKcu@Y{^9G83=8Ry8jDUsxe(V8nnQ zL))t=410$MMe!g8;kEMv6#c+{x1UJa2VvR-%QO8w@$v5mLz1G?u~@@~>LryY(4)!S z_*;8q)>6lO3N~ppjdz2q@nDE4-wCq-s5CM$xrZC76(z8GLX{iK7hWFGO3Bll{3ACz zvL+JeP+G(lzga=r^qRy@6T(mt+lfC!Ne#06;XK!Tg!|Q}$_wtBx02aH3l}+Rc*xFZGTz?;vz07M zqaH+Ql|W;eObpsYS%*S8Qv^fI?Q z3Rcs7lh77&<4uZSSZ$^fGK7Eu$lF>BGFQXjwPzZ4K{e4S6Dp$*29JV4XIkg+$QZ=O z^Nq5-r(`E5Q+yzeTsQE4_wlA7En#k5sx|KQ4$WYV^=Q!UldT=~=k!&cnT;W#u3QsG zS%80n)LrB;g7A+3J_8z)l1M5Z#o5|-#G;h%1E?JHXHEyz<}8!vD-ivFn`SF$r0?PJ z$m!%X7iurIG%4S;>o2Om8}4Y8Ep2@bU|Pp5k&8gcfX#^z=Mwh>kme;Uqdx`)=Gl%H zst|&V;dU+h;`aprzf}|pC6|!Y%55T9K72&Wo{%8oI}Z-B&zLKajHNdzA3`D|A&BCg zjJe6wxdGpjX3W4L$H7YgX>@wg<}%PFriaPK-zLMl)lP)hm=&C|%qKT48`%)-7D13h z;YkV3KeaA+82VZIcjy-bLTg-3ibD=DV9{f862b!6F)Qyu0|+pQ=2!9FtGHdVa27r< zl!kQbpBg|2>jdA+`mr04iRMA==;7~Rc>fUfJD@WVDuY|Ovw27XX045M`C$&)U|6df z>Qa^&bp-Sz$0$~Fq+O*+a5J!m2a3Xx2($NWI;rWRsPi^Oota~1NB~6o5tM0rO6PV0 zw|S@##@ezSD3RDgIi%X?ns7KPF>rO8Q*1buC9q3bY~RmY?3S&qyN`N*>hcR`*5ykj zd(AKkD1?}hoA4O|oa)kRB#Z9IE0M^Sm6Y@TN-2|;DK>KlaB6)Tn~I({#UyEhGS_3q zKOP{FKpZi)VW>1vM@-X4@EIyzuto|8q{;--qw`YTLm&&m@w&LvXqn5vX@#~=^Wdgj zFO*mtb$?H+oq0S06RFokExMp;0Io4hO>3^hfw>L50jx)WHv`8@?~g%G27%UFaMfn5VnY9a7L@rn$M4Y4g^nmvRJ7$hN#LP$TrGQL zGP|M~=)i&{SGIy$SgeP));#~py%s~*7zt-#kyCV#a_?pADhUA0QjF-K}BonyfNNw!{V6yx}T?s7YBydKdGu( ztEN;Fsb<2d|1?c56 z{)(IYnM=DB7A2>T{*sh3mP_7y?Tcm9y)y(w0asy`orW5=TyKnHv#93;$e2i4+VqEW z;+LE-G{=+u&hHa#n#@rR8HJy9VkEa6$Sp9Iu)idUGO8VGHml*5e7>+_%CU$fp9;lU znL(J~opv(5^K0+y&Y@c%Ej8xG5Af6FlksG#Q`60OWmp z3$)bqLPX8*W<>cst92`{H#XxXsJ#D}!>KdZ{#m!j*PyNH&p%l>8P*%}?B`YWuCM7% zY~(+Nkae6t8`f3TbqOg#gQTa<`c#9TyBXe-u?*D^EB$t7h5B2UF7$EPtpSAW8n@ne z0jo|p5NG{p;?PkK1iYlK>W2PT@RV=Y+s1RGOok~Vg!Pv$Y@6n5Kb~c*`r@3r)9#bS zlpVR{adR_&vDwfVN+AEe=%M4t3xnRLTek?kmy4^Q+sDW4LCT;IO;LB==5%PH`s866zuFf2A*+2pgav8kM<} zrN&KQ& zu`7$4n)t|kdm<9$Uk4eQ(&jPVG;lyxlV@FCx<=#p6u04w^h%GlM*?WuT_T-2u=h}& zza0hf*6`WiK@u94O1`z3rA)P_m}NF?x~0f5ZDchlY}?1U`38I`MZFJvbTtJ2#e6Tn z*FCrD&~q_N7oDOiC3LtXsHk3IqIJ6+$vX~K{pMNZ^U77BdoRRT7|+krdDmwBEz0?K zh?QddTl8u22&<(o_B{Y$KaE?UR7-b1%y(vbAHJ`zq)&l(c?e}3M7tn=0{?|;W zlheWTxA%0=WtQ-W+b*@+Io_22G?D(wJ>Ijf+*kFt{|yU!$DN@5Z5C3KBW$EmE<_#Op(>uJgaO%E%FFqD~SNU!?_7?pE3)*g~ zJD+E5qn~#MvH9USn_pVcg*^82@};o5DJvp`JBo$<*kos6?sp6qG%%H^V?m zt?=vd8*7JmPGLDCRT1_U=^U<}oWvg+gdgAZ$XF*1*9}iNcb)92gIymM1rFDEL+M0( zoBZaSM*9n~FyQiE)@%%HNTmzi@)AEkwuBM7wSEy{GO*I>&9x~TV7v+)RP@uapfW=` ze$!6@Bv`Mfvg!O9b37}$H^wlD{Nv(Y_-EG*guwEx9+|{<)UK)Bp0h^ z+(>ctzN$D9dQ#qDLuITDgFLP*;1U^^+=i@54XEA1X^r1se$aQ--%N~6mZ$b*9OFKc=~Q{jz{|lSFdgagOUL^X z`n*f>o;_6F%tuhKm2lmRvqq|_%}{DtUg%;|yoPOG)u0t% zGhV4S>SWm{_-b9GV%*qJiJ*$EN$XRmmHfaHt6%X~v`CC!kaCT5QG)>}THwEAYg8&t zTd75+u&w^P0~C*o!gc=d6<88jeR+@Fx!q~YJc2VIcwayBN25C0ettrWTvCRoBCr16 z+zWTBzV>yd9<{9VY;5HKK3KPL~`2Ely%I3yL>Arra;6f)&G zY{tt+t()5eS8L5BDQV8gL`RF@YXyi(KICyUKA*fGaF;`N4N8VMYlMR#5y z?rEu5!d!YwXfXU+O{%>7cIR4~^RFu+eg2OJkw^uTmxuAh%R_L9-qX9&>v1C3-RdBi z8o;G;D{0WGzU?3?)6=pZyc+}lrTlm?fZylqbWYhX?TIDGWs*j}@U0ktl-3{xTbXN| zP-B1j37531F&$KAW%p%*3xL>l;#<$o$&xM`fs26SY*CaR+n%ArOadE!pvKY<&vP|! z?@}y{s!L`rOJkf2>PtWUICcl6ULqKSJkGaPK6vq)iGNMPza2-Vd0`V49}rv|A^L>U z7LuTCrDu@A!K!uSDQ^XIPdY#45m7zffpE3s8qV$tt*O6q+=ylz)#{v9=^ixG2TnK)N z8QISgqv7yTpwv8@f{B~(Oqq`td88EYNdA@YqTc)`)1P;9qX!ZIP2o;$M)g>NpCcnj zmqJ&3{1%t{=PdGg#SDVd0(vez2hn!w!FhQcGh+o8k^3@j6g==D9FLU4t_F6*1S`F4 z(Jx6X^NDf=n^ACqQ#1G|Cz=-k1}7;I_(PKs7aw{{Yhy@HDC7vOSsgEy^2G#UN^k#~ z4C#XmN_Uo@1kw^vmKJul5&r%726Rb2@3!F2L^%Nt> z`dTD6IRhd@U2Wj+=X~O-P5a&nfq)RR=gw#==KTo3e9P%rH~Q@X#JE zJL@;YR&)~Z0l1}^>L5O9t3WHiaMWdLxjjz-n3Z|n&Ao<_30u6_C^60-P8vU)8}!@@ zyf}7h|K366Zodr*q zftRi}Oz!*uI1e}A1t$7yMnK(R%ePn<;y_x^Wi4MCc$a zjA8o)Kz;<`S)(g2Dms6~m{8k0^Kk8qrzN2= z$j!^9pofNtvVOuufoM}O(?-H>fxvO|qUD!%FtJ1cUO2+HoY6?G-Y!$&IjK_Ihg8Cg zC1?Ncx=esZECp{m`tkAz;%2Hj+Oy;*6Oe?6z1SeI|y#Rbyu@iT{+9~FZ$G?b{0{wUklWGz0L+DsYVSJ{rK_Div+=7E)I zR$b9;@x$i_a&cqy4>ix!WI+gjg~0}tp3N9%hrPtC7R^#^tYwOM@l0CmO5tru_S&Gs zV$Ys_XUGV_COV50bJ*GBFb<{gY6S-m9ikQi9LQSj=^nTG<6jr)BK^p95o^}@EmJw3 zVs3Bo*h-ppMFFkXNLy8JL(uDQQH?74U4W z0D0t{_E1uZ zT+gR^;#2$XblzF)XVY{#i~dGfp6>N-lAdXnfkaSwUA?ewTx5p3xEyj~$+$GXAZ2YH zZ=s@(XEg75O%rbiYytV_iy#jT;La@o*lc|B1H`XuD7uq+;fM^Zn@{cqt3{7n%B0&i zvEu22e@~NET*K(Fj49_ofmlO6d294C{j^wk%YHmkgi>D-6mn@yt)7oAWskA-^C!0# z9({x>-~>|dn#ABmLJgLpUnO_;8Jo2q{H?Zc^nzIAW+JAel_HHNwP^<~-_OqhrFDVi z4B7lq`?Ij{*W>wtUF6NiHww14eBue~YE_3ZgXHDqn)>p|8S^pI7&$F|Km!W9p6St| z>QADJPz3BUdvJFM`!#A%^oTS!`on-)1%YX%rtAWDq^MjgLyPC3Wm(ro@06N;0o(>5 z3sa?}Mf$klTV_4LEUuo>?6s~Y`t&>j0e{ol*7^&VX?LT1b+jETX#Z+M z+rLF)0()45`n61!MD-7x(@WTuNZLBrlePh4WVRnec=DK}seUVsjH+N?+r$Oq(o5l` zXa(DFpBIF5ACLdPoC+Q;>L2F99YvY*l&Oy~+TF-1Ek=szG_3oKUIFnT6ph8-Pv!K?Gm2mx1 z58}*Z{g`pV!vnp_!(XX){PaAj+yf2Tx}3t)Fi6w|ZBx4lp?J}$jIrqPkLivB&R?A3 z;k6r>qsDl@DfkRHJ?JigTx)u9G>9vv+oAgk#p#bU<5RGs61Ys>`%;5SE@8#ibSmAn z$xLV1tY@UoLnja#3OabWLr!CrDcP(k??L8EoxS#O5}%!0t;valfH`g6I&!3Q^1KqA zrBR`7wyr+dn22g24=LW!G2Z>{Z_e_b+edECkMIST&CUGk*RSw^)lA7uQy0uy>#s4nYb+*Pd~T(r!lmzRf|n0% z%KO&O1Aj*ng-)Jk-3;akUim^t9fXXC!c$zG{?aB9pRHFd{n4$w4Wu6SO3oifAMQkJ zyN+rT5y&5Qy>77p$hONMSRKGq8`QMeoVTc=geP2~{9bo3ELdYZHAgThaEM=rO24%K zX|;aE8;GT~I+63cp8<8ZXhw#VM$sfBROV{W63 zTb2;Kjk-D>X`gJhp!C|TntY$esYVfp+Q#A{@UQsPT=@;Sedl7RJpph#Vl`&eeHTFryMMuMj7MH>e> zs$%m5Wtvgdf8%Bof*-T0o(HmbwIXW?okb~B1keGPtSVIX<&$_c40j!HrF7Tp!>Cn&JfL#tfYzlwTO^*mIY&c2meUv7{`r<67@c=KJn zzOM{qy6Jq**#3mjMLS=Y&sNFyz;~~{TL%GjUanUq>aP=Q9lfD(68eUw-ZR(U+Dz}p z#t~d5B3+i1U?*ox-+D&bYO`JGxfp>&z9~3JsX^!E@QAEjjW)2?$cM9cdnlso`uhB| z*1F~!JTBsc%^6jH`}D*elF9B*F|_!VBWE;hq~%UCX2hX>mE!dHTbk+F);hZ54HQ;& zAip{5$=e18%cyDY%QTwALJ=nUsxgw@klGaT??-tXvpOb7p7P+z8dw@X)?zhELP^S( zDZ4S(_%SVKaBCmyY_v2Iq1)a^#_&Iz zm+K}h^5$ur{-9%py_#&EP2?G=W<3_iSP*BNbal? z)0Z=9hc;FpfXLd*FjmkrA&D)8A7pc-$<;W^oRAO_V4 zvAWPEv~rNOm>>h2_Z#5R8D%M>AI$7@E|$BDFJo(>ARQ-Li5Dab9Aq?!IQ{qXc*&5n zYTD)$@S;#XXKQkyR-Uz`E|ay>v}Jga$m~RioES$@bze)XOa6=%5+x^V3B^d!5@H|a zb47}Y6w2hp`7agYSK0&q|49eHKPCQ`4v=R5KRTEX9|MQYSHsGC$pTs zQ$1UJRV05M&yRhfS4)bQ2yAWvp@#e4GCluToExIuQ)mS3;-K3es9ng=K#-g)PD{_C z2)mhgP@XsP{VI&RT9Jwc7&Of_cU{RzgIc|%DV$MNU9a!)c9VllabB}!ln*C+UUVHS=R2ue=)8k`x5e~zj^ zbr2Y}vd}HcFLQJ<)P!&e)JD}Hq5c59kB&Ks9r(>{=@&;^YY=^Nzz!?o1SOm?@oz3N z8>u|kY_Z3}j$1a;oxf^OQLiMoWc=$vnZ8^C{U@CaUPH+UP-p`=jV$3q;)|5E7*Gc? z{<|zwaYdAjex<*uDA(s7oKPu@N@HueOz=jx}YTEI5>PAzrs%6cTx z#{?kju+Fd#Ca~2<0EgLZ_3!TV?3QSXRy4WZx8Gn~9PdDd59^A9B9_Q}baIv0e^@3J zySS1CMr_8igf%e4_o+UFM-PiM(3}CUFOmEj(fdI8_3*72A>7jNXXlH*31y7&q_3F- z5X%MXWtF{A6Fg-0%C9z9KK>@<#=}*M)l2&`NfbtcQoi#MFbX2_Zz^!)s{TguKczjW zTWIz^YO<$88>1wp)W@+2d=GYh$=fAaUu+!Y8G-=$djY*Yc zTLB?h!!|CK$&}`z_)EX7nspYrOxP{u*5i+ln4xc_;41a*uQ#r{+!%q7Hq`Xdkxdo`9u3Huf6R=k>-Nk%qfMJZiGX@19Va{~x~IF*>ra>lTgCv2EKnI<{@6W2ci;Y}@JB zw!33>Y}>YTs^9nAbMN=#+#fZ@9yM0&+Iea}*>kNm*PMYh`jnh&eas4~bnT^$ra$pn zg**1;HvUaXV|v|k14ZMmhT{JEOpBR;;19vON;BOhGAS(eo(My-!XKRx#;B7siV4~*eTU26S@QFL-Eu(G7ZmDxg9qdxt^WDle-tK z(MgLwE4*vLq{Nz3#L*4ZiUM;TVkM5Nlfkh>Wr+DGjQ5^ub3XO`7!5f zz_r3+uplyzP=yzza$2EFg7HT&u@6;Swx-%ifK`mAh+XUK_??zvf3za3< z-|cKdiS>W_YHKA-$Hg!lL4-JxT!$UtB>;>4qsnd(`5np2dn3UvZkc(MktIun8ySSq z%EJ3su$TH5NmYO4&!9{u_NJv;6!;}`V^ySE>4(ZkP_vJ{sQmsHT7s=)oTK~~8zw?D zcQc0tT{!)V3D4%F&gT+vj}T=jvE|#pPubm9R3nhdlfJCluS%wY+ss6ps)WW=AAs2g z&@0g6kJo##cG>;iuucA^()Ncw^4>#8!yjE+mXzxWd?)4Fmr%etcn?d#I)S)u0>n2# z{nIk+H}!xAiN-u8ez<<_(fL3ZQ{B9>Tv~31EL@~ z>Irz!QYz5`j*G!U>V}dYQ}n2_?*KK`S4u@jKD4q>*)aw~7XX=r!UETB zfix@0pNGF3NeuolVcgd1c@DAh9I*LK%E*)2Fz`p-WufX%$r%&&<1y8KFPY5we&dO$ zp2CCQ`=X6-acBblb61ret*15*OXtVaqzUMFvm!n8(114Jue`MJIRQI7G=1=P@lTcn zB^cfVYXaQFh!!_2@GFX?;YC2moLC(r0c)UJd^qR#oZF^pUc1SMhm0}I*A{Z(2f!x|{xx55eH`G0U{&jyM!rjo z1#{NQ5cu@8jghxM{*-zS$Lo`~B@il}>>%~s#ISaQ_i<-z=s=5CISywJ)BP*m418p$ zFp(d4GbN9ccOetUzsIgmL+7_kSISp66W}Y=6Buw0$_5c3<)V8yg$t7B$A3hv(|ROT zKV?4Lso+m9?Yj$Nn*u081Y5Y;QM9)#MjlIwCjX2bSXWnX+c@LxkvE_jD?W+RRAOb^ z8d(b8y*W;fQQfqq8J&R(k=n(c*EZ}on$FvzI z=I>=zWYl&_C7_H{3{xM45CDPIq&c-y7j1ZQca@ayY&V*1h}h9 zpJw%$G%i15{LeI^%B2Xcu(n0pgazH&T9+k%3BciPk-XbtGl-h0Hs2^e`}Yi_19z{$ zGXvn%^L2*N94%mlSN_sh@D%Yx7d{LN6`v!{0A4C4Et>ZF+r3|!3*6Rn*0Rg7HY%;X zgz@zG-i(fRBuEtN3S?dgDztIdPmL%p0`r5g!zAX^Ww_DDCKPKCGkr8a%*ZowGu6=W zCcrbBx5d`osIcc}Hei8pw<%P7R>uqXSGpY(ims!H?pSsn6nSU+z|quowwyfg!<|ee zL7o;u4e{mncB#;w_18{qT#l%CI$yX{FP*&S@3&7gdUDinBBlHc;^3PvnpQrYMAa%E zp4mA>;LHm2$$n8AssxT{p2>K=fu{OA| z7A2_ zNNj90Ij~9}_3ra5VKyMr_x<+%Q4;*G@SR^QHnzUR~gN#`c2cJ?E13O0JlGpkb)5Bq_p$Rf&I%skLN@@JR1Rx`^ zVbB|&7A#rTTgUBe_`ZwMwoG;4B^JJ=XxYPa)?qq1EOZE(6 zd9_wmx^U27`z9^i0tLyL%Fkkk*eU;jb2rwVUxJ2BnkCgPKWc@2n3beUl7+ogdpMib zJef7VduBi-`Oyr~AR+?3G}8-;xQW4~b`Kgzuq3j<(d3l_A!CwPX_G>ff_;EnMQPf^ zoKhL>o`Zy9=}1&!Eg@LEvY=&b$kF(BMRI8hSb>){#Ka*)*!yM%6rv4C37)(tr}Xyf zE*rS!SGx)s`;Aozd^D-Po~TcaUSD{cRqS;3D68l~scp%qb_KwN(b&SvjuHgP@2@%C z#VYS>081;xX@`y-<-4UML+3!(SAMXc-l{V_gCf7e4SEXJa0Ze4jqHs?{hMHEZ+i_v z=p14D{*e8mwK+JKmki__IU^V4$GT_Q3j<6kr$xJAU%AQzD%1S%v&j}vjyXAVUa%yI zfm)J-AsjPNECI0D0wguBc|HeLNCTuiJ+bQFilZwlyz?t|AykPh26OF=F-w>C=;0fm z4UXlhg=!dG8AfpzQ2*TW?wn-GVNQ2)9#s1qKJBl{5ylOt-N%;>5iEeRyPS4k7rdn^ zDOTtI?qTb1ZVNSbwmG5L>KZla^b2ts0Hm{Yhqf<1ZUP$CZ?$wP>IUn6a#7oDVuJ44 zLy6lVbuux?U&}?k@pH^9d6IJi^%L6Ub~{#ZA|4*tBQttnd#Q0`Jjf&WLRDphG{Eer zH~zDCc3G{-4HOI0PcrK!V~Y8Z#U>5*Q&V*!n(|!*>KO!V2F+)sx?&|*=eUelv^vOU zj`+g?>(jqdgz;oNi2wT~xDiWp)E2Ll=tQy}t4? z|F#Jd2~hiG{gvaWDW(mJll*R3Y+E4_oqpZ61(dwSc-Vo#WD4%l;{mI znKD9!=kb+(24Uc3<{|w%>!+CjZ(2V_+gWZ^S2oyy2x|QaU=l42`|8=+N)ksqBCh}9 zxMv2pCE`U-)-AuydSW*{^Q**Tt*fF?CHqNhvG?^iVWPI`hj4QW+eKo!SNT{)&awE% z!|=lTbqj*1IZARt8MTKD8Df05EMo{Hhn6om)sjk`%d>F*PMgq~;4g51wK$yxu-FqI zR_N%$PmrR!-5zI;gk8{BJr%Th=&7sgvWZjHSfi6xqNZ_`qfR%&2+5On+S06McpWIa zYHXPn*WPS*M(K*{I6`}V>P9_==(RR4L#~v=*1F}-n>0d!;P#M-`R6w|F^0?H6djA0 zd@jB~FF3;C(R1&ubd@O}aCHicGKG_>m}8ROF=dVD*WUT}WpP{s_h;{d2t{|=j={yfP zIqps@Mx#xieK79nEHs0qjAMwbKibwSV7}*+J)_roq@ANIHCaIb0qmIoobZ@3$xCg` zZ``S@2F;L13;9NKtwu;maJ06Iwbbl{5)HitS}N}JoAv#;eVaXD`#-S z8j2?G?D5m4@)q)P@B9AjY!`8fPZcEw+NpGIs0~NXXB?fAoLte!km|fUyYmSjbk&wq zLj*b{+Ar*46sQPw7_nlwpcYs6Kx?mW@E{pb}qWZREpe`LRFejcZCv6Yw*dslnQL~Wjk zb>3l=R#ia=3=tS4sytWcHPIXedWf!;~$ z3gMNoI}}dIjl0h0>cCT$4_Gw$dU5WjI9{ap7PGu9B_Bpda_e(tL453H8Jd;Zq=>{8 z+CUz3Zh2l@n2uE3v^!{=2O27Y+0?0y@$eyJYXDF|a<&jGFi{AdQ#px7minwYce*on z9&yw5-z^ydP>Rw^u|u?xlW`6^X<3ijspBES^A^JBVbmS5hjYR%3wGZ@F$k^XSCsK? zR*ec^7xgrvF$g0dxa`Ok$(xrjOx*+`Oo~l2I(>o8$=J@1AT3P;&c9-QpIX}iKN4{! zg=eyWMq~evljjfQ*&LF=dj#V8#Kti-Ai#RLEG0)d{% zNz@wNsTg>sZsZkWT}G1Nsr|({p#LYd7Cfeo7a7*x8$=yo{WF|q5ZJLhGOdag_X`(1 zxBA^s3bbOL&TJ^;^gk2EGjStEUB3tMo&~AS6|ZOQ8LVa>mz3DSL5fa3033XpW`(z7 z5@PZ&dhJQ9ENyMnobuzNIzg+HcE(8)dd3D0;U8G%cip_24rT>DWCp(M1RBZbKY+h@ zv>NyRe33~rA(hT`UYI&_jAyAR8!~Gr^1 zj(=H&o1vP0K$IXe#Wt}GkXd`#wE!LZtuLThfesZEI$A3amvJ>b9qs2P_@MK=2vz)q z#Lx~G8nH*-(79}NjPV)pWw{6?0@T?2R1wGIwXj3A9faOX(q_mKEb}@46GjSU$(xLV ziew~m2L?*sb>Sdq$*%Iq*p5!vBn_DhJ$%cxcQ%Xi1j}xe29gf=Q7`N)MTW}alB5L} zsTwytkphFqZg@^++kdzn>hAO93@eN<=#nIbEUmFRVcyiCC~i*1q?ogXW0$ifUW3i5lk z91d+8MPBQ(^sjDQ-?|d5S zIbwY1#S)dKQIL`U`*tz%oX_&>IE9C+BW!74Ke0in_iIW6BTMLoho(^oJE0bD;5>Mc_|So|?e6|QEw+J=FO*V< z%Z-UJ1o517uW@8KU=C@iYp^t+XYjdAGlC@tK3} z+F5sfsh3&YQf#4&dif-L(q)f_V3H3HS|+QA^)U7oi=TpEu2ZY%1jhW^>1dsp!EUL9 z(^|4}p`lX#NvYu8gam6emWvLy^=cezkNU_m$6OF&EN@={kA0(Ecoqy=pHGjL87?CIUL6F&O0I|-_d|K zHdXcfyZvlkp=RbCx}K+Ytui_)!pD+Y@1Uz6tnSXea+V1A)ouzwTWO)QM=vxuKe{KB zs&rvT+56qHnss!&NECSVSNHoA>i`~=6|ig^O;T}!zOc&2eN_n@byS6~^d0(LN+7D^ z9e1F@ZNFvOYcj9(TO^)SVW&z}_KHo};Lq zOL?jCMQFm6?O^-FP&KtNOYk$vT*BM3$uoC1aG?45R$~&s&Y0CNtx%(Hp?`6sb#bpi z>r!plzL$bNj;9wC@@I#9U>82FInP?e0n$+RN8hl_df=02)`G&a35*e^&>q*O%eA5d zKEKvR&!fi17gx3dXZ9hNx-(!Z+AOD;+7X-C)CK|;r1|9bbd4$s>*=2VvY4Je&gJ7| z2k_cEmTo{hW%6sPXUo|}_E#Zv8>3DASoqQ{Q)(A?+LK^1vTCQ7_ zT9HQrL7`(_*cQmp*H-*>%aD%C4jgMEn@~eqFR0kK^2p}&EM4*nHV){OI%c zT-b>qcDgr>3s?KB!=9(dXI9*ok=l^5XxE6P412e1HceVPHo@*wvjMv%wqC=+Wf8{@ zG^<%M+;W&=JF}#vc3M;HelvPL`sd>H8k@;nyN{gA}!dWS-fFX%CW{<^e) zZ{S7ftc+Y7#4J2)j2y&lEZoGb%$$s@Nlvg-X^MKFG-&~F;L_+^{|VvzPY5T_B%BKv zlIG+O%9I8P4^H<#$A}Slh?$91h?yitpo6o4ITh? zX4d~{NwlD^9S4-p_RISx;6;B&2?+t}?(OjoY{%~lL=Zr1Lb!hlArq>14VXlA-&*W` z|2beIQ}wC^tzEPXRL}0cYWvFD7`&)8H1P9+MeqMk{{H%uCiHdr$fUSY73(&)brrn5 z82tK<`T21YrrQB{eke`50vNUCeeMyFx!bM(cf|O*ifFGN{QKp^H}V*|$PH|a@=oIe zdrVwete*O%DW>=FmKzsm}8h zG~nXh@NfDxyW7(e{HM+rOV9R+-0PW=V#(Cr&rioU!21-I{lw5h4XM?1NAy-%jP@m@ z>I>WhiysMBJ_6U+K2uY;VOxytWC%UidO6_fmW zzFi&+4IkB>?I!PNb$>#_(SsrK*4btxNNs4O6jrgZixxOj_qFv%q{XaT&R=@t=iR64 z^4t~(fL1DO%GdaF)Q1k3BE+$594;G6jH9NCiG5#GKN)EDKONp=>0~L2;D(bd{mq^e zb#1DKK9Pp!Ssto{QyAZGp%=p(pcT{hA1}hdyC~4Z@hP^CqDjkxnw36+b>L%bN zV8*KuqTU^IBxd-%`q0*CElOgxJM#?``%b+A(B3P)&MA6|F0YA*D(6d8sQidbVr5vU zrcnyAx+aQWg$#fq&Iu8OCPhxRPZU%3dw^X7XI@MaoY=;HN1D zm}RY1WUr@%;K9!KIdLA4{j?sG^>$e97!69o0JiglzVm5UHY9P3T8F|4yQU-7%p`O$ z>--|9=jPr48o)!@g{;s`j1kYQoznX@ijVwm0o%@Zw5<7l(GwxI$OsMC?#zr%dpce2T*p`fc~|msEyc( zfHwL0REBYB`6R50>7X$1Jdi7On`BKGCw}XB8;MT1lpqC!sxi2QZsf0-0mV>&zECLo z{}j>c+keh~y9VOgCPeYbJUQ9zV2D|iS|A3UZKQv|t|psV;ul_?_CFBDD{v#`^oY{| z?fFj~PU>b((zJ};H&0vvuJ%-BSr0V{z)NmAflxU<12vF5E& zKrbGXvK6uAS=8|aPT+t|3-B_eeI$W3K;U0FCyEUWM+DQvf^8;wVmDgB zCxs5M{kJOHYyS@EMiuQwBK}(}ya&*ai|zk%Oz{=JwEo?|FOK+4b0w@b7s}^9Zx=tG z5GUINYbq9KooHKxjfm`wy@s#P`J20ky}+{64^u0(6V{g>a3 z7~s-Uhs%DW#KDlC)i{7D#cyb~XBbuEB2wvzC{E*>u|Dz67JFLQM3G8?|)0zSfKXTLZpnZu{-=Ea5(ke`GhkpB7iDKsF%Z^cQlI08NG5QzZq~kV7 zADL;LJ}#LEg>*V0xx)K|IZ(Wdw1R)X=OgS>8vr_jR2rUoH+5`2>|3JNQ0*bV%VW}E zDp^#mq}2|Byel4R=1+$7AUR)MJH?MQN^53TBl9z;0|i8sRxDso^8tZo$PwDNY&Z@3 ziL8i9;_1JfHM`K+T~#2Pjz!5G)U@u^#1Q@r4rQeN3M=P; z6j(-EE%+Hz%pZe1`1kqj+%&lgUq&^&nbD0QcWGQ-){pW)r(k?^ zy9CCLgb@-T;! z^lTobUxQjk0Cx=(2(d*}7FgB9D4!c@RJEcRJ+h)8BBgae3-~Q6PQ6H@xkM5|c$mM* zyc{Wcrf{a+*UWsN-8K;NB*8lmw+1$2I!O5EQO*Xy78^6BkP)^=@+K@41^zAGmu8aY zeY9t+?0+xnNz>ysLzOJ}Cc%(3>`l=e>jfK4X$ZG}t0>F&1RUGP16vj;!Kyz0TjMgi zCsY)d4XXDH443SNS{Y_@u28K3Qc>`f&fQ|+fS;BA-izHUmFsv2gl#nt`c5|C3bcHH zoUwlkiq3uQ9>)P6z*}m*)pvK`TZh!WRa1t@6B5H5j)0g}f$+_Xb8VDSsJ`tFEww@R zN)N@#?p9onpe)`2Dd$sxKZ>fdajbI?D_vQXuhLWp$K>qz*y~UE6 zcvT9P#BSw7 zRfWH0w@o#kzqX4)l}n!Vl1ABf^IDs`-TEVI6ctaMmUrau`)TyX+P<>7ydfI=AbiJ9 z%94i%t@0$X4luHZxx*E5Iq==rsDytJW#WU}x-y~Yh>B~}s?UEZy|PL&$QAe)UARkp z{3ZQm{*#Ul1+=@j++|B?f<*~%MDAFzkyiieX3UI;%7hs7z!t%r?i5~+G#Ck)OgGOl#T5arIDPNK{}LoD{zgbO*^ixM0%SkcZmfn-qLFNBfEdgFt2H!(7pp%x_v$&Mi<5#zv3!zvt379#qE~D?F(W7Qx z_O`h8sp7XjLjn=LI~bfUbak}*UVrlX$_p{w1_yRE+$KGr*nKB7pka5=8^p|ab>WVwAjRkXtV(IfHNP;^nKBR|Gl_jte=Pf zGq=&{1tjc8uUjnVH~?x;pp@X?mnRLf)osR(huJN8xY4A14QGF#xj2J{{kJr*a6*4G z&b6irXWjDP$J(}7|Dv2RK`IlJ%Gs0Lk0sKn|2aK1us(w zn6UDTvJ>m9vs-zzQFV1R&v@Kv+}n{HOIQ~d;<`z?_Y}=h#kBEw|(>Eex+c%J`-}*c&-`no!K=hiYF5JlG`2amiOAB$Er1uE6 zdKTV!SFM8F9e_~puOy!=bxU~?g+399*sBj!htOH3m&0C~Zyx;ap?>D+$-y>ZiFI8~y|WQX{f3dS_=>08^w|oE&_*2`uMb#p9~+og z3YOu?*~~RPE}%=b+hAH}XLB#O^hBKn7E>Zi`CQg9?tn*@&!2zJJP{=ywFc-8B314c zRjUgSp9|iR$3M*us@-ovVCO0}{zNIn(r0jYJ+N`z?ya`~sXaV5CLgDx99P@^>4R)M z>2?=~o|IwIt$3@a!6TI+b$MV;Yep)jwGjnTLV z`DqdK4aK4rr5bw7FVRm<9wD2d8wf}rMTo)EJT-cI9u4wdUsX0%eQw}$`1&IDyQB{H%| z<{Ln4gH>HnEkeY`n3G1E5F&mqX5l81T#-kPhB(mp^>@e0pFy+d9Q-o5Nlz&Ro_({@ zP)oi!ud!=2!qVN!pKTv6Zp@EO*wh^?bhy;}n~rP<_DoCWs_G+!PK+UYhI9QzTZOOj zN*z>WSM<=F8A+4#tbJ-R>`1v@JOy)+f+3L1~MuiVaB)B9Uc-t^-LO+KJWs3Vy<*d{`B-*by@4W_CGN6&+Q&jR| zXKI~W>j`11o9W%&jV`y_T}%7*8kqdcz9PI4S%aN;7fL$gQ92b)LBve%7~U+d(8 zTV|`4H}gKuwA^|6jm{&FH`t4#S5N@@DI@vZae{W_50sjrmemQI4?Tu0`^Uq2tja1;-8@t#B6^@6r`#(TSDcP#36Kw3ni z`w8Fs1=s2O?y-N|8+r9Pl(v%q`F~Lv8%Tr%s(5p8GXD=^!vc_#|NrsOq5>8HEWH0; z53QB|hm#*sjQO(-Z#c>+ibAG}*NnhmfV7w8>x%F4%hCgAp_P_qXc#!)hyn>DF5E5& zt$$t=XDzTeynZNzZ?yfh(CY1d_msr~@)~Y$fxL#talpGRIh*JPJ{Q+y6YSM1PY=J; z{$!Q#40qu@kILaj-7Py@NHLt@^4d|_)z*sqwS4H;{KefAQy2E2eO_~4w~d4Z{%M*_^Ju9ioSR4aMti(H6%BpAx+a}y>kNTpjocwWruqv!g~P* z9bNMOxScs&AV^;QDBrBAGy!FWf0w#A)&(_`yHTdgrF9iaLR4bo69uX`#5XEE95dy_=s(m?RPeS2N+FLhtn#9uxu}&M3~9YgP791au5HVW~ilXn#@t z?9fJo`E|I)T#dTWtt_G1J>!Zck|NxKsK5TPT>F}(wFhjLT}}GFA;Dx~Q+1Zs?)eez#>tqSz(A(E0H^rMu6b zsG%N&!5e%1fq{(IG9ikR+TNygg%3Q*q%e4KqIpSg5%#7453(Q=2=g70Wqtu#3LG*R z@Sixva=H*}9(*nT%xiK+bLdkO&BV@lji2tzl8wG~IT{(z6#})pnC*XTC?C5J{u|I2&(h)R+C|+ z=mCBUQ(^K+q+@Ix@XTV9oBJB6G7$~=ZrydhzzBAVZeRozS;}aG&>Nul^=9RASe2`1 zTz;#^Q?`%RQsx6rrSB<(1X8<`{P1JA@IXZifACX1npY!NLW*ziFRcd0%^XdPtuKJv z2lA~cvUH3ojkO33UC*#AHtb9Y=viIgq*);}q~5NXaA zLbn=b%TB*vUYn*vt?#fi_$|)#yRg^}_btO{#@7LBHF9t-@vRFyWxuC-vU;H71&Imk zh$rqGl$TVL$FmDD+}_+9#e9rMiz;Bgk?iF9j-pdr&Z0Jnl7i(w?JEMshEeZ$?nf>q zB22&Uxc~vz5%z3Gb2P+^8yN$b!(j-MAfC5-m8xmF#-6rWbmqPMoZph+;d2COVB`GK z7blr}*_Mi4djj8m0!ZE^FOHTet{}G)b!`Vqz-TROQDsTQxbo}`xP6PV09uew-9CG; zTfw`&2v=gy@)@xu#fRirC34DlP3U7$&U!z@yKgpHlB3kqa=Rrk6mm2T-Tibu`wT4; zr)x}tDN$S)4xqZHoWTQK9W))-lw9~py4q%fb|YXkb|ItSQR@G|%bO4=Nx^IX3B^8# zU|BXF5DrY?-z23IN8eS408ni*Xr3{PQl{I>c_o~v1O>j+GKh2J!Wss?b=^W^3wM=r zOgz8A`t?&mJ))$xk3b>edOF>Me58qj?NGS{PMMtri2m#Njs9t0LFuHe%2<1*n@_+F?j|$xQvsJrdx6-}=*#0|e<>=g0$;$d~ zVg7z!VmcJG0)tH4(0dG)#!TqKNhA_v~X!%<;<-h9v|K8uEy zVd~8uoIr!R^1Rh9vDEFU%Fi;hH^DKY!kN)8bnk+SjT-4HHf(}AY#$~LyhGu4ghO7< zqY8(ME|??jc8-(rZRx_vKe7gu(~V@bJ2DXj>uq`r1MuDLMlD!KQQ(USMb)*~Idj9I#2=(o;NogN)KP#OTM!|K?OYia$fGYmiNFIfB8pHY9v z-DMP8swKO!yjpZ>t0aFc6B(JwT!dNrSqCoH7RH zNVy)dbDXg9j?Y3(F`HWNb~ED-O?U(3B*XFY)*LfuLVScrM zG=_F}_`q>kRXnrOhFk0Z!fp=Bg0msx<90i#Q%P`FmB@_yfu}e_Z59rV;p#Z`!269Y zAMA6)5iZBjV|_yiFIyr^Pif&M6%I!nuOYgRCEB>-uvg^V3>Oah+uSm;2pC|Rtnx39 zMH^evnL!zKfBSDpJ6;K%>zO@jGsf()_XFl=_7E4x6=4xg%}{=1l|C-Z z6an^>%AK*;=2!myn$NAU>T)R2g(*?r|fT#Vgsk z*BXhyLe8l7NBu>lmNru5QlP@)OZ4IEuzvRRVENyu^U2m@>| zWXYG9)ZTeqiD!-*_bV$;y*}o=0@CNyt3`;@#=5QT)9Fa~-N->ii2{_QkW>8FN;wae z%dU3(!wL?!tR(yq%9Xdu)eC0#kM&-A5{vdA!wV!F+n-IPuVOKZd&xBssK+I4?GC}N zW?Mw74=3*%{QECzp>2R+)w21QQI@MY&#VdEATsmGN%l;lD8Yl?BXM~fLB6WUk{;D_ zndYnZ6x8;$mKXkoX9diDCjM?F{fytu+cq%a7lW*E^%y|^?GyFM7f7?j=H5@zwXV10 z_lBA1T$Am&oprXTl_t31+Wk4SoFs7TV>E$WF^5k#a?v?ii&DVBoPW~sZ}5+%pMK)q zd2&!z!}*~d$vqUJsZsxif9PbUa;6GAHh`^U@iHhj6AUEW8G8G@A%8DqZ>3mKOa&h0 z3c-@16j;SYVpYbldn#jO{NTTHg(__r)TS@Xpva-E1i{II+L(&(Fr>CwV#0lA-YCT~ zrOsM@LWAQY1bbshR5PxuN*PE# z?$Ne)_hsnQS^o~{iWQ+rggh@`)MZjWL6GaW?(G4mBd}7t5ROPP9EpA8e2DYz;$OAj`7jN zg6*+U+*DgoGvly%j207Dt2^ z-moeRh5W(_8o2nD22uEb%YBaufw?a`GxPtw2$k_AEse}Sr zhp?=3?aThcHrvMGY%0fg6v}&gbg_2n5FV#$WYcGa`vSpKFfT4NvvnMA#v7T?tJmYc@A|jC%t%&pq0m# zevMAA@O`gTmN7rX&KC@xDekRcZ|)H=P#FEYPk{H;z-u1wz0JtmJ@l4bT^;s%3b|)$YyeBY2hBBA&&$72dyLkL|#p} z%y=KM#kw?j?Qef;$PfgrXU|NZl<5|zjXA6-H5o@fW6D>G(y<+;dw1R+>@1W647jWz z4@DlL1Dx#Xs4{e1yjddZs{$Fy+o`lF!7AFFrWdQ!%m2=8#t9@=xmKh~p-D55=#Yf) z9%;qvq`jL!xC#G>y6VG%aeAraTu`(D-u7=PQ>q}J*%VpXh zT#UPUcIn&8yg`2JEj4zxjup%Abk@#I`1}kr|U=+dXJCWBaI$(g#O_Fy^&nb^H z?a~aU4v2bPXVmO$Jb|*^=P8tayWWjIxPY9H$u-2Ij7uBKf?LLOXOq^w3LcfVP%n-1 z76@0(iizf3J$N(gKAqecuir}(Jv61Kxsk%sTWc(l8}5wgOY%R)z{q z@)SRVPCOQ10H#5MPEoCrEbWF`V|<2bMHX}S?^(2#?i^8iru_PTB~TP|E}Jh4TuCPu zqO~L8T55`(ca0)8IVozH+l&q4SqoNv#sbkAe=eZ(g>mW;Qnf^n{zU$KmbkzRYBvF|>`a4hZgsXHfhTGaRpamwNdu$?hhWDE`wMaQsp9B;w^a^tIe=0EF zjtTyOoPQsY-S(UTsWlKUpDmxLCM*O(rtEI4mWCqd|DdD`Aks?QR0a|vuo7RJ46wz4 zEC`fxnc4>YrWKMJ63eTQYIwEOAWpu4W?Sjs?b)hLn$ zL`<=I%VWakoK}sddMgQ9IylFFq3r&Hn2tiur)?z5R4QC)+4hF42!cs0k&NkNX(fRd zYp^T`tXiEA`~z=57fv{1WQ6Ne@giF7N6W7#tgW3ZuKGLV@0VdDr0=2oit)*MMP?(b zAzTTUKFGBO z2aK@JZM>A%+1Vh-0LP`wir*}gyPmJ?*^gT>ozc`VlFjRn{9%4bG1jBuR!D>^X7yJp zIZGm-T(vg?t#R3W2W03#MiXIPnhY|-GJAh~8}ehQE#Qf#2$6HzSxcX&N^tQzuUqUd zj|H$iGj%lB2za%TMe;?_lIKkkjVm%6jlN}`@h}GVKFC{?U|ceEf^OQ76Hl#vSM%M; zneGjHSUT;Qa$^d5hkB!M*v-lZjR!s^^*nQ=Wnz}>no;D$4EW;mkveIhowL~pq^?5f zL5?Zw1ONp6)^=3sG6eqYtQmxym4588hmxeqDixxb2bv@)(_V^MH_W=~=fqZNS^+4z zR(roDl?d*i0sD@4qajjC~j4X{|il8^k&Sl4uK#bjAx{QO^l6)&^+_efhG-&-;ixvCb;{V=V8-~&*i?M@)3 zVhI8|z;E#2)hg6Wrj>shbP$6SK zsNPOh1eRqK#1&~PZYdKmFk-d@(3JzU<0^_S{)S3if`J`=a-qV>8^wF$Z-1U`$*~6+ zre)e?o-|RTk==RzBzvGjpfOBln|%A@Ib4QQEL+ngh$1(G4rD~Q%IJD68@B?|iLspQ zeJv1F6J(oUQOgTRbd$8Kc;jWwUo8{h?CcAWg7#4vU^Hcx5ui059z^j1jA)N)3JUg& zR8#+02=tAK=jWed;KliS_j%KSufFQD*wH3-q=B+l;^E;bYTun~pK_;l2oiJhtq?Qq zlzJi>Ly#_4TGv1&4tYY2k68nb;8b16pEK9h-Mo33Dp=|Ws4&%+TSFCrdo@VSEXH{6 z*(+h0M34M3$L)VH_RhhvMcw;na%0=JZ96x%ZQJhL*tTukwv8LxxUn;N-|tLK{RTDj zSMRE`d!MeZ-g}+Z&sv}72_Z~7e2q1}lPLX68`yogO7<5E{gLD3%6(h08o7TC5|D{K zE9_#1Jz9Eec{3qUHU^^H%*K!@VbObqZY1YgoA_f$E=Uk=3?xy1;c}XIZ{LS6z>7+1 z>_hXSq0MdjTsK!c8xv1PPUU7UrvhonM%Ji2T|zH9-E-Q(p~d7W%Z8Nn#ZJ-AbQ!XN zOC%G)rQfxgn0cXCGc*Y;-nWW7Z5|lUN?9yhU31L+^WGHiBQ|h)=nE@13OV6qdZkp3 z6A1S)Mn?*yl-C%3v!Tp!NbLH!7PeR}v#I3*VE&S@%0S4-(?5!u+K~9Gb`8JGu0Y zwA~zN(qgatUjIl{o~j^Lz7o@^c2JRF#M#CV6}u*8Ag&Q%&EC{#mN}h3Zs2w#@IUeZ zv^%sZ?e9ejLmy)X(nm{>r@*o2Ems#m4_yjk)ic#6RTj|;%A|L|-k~fFNOGV}*vfz9 z53mRL1|ls8qGEaPJMu7ak4IvuWI0nbr`S2}9|Zz`KrKZj=4ZnHC=d%g6CoCl!b-X5 zKi1E?%i$8LUdhvW)9{XPT<;;9KcS4pqESR=<3|$l-!_~3sYd*Xk8oW7`>J1u(Ydle zzyI?!X^DOCSVPRP(?<62EXO18*t-fhmg!k|c7_{Xo7>wuhD_l9Mjvik+;7nT2|oy2 zt3bFEh6t_noB|x2xVRI?(D=_J4OnqA$+*lM;mzQYTfQy*2^-FVgFVvhm;s%QKbP1; zreuw(`~Bkl%p6+rbo3AYf|>(D@iN~4v1PqB*zQg)&3w07!)S&soZvY7p&gZ+s<3HQ zy-`{>m`A!fk=oO8x#}uKsV=xs>0`TRq!Ln^Op1wpQ8eii&W%~&6Fj3bNx+m-i_Gz? z!Qtosi6-O~K&KxnN<;)l08&p}u$md*@WVg{LYDmWG;xZs^dF#+Ai%$zTChj&wsqDQ zUWb$k6dsE{Hzue_$yB>T_Q%m4vzBs$mO0039;u6e&1@*Ach8wIMYCd`-jMR%X=>Dj zWzZm(L*rjNCVb8FldlN58X8<>L}0Yg44t|a*W+>fdj}-}p9X?Onfh{9rPTr(=5zwH z+j#H_$PM}h4}!kq8(@T2kffosLQ;J>3dfr7m`eQuQLumx(#N-eEM96;v$3jzY9#~r zZe6EV1SXxx`lZ*WkDN{}#_9lBTx}(=eHp^$sU?c2P)j>hQJDGuJccQl$ofBD3e?J> zePAt#2FuH~he#bH&;m6!xMgjhnnklL9XQcH8!%yko?#?Ox%Jzo|{q6l^#dg{0)d^=F@H8tIPj zz>_DI+b@`3sizUCwhjMp*}g&}*bjS-^?%X1uXNY#Oj?nASJfY!fm+)c1Q892H2%k{ z+7TDj4T$F(AxIkS`Mjr9%+rh+U#L)fS*HSieDIUKx9;{H4&hsqfgbSvdX`#R#-u|! zTr0r)d4-Vr4SKbFj>`W1DNb3f?BN$K0Qme$Ao$7i&j3G({?X`nh)Gf1f(|YR#!OSV zwtvLlOWsC7CEx6HDYSGD*`MqXQAa zwLx@dB5l9u(zw=XPcEOHe2!Wjd0c_@80XB~=HkT$KTfUSR}t@#z<`pP%Rcf^Jn9+~G;-2gmm} ziiDmSRfu&i(^BtsGn<9xEJ1FMuW9O>r~tUL6^vPGY(5{e>nr&hhLO+5=+Te!7LuRo zOLJ5?Mx3XI+TQb{d}{2s-`n*;Hf!?Pq6sqKz;qU@RbAHyfxmes5Hs%s>KA*gw=Y7} z@_M;m1wbjJwxLQ&rY-0B!}}DDmBI2 z;EF#miy8F{TeXX`Ln2N9L=x@B=EsNN*Ww`=_O3KYzT=7lkwd~h?%pRW^pR9M`ET(= zL(kuGh?WIw=_${cA@qY|8{rFqjn4_-j2VZ@9y>dBq=RX2a~y7K?pXWW=ppGmy}xcu zcy);kJ#bV43k=~{_}q7}?452cPpfNVS>7C^Z-|{^uT>Xz$20>oIJ+?>+A`AyRBUdp zD8WV;TrU4UCuqj7LgbEX>M~>Rood;!cW=WBJzk1h!hdxSuUU3a&#YhsQFR6w%YYLh zHm1nF(gay2=4-?is0V4mhjJZxgw0x;;g~Hk{0ydBb57C&!#e9MDcubn#ZK8N4?QU{ z1Nk_&+85}YSf{YM6;99{`?CgZOrg~9s@{RG_eZQaUxUA|&gPW!?+nOzw;Sd-H-6cg z2YQ3)7)rZX8BHUv47Tbg;iv;Z{iiTOHpl{OwtSo>aZ^fN01Wl`FiDHzx41v=@dsEw z#lUEX_(mlp!!m@he4EffnbRya$OV?2FhI%ZMT`2aLikhV8i-n@9C3SbT{%X(b55PR;$MjvU z!#eQUnde=S#nPmn^SX8{nndO-{qvHQTQ6!cpUKQc{GvJnh;R`NdA%z9q?4;+eJDJ( zYI5qxPg&3k>c!q`v!w>)(x~#nepELqArJ^RT%SkpXT=tk)$*&zUkz()93v1?c^}D8 z+I8B@U2Grd%&xI92DmQQu)%UU;!wBWWjtRi%h~iF8wlZyyeIhO4NMyR%e;W{dx;+z<)2eanuUizR&6Qiv;u(*u31iQkkTB=54^AI0cExi-pwSXvWLREjDWS6 zz-Qc-Ftiva9A+KBQ1v5R+{M{pbcK=;;tCq|ax+ALT#Q$$PE3Nk>qA=~|NQY{mpP-f zS@H2ctF@D>L(_DREZKNZv8HNuGnFZEKcaA=YbIr0GU^)FqCw5gRS+M;y0)1{auRR) zI!8JCH$raN+&4i6(#F95rgp`OWFsopWeRT<5Q4|zGC={ru51!j-D+iYbo=~cwPkXU z{={oXkLj_^@-6Zi@&h{6zR!1S%6x~~9BC7{3Gf>Tel-EQ#={mq62&23A9)EW<;NK4 z8b2jX{3no0rF3SaUlO|%*2eQ5vSt*6ck-jKZ?)j+sP5^%EX@At4uTwF3%Wvbby)WZSna>V-)qbR7%DJT;%J5v%l(?g zbNbM=wU13oDYsop5^WKqI7WgiPN8L`=VdlQeAa;1PKA8v!N z8HiG?8=<7le#0ePucYSzgJGaSqfJUro)BKp;5hd@L~fZ`YUG|j{j1b*B99Ad-@)~P z-wvV_uLz;3$Jqk=w~6gn&b%=}_%PEO1E5HJ(f^4J{L*YGTsJ3>2U!N(yq@lMj*twd zhuOyokbNAY@x{WZ5vm0iKkU&ZwE_np0mUR%r~<(g7?zh9%B0h9qomdWAkq0j|I&B? zljj4?vQ3K^HcTSBLI3F;j08%=7p)J(id46^7*fScpW804t_{bHtR7&xlrrScegfC*tE96>>%VjITi^x?H16uB4Hr$Wq|k&zerg&DB+6> z`oT0PA$sN!AF%&@@$h5}P}CXD2c>;55lSD>U<6RX^(!Ip=?0_0VoEX);xGM30^!F6 zxt%{i71{PAK!0~Ot4x0b?f##4hs>k8P^!s<>f5vgFE`vs0ZLGT>}&sfx?v94oD7t- zEe{mI&94i{Xu5&~`VgLP?CFoaQ^WKJqK5UzzzYfZr^&B|1gZjx3~#gFf($IYXU*oX z(A|UrLKdFcCFRqy<)lS9kz5RX*T?d+iwp!nRwq={7ubdYnil{)Ad;FB^9RK9 z)rokYa8PS!l!OwD=@BlkN38_6BDKXRJV~jJ*V9yr)2;K4R0)V7o~I8OalR9?!FT(d zLP_%EMBU4C0@Ay4%BbzRlNaq7e!GqeQyQ7$>^(SN$(4+T!!VW(vzntY6h?(T$=kc_ zwUQHne)n$235(ElMYAKKx;j-K$b5Y?LI+!V@g%D<0+XAlR3e+?Cttc+?CwFDP5myU ziGhOa>bt3mUk?L{$DmEGiG`Atl*BezBd4OdVY@eU2##hsVbM@;U1e4r&NX%|C|LX7 z&9(BsZ?2!GtmPuos&ekwblN#=RX`GzSm>ZOfsV4N15WPb+{($H9Q)jb6CQ|W$9Jb^ z*w&Kvo`GCG_%D@I#oNaLzvr&`8(y~x_KLlVB$w#|3ZuOl-L=&Zc=-P9s9&4&v+xCR ze6fb-i~OK>!JkNf8Zn;iJyJ)K)_Jy6tWkZi+*e9{w4}>r`(p)p(hUmg$ zjJxIjP8F0tt1+o<@2Q%ta*CMcTWZZuS%-sMoK52{y?UMZ$VP#pI`7AfoOvGGyZk=< zn1qnqv3&j9UT6spb+)Hf(0h!&%_o=1?GU)_0ijb>w_P8{;ON7H@dg|%1Px_qX{=12 z@Voa4j6zo%bjNCbGT_uYt)(wTz384bHVE1fN>Ae6;a9e9?46s zlG}#gY0i6w+DT04yp383-#MDF=KRpU{@%&- zc0GvJ5y0)mzWCen+1^8Q*?5sO{s!n^G2q|{koWoiav4u(+w@zUSC0mGm!1zza~bg<33N( zkd+$9KoT5Rvj9X>PbB?2u0_Q#UQ8F+bOS|d#f!$!lo8?q2D#pJW6g->o6VHxU1BZG zW<#=fK?e#@$NNR;-8Pya^1PsjxCu1Si3^x>7p(6QCJu^57?w?{CobyCu0umiKk)z| zq-epp@8P+!*<`Jn(b`ECm^jsk-h}ebb`5L{MG)C+!v<8LgETgjvcb>%UEV_3X-w#O zKWavoi+KLKcA)X>_2m>cfGZ%#WW)m4kt(9tV$wv9AGg63CG>Rt*#pVrn@;jF%Nm;Cfnw+bf%C43FM7$nD7oTB~tRWCY&yKyGjIR8_H8aV3k^wZ``tkIg8?1 z&T>SfCMNw?@y&`=@bpYaaHIYOQN%{`1Au7R4lebe|0i$d_EBi zan~pzMNH>s{Ivsd{XJW=|8#Itx|92B*Z~O&@bU04xMTPIxHNpO!SVS?*rY-@YE*ojWchZ&uYX0a947Z{xZ5v%!cleW}ZR^-xh-9koi|3VMN`rh0{rtPtGMB~TrN&cT5xDF=(k{3$<70`E66YSA`F-l zCC;2-b?UEu^#9ao&*_us(*KCaNmK%x;RG(CywQaiM<+>6N58W%fy3G~gN#=kwBLLI zM3_XFQTvL6{ft(IDeq^M_)p^ObF-F^Ef%Fg+Oa_SFy>B%3EF4Wo@!R4+3Ps0i?r_4 zYs8P|Q^42BWP+}sx+n(9kGbZ1o5SMHMro2v`;_hBN?Oqx3NQz50MEFA;((0ei$WyWuI1!Jy9k>+J1WU@0d3BVZynL-|YFtL`dk3 zC>|{oR$B2c3%5!)DYG7UliaP&1C~^?uzO7pESz|7*Y0A2A>^=G8!&UQO)R^Aobhf^ z{&re-W=t4PXRs2=)F zF9W~}l(DTQA_=NiB}4@24poj?UiPceoZo=Bhp?r5vsf=JFNEO)q8~5!Bk&FUtOemd zEoWTUS6;K6bbo1wcB^j64){?6F7fBlvNsITZ6DvORL8ASJtxYXgKU=v#z-!3EyK}Q z*NfKOW#~!EANQL$ip2@h_CCZTTV8p1;vwF*`RK>9k!ep62tJ|Rt2F_GDO{7HoSLv9R4moDUi!}S$Sv4(`3=c$M`Ru}MFXkx$o6tq&XgCx` zm-Q40KVCbdB=J?lCGn^o7ZRj2e3MEs^M8?jr{RL&WYK?`q2cN+`LMxW;G2lFaEOQH zA@V7H6gf%MpNUbiKNB@MEgyTA5dU)zktX(`l1B^FU7nxbYuhkXf%KHVe?`E0|AR?N zkDrNgfMfH9)COeG{w&5~N$kw#OUXLtGZ;y&yKm{Nct;1sm&Nr(8!*13G5g+=haz*#xJ5N0Zo2B|a z9KPrbaika#rsLf|_B0 zC^Y}M4z36lq13)?=0?Gl&J!&)`R4J?gGwl7Mr%x%iA)+%pPQGt7O(FH=-aVN<%%={ zCz$g9h_D;;T}`Pn28tIb8WlO=h&sEPKa!?|eM0Dp{kY7CgSLJHE#nFbW&$-BBI$9f zT}P<@0wyo`wVxE82ez_I15pU{Ap#W?`FMUpQw)kC)N98IN1@mLa}JWkEv+q`<4bF9 zRnt-H35ZlnFL#R`6QSe5?ch!D;@uDa8#Q(XaM+QfQy}c=R&4sp~oC*#TZQt9aydc z$jnJ2y`z$?J#3Mo-f?fZJvuX*?_a~1Ckm*( zAq&bQoF&3^Z!#>?oJX3nfqCVpwa7!lVm+Z`OS-r5fBR`ZO`01puaT$!kSKTM!)hP` z4>wYTZh_RfVGFhvQ~l{vXtos9b*T0XSGaX^jhjxPHKXEZVeGF>_RDt`y$^H*Q0vOb z!*g^kbcvdKF7a}mC*$`2c2J{%rG%=9Y3z0wRU2krL3CP^KF& zWh*5k=Q*YYrf0jf>BQ9rMo=j`>KR%5lZhtOGgmfRp?xFlES|aBCZF=DCbc*4O*DMq z<_mWpX7Xg#k9+H`O>Jbz3d)#(?x0UM%kvx| znQrsqO2+%r=^-eaqSn>jy=4h(=;1wpl71LCoO3d zGq8-5HFS%fLAYv59_+vkUU5V4uu7~S!W%Rlc{W(WvMj#V>Hm;xr8!2dq?7Dm41RDJ ze72w~AuCOI(ZD)Cz>P|{_}vnSxkPY_N79HNxW(BEW+mKz&i^YbAZ;xpt~qgo$EKDm zi>M*jBDi|Mc{nOZFnT^z5wI3sxCz-JBRcxPqSUgdTzODEqbXx6)ryVu`I`>KaLueM zwXa=(VH8HZ2?c79o`^jLTu;qG`jcZs1*TZwy-8;lR<%3s)8_9 zzLk2Hl8GUY8-=lsk?H$>h=yv4>OZX&6(?#6R<>Dyx)jy$U#Ir=j9(;MY3}m`E9&{Q zQGZ4x^E(mMvg-{dncb9Ix#8#G5rBSR*2bO$+`*Z@PYDJBjU`BjJO<4Tn0I%-p=T3e zSMAG^gpg`>A)9V9edOwQ(sogdcxZSl$NY-wjrW|A8^E9m5-G_Bvl~Q+oSB~h3o+aBs zMS-({q`;48IhSrGF-Qz~YDUR-)A|q3fqxksAptu;Q7TZQdn#Y`_*8$Kl16--WPwsS zGk;MszJQ@}qBr{ITPe4xsWj21tJ1foWLFvk)FyZlagx`}ToGn9SA%IH^aMt^Q!Cmg z*DX?u1(W%q(BzHGeOr>9ejCs{Ss&k>+F8x#}%t$nq)z(Jq|@ z3^fg{5c>rx5J$6ZIuj&0+iujzGnI&$$_#ibSTXk`A?jdQH^(naBh#Rj8?rzdz$3|A zvykgekl06!WViLIx*(6&OEWuenKV1v<@5Er@PnM#(j?9KdxR~e6K~U`(Hm-}IbH98 zOl{F!HCqZ5Y8wsjbXRyqv$qw6thD6F#3nr?_x#ikJe2{Uy!Q1_g_~~tAt8ks)!6Rs z^5(_GZ2hMzIvhKrW5gMth9}1dXsS*ZI3k_kNNs!Wx1Q~AhH+zfuecP{Sa%O*zHZ;Q ze?c>n6PdcOF(cziU=TMoo;u0Y$wd7~R@wD}@inqK(ew#+&FWQ5n|NQBC(HWQ3&alf zSWY~nk!$X7lTyBFY2M#!$a8qkH+hX9CVVSiOBri9qoI?1DQ24Uu!9u^>>Q-5HQ`4O z$d-&}c>@j29fbUFcaHTz6D%2&ptt_#2r=Hmto}JdE{SX`!;d6z3YJkeRtgo7cm9jY zN%&|&1YZEEjS+1~u=MyvAcr4qX=JA`YbRgIJyZmO6ybUM^c$e%WAz87SLBs-OT6;sjP z<%=e+m(}o&u-Wid8OEVoXs7w9hO8R^EDH~*EJof!UqHi@skMqgDYtqC8O`O9S^0xx z8kspw=AjLfgyf1!rC*QIwMi&+>=JFf=eNVuvBya(jW;t%3p1x8B_*k)NcNpe{*r+S zb@`5|i3L^SR$X#%xUeA6IQoyD5KJ*><=xBH^)*7SCdy7E1k184+benMmm4;Sw=&ef z90vm`4fuD-O`(f=fz&UA+lZ6b)PV)C3^cYMQW_Hn=YM!vi>?Sg>* zTm0NaMFIx^0GnWW}^2M$A87I$mZFl13(O}_o6+*A%S z24}Y9%a4*)y=|g9AU|#eX&kEDn zPgpzBs|>ynMj>!5T8VTLKw(?bM=8XYoD<_bCq1}%pCa}`dSx{5bSuTaOUrK zB8KCT7kh3G!y%ew;`nWw=mEtz3`Ra=c;6_u%$D8>F{b_N-m7$7UZ9Hq!Q*83EmMyt(6>ux6??ItfH3=+BAQ&FLKjb}rL8i%ie8sN_~^ zdrU$w6dD!}OZ5W}S#EdEWJr)kG90nxuy%4MA;}9!huk%xJZ}SxT_+k8WzTehzd^bX z)|ON1z4x(%1Yol}Ya%PmL)I9AB6!!Tvk}bkWsTF=k zJnnE=hVI~Yve|<>!%W9iTBdvI?1yf_O&8K3-MWbr8sT6wf}GXr@UUR_FI{-cV(nouiOdl~ec_q5Y@*}hV=YSM_|}ekG;Nb0NSYC+_DSg8 zMQ2jcGvwxN8VoUXRoQe?^HL9a&Y%r-hJ*11O8_1O(+Wp^wR;NqFiHPLIaM_rD`Lee zHLxnR5-6%)A&AWudlZP-xE5D39D&R)bfGD?Z-+e&hQ!^Z4~Xtq-&tu3F&Z zWmvvA@x0?U3|=t(V%Ewp--jW)6~t}P2jC26To=oidleSgVBJ~MnO5>nfeyyD5CtT% zzW^}4neeh=w4?`fcp@~TaS5u3C8gGz@|xA*w>=Zd3(hsJ*=h00MewBgnHm0e(!nTq z@-ua(G|CmxIcc*&yviCPXrk_bCUBz=MVEx`q?M8>J`q9S<$4|kk0Fb^3v7IWg474b zcydZMxy+WOKRI#KMr$4UG_{6{$y6Lu4FI~#sAGy(Lv6M%2KB?;q?`DaB z66=S*yvJ{>z@ZoW8KYVypH3qbe-`g|ZBSCnbzB}9w7aJq>nZnv62&mqHb>hWn=oCI z#rs{;m>_g{kfR}E9Qdgjo45ezE`ZXSMdRipyIiVwQJ~NofR9^e;}QuP-`^$jCV*Xm z>n@{m85K7z1%z)$cE*?kld{-vR4hSDRGN6>+MzDwyP2RMOm@^4?Yso!uD7dumoFZV z-W{46R+W{!dk~{hAB>0wv_0`U%$lXc^%o;)3mYuOcTT|@Pb{+0yfmEAjJe<8Mj9qo zC@C3^cvB{r1_^vqj~^bgY9qW^NC5tj2IF=+KKEzDDV0CQAaeP7y+o?Cuh^0 z;KShl1Vg^Ru&CBBe>WJO7O!mvOGfwXs9~3mPiWfE$&6^$V0YzxAWb02fn5cwAA9-p zg4Q+tW$FI4==n<4scW2M&){+}ywXyS^{ny8^hEtMsHA za`$97jcFF9vP!J_azZ+|B@)oTkoxpXFK0n_&%IM8>lqWzrL6S-qKt`iR&c0bY=|VF zd-0je3&C$hAnKWE&tH#FWOrbj&-dS54SKi|uQA)=uiZMS#xl*UE*GwT9Ga($uU4z! zHZbkB=Im)K9T8@9AK7I}Z!1HI-eEy|gF{nU;v6;G zrl$sUM{T|Bbdpd!GauMc6RrjK?h;t(_Hj{%QghytWSZrl#a?8)9|ky^`px%Xy`?jJ zWuoBpQfkRc(dViIm$Q|q9$+WUfH74>@~A?V&|o4tw*A6v*AQbHp(OXz_>Jg>dcg#r zMvw_kZvPK2N0V0&2#Q|yP4ZUjS5-KUmTUkIQ3hcKxduNi)Ib6*23u4oDwig>_1Qmu zBUAy08Xp3Vh#axp^hLlBtbigv*b#;DX~S&D#RNAqS6BhKyOGrD;0V#&Jn3l|r2w$Y zW%hDb0>?BiJFrH#d5{y?yoF&IVVi*PHZ>ZygiSiC^uO)8Y5`od9E2%e^!H3`1TSF} z#mn{Oe_MoCGfs%bb5x7|Q~#*yLtHQ|m*i-SNep?h8>r}G+7$p=_4sJ;h7+B*jGDNN zOaeP;vBu$TarJI%Nq-fX74myteCi(ICbz)>cL0knER(yejaL_ngHFJ1r%j7Onqo;J@pcljA2R-#`bA zp{b9Bs(oNM$3FtpGDKCpf+5Wu!Ib4i&=M^QbVw2{GDd#CI883fv<(5B@eJdfmGVEUtE-9sWBgpZ{=uYZn zQM%hrd>$K=Y!*J?c499!%~CvZZ~vWpc$+sby<-0j1i=n)2F1FLl^VT1#z3pxnp?bl z<<0R=mmJuQx2!YkjQ!emJ|~KCzB2TJ>V~#FU-ax2!7yL%{GMl7m?*!B_qxThwA?O^ z!8KJeYY8??$4YTR4`ulGtj*HI(gq{4czLy8)?lHr$rcZP`THIBeR-Vh<9%aiVxO#n zvd(Ap{QCgFF}h<~QNXVR(&^gd@-epYyOwj&`&_5oZ+8sdQv_(4zT%BZ0E4a$A3Y^h z$aSj5QlbA+HjGTa8LiISby2JkZ&I!M(06Rysv7-6DG_A1Wh+t6R|1cb5_w`=jUEM2 zGFF7YqlJ8C7mF@U6Lw0fc*;+Q8=OLdN}ekN5XlP5{| z?}ZFn+p+d`z+fY`q?MqIxYVkR+0I&rknDazjM2<1F%Dh|VcuC^J<5bSUyu}qofwfZ zW@eo4-|d0DOrViK*1~ywr*bo&K%jil@sflDJXnbVp&Vv$MC-c8sXThOKQ(@KvT zg10un{b=?rVan#{2^CrCtXLpC94wXbAkKPO$Z~dox5%0s`2FvsATu#ZlV@tG$R}og z08+Ss=Va~0xgU#tPYIYgl*AEw%G3lHRv`q%?1nJ2SO4OlgFiS4>9T3Xnv%dT{U8rj z+%l6mi80BVri3Yz6n06LX3%JP{L%;t!h%wOXs_*GOQFWPCK?Tq6ftUlbEF;cXT*&1 zZwWD4<(HH>B(~bojq7UNV>nnjATOU>N8u{=GKDNQ0<2J6=cYQ}3O7E)YH{Jq(Z|~R z>z%lqy*=$ZL)zVDD<|SdF6~c8)FpRJoON@LQ8-Dia&QPw54?g0tvT-NM;6oj3P{!g zqRwR^fd`?JvlZb3*4MTs7iMs_k@3+d#IQ6a&Lb(eZpD# zrctc>k{#aQWa7aAA}d*yw$KI;9)195Em}G4j0mzm!uYpNt6C)3dd!DlsF}Es+AFb| zaRpDaP*>uq>8joKE8br9f-{ z%vP5^YNKqJw(6 zwzJ`l0ixS@7b@TId|8{gT97RbfarRd_h0;-Grh^KN#(xR6n6CzVW%TbP2I91_|B)Y zKgZ9sr^8Ses7yZYtr?I=6KR3$Ws`7*@OJ1)bf4Q~pgMwAXV#q^R9GFXXO(z!W1IZv zeAGb{FxQKH4U8wQ`AK7#sfOX+t@DVZ`UQiEn!jyoXX5PQWNK&&{WD5sJpdC)ZCV8L zKxSiM{SRN9jrk{y{&`{Lp#LAXIOx&;cQXAyZ1L8?Be1m&06PoQ|E0=W)BdOh?I)#f zn*}Ry(DyI!uQks)K?iBNkxVR*&?5c(7L;^EI;xCS4_$d|rWjw!t|wK}fuFt07W)_) z$hG%)5x5vWd)LSJ^9@sn#kddN`Fg#57RdfWsgYBgoh|9@MH+#@$UP~2IkDf#1}q5p zy`SxE+^n6Ieh1qXJ;`L_a!~w~TKj%-y5rYM%vMpRwh$zR)IZd5*jP^QPc8@yOwQ=z z_xPGo)R3cmHHPpfsujoqj zryb|xaDB&8q4~*t@oh#1rk>os1Dre1Z!Gb?-0rPCJu(yJoG{*Vy;ZDw4#@wbIP0yt z_0*7?d1^p5vpQ_RrGdh^;0`LkgdZ&5izvw(vT@q$QM7og&X)I+HtmV0AB~`N7@liz z<_^3umM+u0E#gL9I5hJU98N2O8(0ZZyTES2PoWklPx!P@i)3LY zyR}^ROH9f0Xi(}3W%Aq<5x!2EO7C+rn^w>2%tPYN2(R0@N5e6^#@}hlui04OSZ+_} z66Hg|v{(4D!(a%N7Je+?JI1XIO*95-(=8YvqSomvs|WtTH_W8tZHVOXTL>ORNlmha zqabK1U>P}Ua~bnOolHTA6(o8E_ERwcZM*giLXoyn?vwt0Hmf%j}R5GDi~}bSASR` z!)yqwt_Lb%)8+Z13LWVdqIQk`2oq4Vwoy7}+Z6NJ*PMyxX<`yFQpp`b7^8mF#NoI% zX-wmka5LzTG^JHBsPxpuN9Kp)Qu>eEuqyf~i?TxpPD4DBvK_MTGv?3$o6>BgcxlO& zz*!OW<K*w?2uu-8j;~3n3ILn~k zXxU50GW=#XL^t0u6n0#K|1!L$LPd{u8ueQUD~UDyiL-d!T`LLK#MvhEp_j<2hs~3Q zsB_zv-S*B~IX31$ynll&x)l-!(FZDG*`ycC6T3vHvT|~sH}ERE5-mH!Z{>__(@+eM zlt7>Y0jPz>GA907a+%mQ3_$hh{p#R}wZT{Drn_A>hf^z&8i5XOf#S|Z2yj^gJC`ryC(`*z2mfV|^d-4W@v?=ehH;B&SrPc2mLtSfqbfw9Z{d%!OIa6g6 znKsfgCRf`GLVKTXpyO3Ny^l#22tWb3jE|!35~93v91jUCS|3A|t-E}~oL7l@sgmZF zji^9BIiyRCClrMy3mdV4^^EVRsKn7MQxZYHRWZl1(I~BYg0mp<(Myf=!8^4O%z<)` zPa)YNty1rDyd7-9ohO`3UFYCqA+mD8Oyr*l8Nd>BZ^q}srccU;>dM{?30ie50o!pL%Uo_&|h<~xi3SrsS`nTX^AEZMR>A74>o*UZx zSx}^nV^W@SC0DiA*oQ5<_9LC`@Qa;R!uEC=YRIqRDJ-?ZK_Ue6Y^68T%k9(2Gnmw= zcq7(3v}HK^K+JTC*YHKfD}2(J6h-qFg>dLtS=+kP=vKtG5{xj$02+;vaGf`Wk#&JM zP2qnTlTuXv^P$rXF-i1Mwbs>w8BAH=;93eBZ%(TCL42Xtk5?@B{5jN3iJN`Z`*Wtd zWn`yQ2hnXkhiCW3y)2#qqb%)GKK@u3 zGnDk%73Ef&uErfUHe4?g?~%rt+;=CF8ZVD`RnVptn=Y)cRZJ;SMHze){o*?}i}vQe zv_^NKVKteG!;yfY`1P!!9R0>iH?5%6S&~46U0F6L!!yif0?>5DO$KUCk1@G}DkG=q z2KU3z`BR_K&96U++ZPt@Otl$vPSaW&H7}N`$p?wUwsy*|<7BWlO-5aX^lx5e_Ky*U zLRc43U}3hi>DF7(!c4o7vooK?KrqzkvAEvx_ZQp8>!Xk(LCR546lZaP-#>kU+3y9Z zQEh=#bG@&e9KeS<6%K7scF>)3jXq{T|pl-4B`xto63h@O0$yox0 zHNx@B%EnT+Qnwka{Hhr|Gu!h#at8*RUqE~AKI~sABTB2MMwNUi zyh14OLD(~QOSG1#zOQRENWZ=n;pt~%?2R646_cRaD}c%*(*_}Kt>+KAQ~{g*eGyU2 z@u=2G5X_{sb4{6riJLvWE~;*m$xUldmGv?(3^ixz`C(y=#%{J%b04J$Y!>nhFV`g^ zHri;hDgkEeYyS)72(1@Ny#cX%&}T?iQeeZ~vD^3tIRxVEo?bkeSHm(+7!4u)7~fc}$AQt5;_`>)?j=0&MWom|)7W}3{0q_1|% zy3}gYvUh^XNOO;czy3B-33An&bRMzILuq5(dIJg(i!|>SncS+%FViqQimk;Dxx@#W zYh3rLqhW|j9R3#bZMWoc@7l|r1JYOth+q$%?S2uVz0N`JwQ^{|Z#*%Pgrdu)^kAAm zAUy^Us=h>AD1we(3&lM}hSUBk$hud$*Dd-N?=hAc-XLJm;4X$>PfBu4$?HWpsDPC% zrvU&~3gNN3n?C9N0cd$|+8-wDr=3dhM>BS?{U&IHt5808Q$M9&G&8N&eKcv>mxZ@X zO!HDyYRXOhdu;GxFzhvx@u8IzAQYo;19rW**wU|du-7vv-;ysOdyX4(KQ;qJs*8w# z6|%%&TSnC4zRKX>5=mkhc3n2Xp#OVi+!4^+Ru&U9gTZl(gA+ebK>Ze=;kZ^6JRe8v zylkx~fNr8uO;_e*!RT!z9Oi<8uQR}NasLV%tO;Q}+AXe+PhGgq;GH|<*dPT-VB*WL z10VwwOgHA-SK1}$j1qz$P*btIE$oE*{9e36v+s2I(8SEHsaE*nFkQ31pz zWf9&RINE{aza{qf?-qn?Q$vWb>dl-)FcT_kK<&Vpii#s`Th=|Cab~Y|4E*WV6ekWf zrXVP6GSv{`A-ZwN2i&PcdCiQ87C#B)n4iPA9q9ZrX+Fawam+JjQ3;}LpEkqn6AJQp zveLf{?S2TQ;{?fUSdVfB{)~w%6Pg@cO=FuRl|zg$g}K}=I+nGwThFk`;=ZYmD;CgI z^9&jX68`0jbjG$9Yr{9PW9DkU4Gfb>MaYQd=Ww$-nPL3DG?DvR;^Z@vBwXjWLRN{% z2|oz>CIg~U4XVNaq?R3kDWEd_H&tcg{7L)!* zx$LBtUZ33bW`ziReOw)t>JOc@eh&{?ta3X-FJu?h)$pv;eggVC-Cbz9uy;B>#jZLr zwmP>;7cJ(qZC*%nE-&6Eqx5CaUD6X!}!dTGY?(Qy)2X}XZ zdxC4@(l`XyH16)+XbA4^?h-6W8VQgL-}l$l%v{aQsa>_-bN207wbp)Cnqbf0Kl7an zU>`0{^`C!*Uv-fSL1H~`>Hg>Evbp(;ARiG7$PMzb|4U$O@5!SfMtwvA$h-IE18%Ri z^l!BX(!Xt{$jl=@e`zPp5Az~f1$u+({+td!7Y2S(ZLO03HlR?K*$0@_n{0l z(}IkQ7dax}S4(5C@Trhssg9czLj{GWr8DYLO040U5X=|O5ghpgSE}}!F=l_e*#$h9 zSm7}Jw)-^yBxg&Qvqc59#IdF)aoX4=NC}}ER`-Xt58nc;b3#%RHl#~IM-U66)1<3~ zQDW1DWp`fjQ%H{KZTJK`fUN?eIoi5ILo6|Pa}N*C1uJQZ(BShCo{q>>ebo+ig*2x| zvP-DM#4C)iFq79y&=9@?doR5J9lj0=4M8x;Zmi(0Z#FfWnfmZKD*}Z2v5!?C&dUb~ zaUQV6M@f#cteRrS&(?VqvWP6sQIy?a5y3y<(bW)+16YweEE$=KJtJ zq7lAglx&a(4zeO@;(=9LU&;Nv;U0HQbK-`boONz=2;lz-}X253>Rp$9dV^WGJG zMRGdm@%%01_#H%=B6 z8JXC&)1SicblV@lEhw_p&f0Yi-xO$0%#GfRMqUg&Nc&os%jnMGd#NG%z7HObf#+Ok zTP$3gr4vzs#3W*P*u?(gx5*&YF~b>%y#iPrvnMS&g9}={U>%f~CLO{LUCAHrRrGo? z%tn;CTl9T^`K?ad8oM_Bu2sbNQo*fI;G_LWrOGi9lt;+pk|s#FvY>A|E_{QfV>Lr# z^0SHOKt`H}G4yMt-ATO9fwui@Fsv-jmJic6s37MWRB6d%=ok6>V1W}RH4oL zY{gW4-D71j=H&Z!cI=U5sfJ|we3JOO~OR6w3 z3@4^dStJd8pSqY=Xa4wMg92W`ilLaC$k(uyV;q+TWfdk3csn4dGY68eDLvw=5Sg_# zr6Ay4yDO}LHk+@F=vW^o;D@{h=)jD2K{UFErM$m2z@#$If8 zKlcc<)e~Lae3GF{Nq)i9XdXd|dt6E}nl1Xy{{B^jODa@r0^1{O{6@tq^ZMeYWwUEI}8sAT`O7XJytTXjlx4RvMUhxPB3k(_;r1TSX zkOOQh+px!xdL$*z+^_sR7lDmZ_rE{_G)p`~$g=flJG13L99?z`T@}WTy%8CftdFDW zz45Gwl!o~B_;`1}Fh|nImt6su8dE+#ky|mDtWURlhL7TJK@>d41 z&5F8>hS0un{4zayMoXTfal`s$@Ie#bUh9FZh<7++1QSq&M&O913n6a=Fa|PXP)kI* zfb%o2(*)FKFlP=M?@ME51aMBmBMM4Xcbzs)xEFaQY4(tWE?;zrBiOX4-!AgRBWtvuv@W%`*E`+vN3tez=2rg^GK z#8$Tzqb3vtM#3EH$bH6bP#JC5)wjsdNLWYY6OF3WfrZ?2XILK1F`xHGmhLJX8(;bA z?v29v>wqjmEt&+g2gO8ap{@sV6f^rVl5Bb*)V?U=LLEf3qXH*S!XW!k#Ha>I2(Y{I ztW@>hG5FH9(%(HiHir(mrsv_DQ8(UiFi{7w;Bzy(u&Z;CPNJ=~w?Qpo?WORV(hK#Y zIhIElGYfcOJgg5}XvJi@!Q-Rv$~`;G!^_T@Sa=Kj@{qHAH=WC!9^~@@R{Gs%CHLor zRemr}cBm2wi8x6fsUS>ssj#$kCJLz3lR9>7kqFF$QD$9+Mlf;=>O$Pk#p-Rx`mSAW zH~o>VcU+>`M{C7Iw?trv=^GBNk)HhAd1wq;Gn>Llw}D`nY^FhQg(n>Y?kzoAS^SRgNs31~Q`#xL$%|no$K>vT(0aoQa#o&{Zv!O{|v3 zN)1U(azbVQBBC!^t-eKr`@RjP0>VM^oH%g8=s#ic^_@DGCs1kSvMqFi)gQ9cMAhGu*2a0! z!=44U#r`mUw|Yu}RradP_NVk&VPf0Pv?zYGMzfaWJk&_EGQ)X=m|!hq;&-HzD|FGJ zi-56q1q{M`;40t`rW0p1mmOpnM_Qqb#=H(YetNq=rdqv^+%y@+!RnWsuhLrV(VwBhTCjmT2ebn1Tmkl01LCdGWDE8vFq zg}t>df4%Y}Rh&Ykfoc%(>-xt=DVi#eTz^o$(ueO-Em~#Hg?O3BOz-20#TbfbRleo~ zHb?0?zFk{{bryAePt0FNmgxL^7M^GYbQ+#ac5b5~I^g|*b1*RQAkMsxp&n=wcwyey z%JNl|h^6p=i4&{6X|5Wd0Dng7BI8eT9;VjCFoKgN51?p4qyjw3fp*5SFGQ~9bxwqT zp#~9pamzWqL??XN*`N6fTXNOB3!eRkNCB2Tc;`r?V{7MbtzqE~^i{F5^x*UWTAJB8 zy%E{|X9b=;c*j7%&CmCbDCB=DM+Q*w{Ie1i`tK&?Iz&Bi$l*Ihf`1)O0q%cfBiDbV zq~P0I|EXK9Lo^4U*CO)b0QmkH;1%NecN*}&2Ef<=o_{|t_|Fr-`@aq_0=w5E@?rA) zXaDVZo_}`#byD9F$!@i5sg+VtRj3W*RGzqzJ7AKIgQ zldBIlFN3b!f!8CwrhopF4}kj1!t_qTVP7uOqq zrFiGLoiR9GT+60bm+Q3;4jA8|_9Sk7&-Ak_FTt~dEn;=By_R_okl{fYd0BatA=fgPF`*WpKSFWI-( z=c99oN$njMNag(4OxnZ6BXxZ8?NN36mGM4Iy|WANZT8wcuHZ zRG6VBf;e?JvKxS`J#Fk}npSs9C}){2#eUQKM~vMPu%_*yrADJAcAO99&KUMc@TDXW45Xk@KMa?l}y zF4@Qb^mcBw=V~+e+UsZW#vv`apT_g<30$va9zc-W zJEYH*xy7;T6~rK3lrfvSC|z@Ls*I|Jv4MK0zxPLlrQLG1&&`^?ep}c^%(d3`$MdDh z+H|C_77G7~!p`BMRFn{d>-mXbN8#Z3wP0Xyz|CmexBDvej!%$2KBZWF@v3w3_3X5d z$ls0IyA?hep~QulFWcIwbSzulFv#oLYnvi!du!Quaw-x@9aFXjfT@_k~L6Dt+kz+w!8taN_3B#tMrCb$Cn zGs4=#>sl{Hi!KzltAV!hAu4>s?NYO&50&u|V@_fSXLnx0me9CK7kHHM(5{)64zmW% z(xMWP&sFU~t%41isxpv7B(tqH_3bi+s*0s!vF4w#JL4EQ;*hRXOsaotMgv(acB1X$ zqVjL$<;saUx6xLjlrF1AKc=KcFcZkT`_0*YuM1j;JTs0**$sK+;PFXYsO zek60Co#+RvO)>q$h!oM$UK*s(Qqh{wBRCQV5Gl*4Q&LqOqYlx`)oJSXV_YlDtA8h= z*(%eMM4hbIL}vAPMg)~W)jyZQj_FTHyOEbS!CrACdVdg}9#q~FUZiQASeR|5+D26v z^%BvJdZwm6&>u;gSo7Su5<$^rG+Uc5ZHB#wzZIE85G)L-v=@8?RD;ZMhOFtV=|z1* z>K_7cJ7F$ksVoCwZkSl=A}!y)#%T~Z{g7<9CJBfls3B2K&yG%JIbO~xoccWWh`drO zHW3<~=r<-$o)&z6SS-V5wJ853h#MX+mXr6DPFN1dDX1aRzwH7^I7=hDBCon<|EuUh z|Fl5vTOF%IdmlpXUGweuj)lRGYkP3ibFHw_gWJ3C5KIYU zdi@I#i#ch&t8P@(=RJO6|LhU3IPX{k17r~*R(9456&CfQAFQB*J)19p763W5GJ+Tb zot#OqfY+^ROR_~)=E}Lr2Dlto#Lay{QC!J-D_drof<*GrCaY$giGWZ@!x!x8owZ}* zJY4B!WjXj=6g+7r&%`sFpX*dafz5izB!}@SnFyOYyFuYPmxj5h!L0)e-g^=?&~073 zD0u_3qT|CV{X5X2ncs2du+clp_NBJns}DTA;c-6DgDUOI!1mB&+t5B}nPN^|&TU$3 z<_E?WNj*NCW;3EZ83nN-Z^NNOf9uJ9L`YMIiBF*pVZYsg3y9{|E;fT6-v-KqGP+FYE}Vutl| zjdueninX&TGZUWOWRp$;w-4zWD+U{l`W=^FRn(|Yo-}L8-IWiMR_Uc3T<*)n#WQjT z^|a`OU_hZwA{`k6sJN~Ke<{S34Yn6rN68QT)@*4m&>+$LKL|4p@WyPzgp#b{`|2MN zPLc}f!)2(=SK#;kp=k#es6D&q#0LDAf(8fp-dOVqW=Fp}UrGEA{T672uD1bOh$I=s zEw5Q`4VPKFLdso@Gh)H-%imvkvr(fgzsQ>^_J9=lTSg(7V^6o8qYz`7oigs*9zJSl zkrMEizLKH){$siAgN|eHQF2zs$Dn>J&a9y&d#qOlAzhH>3Aw8rpPt8{MXD#y;S@K7 zaxaL9_Y|8jV=ZtdAj)5S+ zEYKB&BRh}56I`4`vC~_s7M2Am;y7^1U28HtoPOj}4B5y}x|4E+;I}j;bLmG+n)i7f z##_i}zQU)QC8wi`1v>9fF)U*3|1^h2`dGEus1{nibY)4cVlH$grMcBmZ(FN=Y?l5_ zU;axuUw&}co-JQ&=`i;?*}b#A=;jKloCY$QIOd=GHtiu=CILUeOleh6Oc$8D*h=NA z-S`;W$?>4c-jUcgmu;ApB+JaNcUWs}&Uw^RGEOR%dB7$gv+T#A7Sv$4s58~Hrsh(0 z0CQJ8T7~doc?uRYr{CB!>`I$>*R+-3d`Vw;?Rq9_{+Hw}g9~`JT^=e{XFiEbCkL{Z z_6Q#|JcHOx&~x+XosOc=DcY5k$agVCE82B)DA8(`rW%Z1Qbjat5wcqJTu)MwHAfQ8 z?={*vLIesQpOp|$#SrrQ?R%~IX6?W_IdS$eVqxnzrFJ|-W8DYdX+#SF9P?V?E^$As z{Zm3HZSwe3JgC1v*ieZLY!1N6{RF8G!9N#WdSZL;?b-VNssfziE)C)QTKkP-cA}Um z#%VB{%$4+ln(WFut>?&FE1x$2zzwx}$lx`UATHOb>B0*D(WsHXEBq|Z`g>8r@+H5HUQ`B7~; zK`PKvB*MX6{sTmWD)iD0h%PUv!Cu>zQW)5X?04yP2u&5b@%;PTzc#hB)gFwTdW_l-3U z!BeL*+1AiOk}p*es|Z-(m)=lahIw#1cLCE)A9OnjxaYac{G)cz{*ooa@DNZ4{?c7} ztiu@RMWOsLtE>=TXFiVjiV(TxpwzSzF@lkx{@k4-Y~legS%z90PtrI&Hf)Eq!lAm*Atp2pYgP4t_I@%k*47B`&)q!;cQDD^?5H*-k_(w3NSSS4Kp=a7kW2(>ATVS-F^@HZ9Bku99NpM|g4 zDF@Gn$(}s3jKYhh+%g?2g?Wv7fhL3UpDXxfJ@wd{WExqC=9t%c1A8kv`1MVv%aU1V z5S&JngNgHIgJ@7Ahi|`vgY`3Hq(1NN7|#Px!i3SPrl+ok(Op2K58_E+LCn;^aF_=6vKvT9N|~Q` zZ_=@wUgU9?JDo8Lq`!@GWB&Yvti3=~oPAE7DM!V(-LuG|#g-cJE7Q^7kBzD8Z94l% z&3dS)VV*Lm8(J%CYOr~0!PetGqWHrZTi>;@e46b{KQ_WJ`1m-}v_<>-lJU%fvA)yL zl^~+%73S1!rCtZBvO6r9QM>jhjqM*FPJCwJ^D!}(#4xg6*;W-7l5KL)7?%*6U0tUi z!H#pk%H_GVwT({)h0j6;A9L)?J^JBeKsm1{>58T zoi^ECrMRVrG5FL|$_j`$D4nc8i6S>j?eiA^cWA{4`KFWV&tsaK)*KgYT;=2%W96{i zTKiJapp7myj~Vmy@DIffaV6Oc0rR{*7m%ZFG~(e?^NCU5&XXF%)CH*Ypq+NLnY%u) zA_bZwCQlS^yd23_feY+&iREnd6HD_t5 z7wTO?25M=b`AAX4)l$YV;oZ@vQJ$t!%w8)hyPt=c=4uVKM77vV8W#rpn+wNljqpno zh|;i+DzUv;&gWfEKXe43*+<)y=cjDkOkU|2`5fKL+INz_Y<_|c&@XVph4E5nIVOYb zg8+G)e!)%j78U9wkhUQ92}1>nI_@~^p9CgMG-hZ_=kF8knCk=+o0q}_5^7`L&oFWaKWO-fR+H9wq>f9)&SyoaH9x`k2ICvPq(`L`9W-q@Tlsbc~e zLZ5$c8c(hnyIn|@B$vS1QKQ112~h*}Uf@GYuxlKB%G1wmn|5>8l^bw$Lv?csc9{{! z3hs#pc3{t|>g-73>e{-?okJAeN4bt}IS;5V%#B?Y?&)Y+W=T#_*3su)Meth-^_t2s z4vPc(5>QB>^C$}VN$36=%`0%GIy7t=dP`P!Kt>=UW_h&$tyHNyp%{Q>fvgrq1aCUVag1A8Wzl$9 z(|G5mRZbB%-c;yc=m4-M`v)qN>9mmB3^_rWJ>`Ckti=DgSNy?lP#uKhX%rPO%e7+f zG50XQcOFWfE9& zh!-W2vnre*7Z@uJjv0dKgyaefC&&#BaYmwo6-u2eAq00gBZ-4}s5lj6sEkByxUIQ_ ztOPAS3Gi52^9u0r@bOs*3D^i&@CpHVczOB7{{IP+|8u#(Byk26RugadXHRO%lQ$!4 z>BVI?Y*X7CFooiKWJDHH14HI5>Q@ks3l&<76kA%vEnE}#iSpGLThQz8-_sqR(+boT z4Z6|rC-P3MqirETz?sR&Ac(6xFz-K?!-NNcnyEBXR+B2!ksU P7i@AcGFZgQ z^WOD--~Dr0Yu3>FR8?13@2c)O=k!D>?ZG+?0kejj0ymIH0F$}%I{y(o*7AweJjBrF6l1@Ni^gunn^d4Ld*pI-pLs|Mf~1n}wrz(No{exU>le?(xy z4}T~hfFJTCt?X*+1`y^4@By>{yjpH<-T)!czlOF$fDHf$gm<9fY4hrzzA)hb`r}oW z0~m|Fv<3=+Ep1zCHHLi`YZK|UcHkdUP<-^-U0{~rnb|62sMj>yPYio)=1 zQHm*7IO>Dzvji2`YbGmAi8NDG2Ik_hnF@YB;G<+Fg5c}d9(?f#RXONgFo9<~j8E>m zSvq2hi2-=!Y`na^;7$wv8-m75I~y;6Fc>C@M2E>&(901VXHJ&Ky%m(K3hk?n+Y!0L~8uT{_n)cQX}hGS?6o2c*9`0iT7r&xR$?H$)B z7$xoY&^rq8KKi`avgo>V)N1;wTOe5P#U|$5MT&XtK9Llthvdywm*Fm3<+I`EXu#>R zV~M=Zc8d8cSG1`tsZlIUbOj&O$I4(9wN%&I>}hL!iT1G9(i-*7cwR#uh#jb?s0g`C zHc(6(S8FeCPn(x6PyandMhKkx(+p7@R*Mpf2Lgiuf*=q81Q7xV@`GX0s4S^*=7{XD z3FIIgVF*BwPZ$6M@xx_cYi!c6LsUu}2nZkm0Rn(XpZxu@p=88j!3)ck;KmZ_k;(!H(;Z9k= zM+*eOL6|1CG0Yqb1q1x#its-~8n%o>hXI!d3IM?T!hZ*+ic5nH0E6Hl+~FtiHK#PJ z6PFGR02JhhUx0lCOT#*FDgPP+!hL-*_7Ba(qeBM+Kzwj9K6ro9Ff4q)6YwPQ4+z2s zz;f{&{!Ibg_9TNeOpkyL4PF8SKmdMN9#{t6ro?#)8vj#afcx+d1ryStLjXYdZ1M~I zRRa^kV+#=g@WUtfuh>7Bn1~4(jy=&s3Pwys3CkkFL=par)Db;J0|d7KgiQ)d!z_sZ zB_K1-%A;Y!!{x&K|-~<5iKaJ#{-3k&o0U&Uez}Zp^AByIdKxN(5ANkZl@=;m41N$i@Nh{mjDS-H z)=EY3H}F6>{1kXN45TrBq8<=VBcKrc1Nx_nMDs69PxzBt|AVX0Qow%GU?ct`xC$); zJVZd?zg7z^9qQi@3I82`3oRw~lb7&pd$RBkL<3O5YU$9>;FTQ+fB^qe4GjRFOabu! z+x7!IO(2BtFIW5kl!^41$ncB*+Pd^l!a#T(5&BE#zQ1j_@_%hX2Kr|JFwBg>4*AI@ z%z{A<24$pxxzWSt3JA{%xF-0oCX|sH3to-jDGty2|FC1mC+i^Lr%Lq1vtvd&48AAc z3IGIwf3?P$0C498;Ykip0l36C69o*96$Jyn{5=ifKeU{g4jrC?LV{1l>M2vonJHj= zEU0ksuhc*AEeky|JOPDZbu92=@Z@bBiyX|F6@U)UX?U^=fd6*!{V(uW?;jw~_M``| zTyAV|Ry_p+J_L9}4#vO^z<`$wxXS|YxqaeU;$P&i@_z^t2jIy!LHI}bFO`uvC~*Zq z@Fu)EKMDQ^Z*nlf83+E$xJ?d9m@_9P68z%dHZK$i~Fkf>T!T7|H zv7WHMX8xmL9v2flv%v5|^W;w+TvGsEqQLMVKL!4O@FQ+YoWB;~C66BhuR5@gG%~Ow zZW>Gg7!Lgv{R^4%z-bPKlM4J_Nj2x8Kzp*t56_fS9(#Bh2g8$qUkIkjE(5FJrGo=c z?!bYkRfLL<93i_v8?~Rtdl->q+iE+yO|5%MSv>%MaWk_$CKlm!9gP z1CR#mFZSfof7l}M$tEA%1<*g6FFhK?& z#?OQTFAwmQ3R!vMk+pQ<3}uOhGDlj75Y^2B8L;_wd+fY8Ho zAP)a}BoMMjhf@FyuN=aE$I>qZfCEpX_z!>x)5DB~{}VSChUcCLJoki9(BV2y=>UXH zFv!3`I<$XW``11ec?uwW5I`^(mOv~GI}xGy%M##!>G^~|g+)~C-=qNH!3M*V5?*

    (F%3m8pp! zcus%RE7avY1n~{R)UV-j4AMa~rp7P;uEoxu*C%FKd)2mNC7(I{=CBN>ykV+(*{x*8 zzk7N*@x*?Q2YB2L)Tnog_o-u(?S-vE1Mco~dH&$!^5~TW9$dR~cJ@M{_os=_n}^gA zC|!tks`+E8t^1OR&@_wMsn@-nNdK|KzS|i~@Fq@Jph1w#BfZ$#*7-DE%`b)-%XR3{ z+3gN1Zl*=*_)F6dZ&$5vZgW#5`HO9CT0zC$H%C3!b7v$WvnfE*nhMXuyVQ{#sH8^) z8GF{3@4`tK=D9uMEV0VhQy{!Twxpvh?W@&HZSKPOeCE+Q zwl%l3v^*y_;wBs8Z*zFk_j5zMzagH{g~$7ROW5G0U{1crV6UuP@ZR;Hu<(N@Zy!DJv(tA3RX$mwv zJ#L`gf=_*^u?aQ)obO(vVP{tEE2KJIzp__(W-y41VR3?uQMmuhtS7COIs7K0( z-b-qm7AN?I8r(yqnCd%vnQ5)eGk7`kS_YDzm|qXsp&W^0s4R!Hv)(69@$`EXi8fsb zm?lI|L{gztmy+(iF>b~Ui3vx3o0MgQZ6&z-+$-*4%Lmu zBTfimYYf;*j9Hsc>4?qfcL&FHO}g|XAOaJU_^2m|4p6h(j!8{1b z)xjJIIYEvPIG_nrU`|(6%;!1)7_qk;qR=4{iMc;h;q$Yt=(*(h@}?|Yc*ru6`#IL4 z+WzmD!3ol@=DXJTctT{-GL6KVK2Rhq2kV&q{VTUdsw3XpVQ1hTjrEfFU}u#4?@un+h@a4Q_vlL@Gl3a8r*9zzRjJ6H6p zii;}gTg{glgnFpedVKORRYd5C6&kEhvk|_tu}9K7EC%ogb0+FNFZx zFuG5(*j#eyfm7i6#TEK*mFw%ra&5$PlGukL6H+^#R5Bn(3m z*Az`iaP8|}++xn&tl7;?Vej#;^OqEqOjgTaqz&!Z&A4Ez=KR%+ZI7R zuYDh=1CFQJP4mhg5Cxq)>JzEjT>KO^?FjLSORj1|kd}ju#=CI&Kn_ z{r+12h6!4z$}~o-#id8_-9GulTi4$)a<6?9&z7z|)2QoHS>9@42KU|pchL=e4k(zM z=n1-huI&$+xglrYZ|n04PP`lOsNifhDw~{%HKNx`>Pcb@Ci|Lkuum{fTxxT&O6TcU z>zCFo>3>6S$Tk^^Q@R|0p})& zKoYSjYSb0B2nJ~B8a5`ieN;Q>JJ`l;ZFDRNiFO~&$Rw&63@X(RJCZje=tNy+QsVzw#=q zY6z;~y)mlB`T}x#Aqr+Le>)%?s=9)vB7$V#)`4`DiTEpr{%c?fbD2W=>lF(hmWhX@ zz4yr8Lu=dw=*XpfIqzI|__O@#LZ0KmfmS|s1LiPpVXpMwr&x?KqG zm>*m-=J<9`zvvgSVet*1tNN1E{5l!Z=gNgfvV7s9SPes_#!!rLVvAMk+xt);xQ87( zdgzcMexaT&iM9_`MgC5I#xAua4Cp+ zD!tsBlie-~;xR}g65q{A5DpdA)gLSVwp->%-5{FfjQd8!jO+DDV}~N$zK3X5-&)n4 z6RG_LvJVMxhvLAYJ0CA-HCH29{&=mc`K?<}61xyJH8z{id|8Tk?Ktu0A$<;8XiVY# zu-c5$!4iQ{-10Y}?75WpHt$Q_EXZ#z(FI?rZs!CwMNq2`92Ra(>S6G22_YV<%UFc~ zr;)bEaNN3o$M!3OLu5=Erg7OP4iqk2&kf}kU+TWoiyf~iktu(!XhQMTk=i4(rPB>* zU>P4P-pse^sN@2pKV#)UIYiL)QUeGJ^2PoW6@d~^fS#Al^p2F2C40g_A%_-QfsG`x z3afX|AgFA0F#=7QSsz7Pv3 zw_5*+PD!C&tj4y*g5S)q+qEeg0rRLm}fTUe*#4Jw+#3R)qq9>XeLq2N-~z}an6#MDrb1jcSan%KwOTCX^r>um8q?pv%D zTiekHSZRW?Ox_cAU&7JEN{y(B2#YIY zZ_1`YbR|!Hq(Wp%JDu&%i!|g-?sk1i|C_ zKPN+)iLZ(r9n0H3h^slrIaR}y*IV(3A)3VU?-`gi&2v%N6XHunR}!0@U)0VEE!$^F z;7ss^C#*#gSR*sc0~iUIu_+=-U-QNYtqqdPk%!@ZARtKWLU>gEW+6o|Y1AFsEq5;o z9VICGPKhNaFv?=U5ZMx3*aiDEEnr!hX@d`wW02vqd@qX~4!~t3*XU&)1>ocAXX7ZE zXge|DLq>lnG4T;VZ}(Wi_ZlQGiR4HEJada4e|;U%XCu2~zq{QzI*raZocoFW?J*_N z_+p5MykJ#S@&O_md_L{_=QrXviAEb_=uHTr3-9CwLa{omb)2>|x4Ko`>&>sud5W7b zb9n@-yP>AvV$ip?$I%?u`ajPpevYqnAZ#owcD~Am&X4=L5h&K*+m%*l?0z^K`4|#x zelLKHM7N!N`rGBA93i*fPItd%C0MRLby6^D_G4%DVHgkp9raJ%gFN(UpEtH{GSDb+ z)#4ZPZe9KwQPx=!g4W&kPGz%lXPHzp&c* zs!#s9W>aqRnaO7z@3Ev6|NJ=ONwOvALw+J!7}s|I;a$DmB8UIrd=Yo)IA>5~W2%!f zVjA_8!QzuZ9sP9lpdD0-hwr!cGe+qBTaGOUg}P-)mS#KfHs#$3R_b{ z`U4Qps_32QR6ir3@wy`_dX@v4Zvz#SN)ayXvRU@mna zWXz+GEh5dicVn=Qk^CnjZdv!FJw$|TUY;&^|D|ed?#mRSKAek8%_Toap>rr$Uu(r= zRp=T~`F){#exvr1ee$yVm!wlx*5wULH*p#m=mXc(O(&294_%@`)ELWM><9`uO%c5b z9_>N`iOCtlxv8BK-1Gx@ZLiMMiz4G zl*AHE$<82#1B|cN`o0@W_zX(ClXp31lnbh6uT)c-~{XNY0>esE)4`(amjEbBq-yb<}a;jju)=qb{IvaFKvH{pB z69ieGe4Yn0h}S$6U!7m1Y%j!K#pK%!?#R2H{I-%C7u>GV6`wq{?;(I=$7C}=on zpDzzNjfjU*<`)B#zsI4_uVXbEgE-5kQM3V%hF1f^?Z4vQz5&|Ea=I^)QP*PoR6hC= zswLZ%zFzSgNV;g=eD#|AO=7X=w3k74=tx&`_(&$9#L1m)8KFJe_bc?XqR*HE#~d-` z*OQN5AFO7|J3bpF{|@?WhIUf0uM4$lf9B8BPb+v;>8(m@QNbET044juLws85QjhCT zE~R1dRs^PKlK7SoZ?`82ftGzk8HW)glM8Wi<&iBbKBjj&QS`Zq*N(_Y(*lw`Ar`LA z14q$uH|R&Xk zUo@5tkce0R+In$S5;D{|OF@@4)Il+9Hlq_)(Xoy*+f#5~_-?SV%Av7|%8Q{#^3SCk zo9K-bkgk&6>i#|Ry`J^AscM)Bx#u_3uWVa@MrS+om0+3FS6Z4iPR#9lYOEviayA+> z%U=>-sJQadv1&uBGxFX|(cn_v8*Mebgsg9V`MScTo8CAwVVQv?+kd&BF=|!y32adF zaJ2tGo@bC&N$)aB`KjKy6ipDf$0V>dDO2mbJh!+%`DRo+qUxx zog#xE)%g%(mtO~yBg=^0)F$Hxe6F}YDpmr_ECQAd*xN#E-Y3-3~JfXBR@QCiUX98rE|ENOdZ>DIRXoPBh`Ynck^o>oU4VMcf z;62Cd3`R$}nX%RMT3u0LZg1r!)%Qs?^}~&Ym7=&NEapnD2 z@1j3BS^Aogdqo`gP_1TLAMPI`Eg@&XwjoAB!gtx+54oSRT2anH_-Z~l`fg}fq zxuakCIYaph0$N`f(Y`krbE-22XG@qI{|3CG&_=|qup-w6>1rs@q>uj)-VVz7>D@^_ zjsaqiDjKyg|24(< zxRG{1I;--$y-}UXfvjoT<@=s~+P05dK|2lgIkQ!fima8iWmEP9&E}?Py(P2NU67Pd zLYtvZs>)k!*eY|~)r8}Hq0KeQeV>{!_62hV)%zRjGvD57-O01u6u)@znc=ic#q}UZ ztFUe-8?h|+lWP(A;o0+}xDo~soSu2H-_=+lZvWl3rEG3`R_P0bDSO!?-KJ=}F7H&w zliX%UzWe2gs1vU1>!2|6e!t1>raK zwNhJU5INy5Xl%D={P!Im@dHKLJ0INF&>YgUA8A%3JKu@W zh4}qB=bpcbj{4L2C*THc$K>Js5y=l{=WL)C0;oK)U zr-n*;Pl=;`ch5FWX1t0CeUS^9?BGw*6Xtjsqz8>f}rI zYC^SYL*mK8_;o`rDqE#(KgE#_rLw5^x8`W4exH_)76$#QcuL*j{AwxpcVN?N6>@s( z;ExG|K6N29G*V28A?cec=|5duifE>y%{!}kr+xYg>k=>uMel8n> zJ^KjCXtQ>AfyopXYusk5YaELW^whp2oBr)z9!rqnB3DPTExNKw#6`#4lf4v9n%_$GbW>h#(8Au7L|`-X4rf;257()k+AoV;skT(V;L zSTEzP3^!wqtR>ln6qP`!bj+YTX#8g=tzDzlR8xHorW@hS6}n%$ZE3W(;==8 zg7KtORT-Jc+gWwxz={(g5^;go)oZS8Qit>LqcU4$`$5Q9j^u#-SIPAqmb2%>q3_rz zYgWGJ{%&(+;lS`ibYbSRx%laWJkpwWCX>82ae4dY)P`&8P5(2E*SB>ti&YDMPA9HJ zM4_J*&A~#ErpJXolizz_p9acb){~U(#^4Kxl>K^();sAZCh!8%b;m||olTsN5rIpN zB_L2lzQ}wQyEduI(k{krD)j{^ft8pE$bxLLoYmj<<_#h>dmRRf=1*b4HydBGu(BSI zr{$tqM}@=i))U=6r(mLpC5-l^zQ@59C)b9SATRLI(iwSw8q6@;^^$VYQZ3l&MKG%# zdgZNHi&>Oo^}0y(i-pm7N7?)+=GKzuGG8MFK5Np_1ANk0@MmQH%vvVg_q9^aSrep` z%yGmAkq(f#1K$W#UmCJ7MG~eiU?Z6BQZB{Em~Tj3n*9tJGqGLWe&&~KW!BZ8$43Fp zy4pVa@o`MdkjP>fcMAmDLAB~AJG&7@evr0Q&e8PkY7SvM0A?ihj?qpm6K0QQvQUlf$wpWk zOMBZpcP$#q>%dGjWw`LYDXxV*rAZh1meYqMo`F#HG{S23%TLL|3oj<@?~wR16*-sSy?yI80 z@M}-cT4$Q&KVP?BwK_TFwY~L`U!oM)S2`lax^cI|m_r}n5;bGLjUS3Da^O>wizdCB zEy)0Sa}e^W3EYYr(Jpf*UqnShd52(xVH~rgzti;?SsD!5e5{q?dgnhB{L0UX9|C*S zn-HNIFL=_H<}IAsYUE3@mC1rfTP~yPPGz)7U6PSrWKyQ7Qyq|X&OKZr1rG|YCb>@y z^$YubG#YTSODxKMexFD{KTZtdq`-0F4U-x)Q6_df2*VnE!M@Jwv11Vi9=^k25Hqi^n#eOUeZc47Ps{2JeG_?paPKXyAoi8FRR=RjN)>nIZ z-8eAqWDLk?8h0Ha3!lwup>Mg&qSTg- zXh4f!B@$)n?W{i;lSTJTWLK>oyUd!Ghh>h4FJ6`iTA)W|t`y&8N3UP#M?!Zg?K`Es z#xb7N(~+^IDNIQDMSL;Q5 zAhgP9alTHPY_FD-umboD*;wzDi@xFRP=g&I=*!1 zh`lXk%9ubDCVd=sncr>X^8~kKdO)^r+LM!jj^l~iUA$s=rBL57OIFKXtRj8K`4b)A z0dAEoiJ1NP_l8I9s|F8Oqu<`EPfVo&m76F$!n0%$;>XcP*{C*4F+X!~5idlM1~JjD zyKD2`b#gpR`&k*Qs19z}wHvF+tmdWamYHO-@8?e#3@rv{%8Nl_)$X=V6wrw-{H%B{ zNM5R73F;3FyFq!zI|8|&^cHP4g48Wva*eJ1%dR3<3axqALL{j~ey+o^`5cRGw6(Z4 z3%o!H!7Q~qYAu{{9bTBhB|$N1eJrfI$AxyUXtHh+tOuWW#Qz{j&{wkZkJ9TZEdL(B zt^d6L&Yos#X2+eBnfJ0SdinizQh4=nU%Ub#6_)}Cj0e>xL&ZydF`q1K`USI|_2;0M zs&sTv>CX%7&Dir*z*@6jO4QJ6eXtPtIc z#41M`^@)P?ds)MS{_i`t@8HEyt;sjgZkJ zceeexJPYh^xaiCP`dmU={(SyW2Z1{Ow%hp=>GfEHJ%{nfJ-Gx-hI6}X@_`q_}xD`VCcGZb+maRcL)U68v=)n`QfrGS80r5D5 z+U0W{cHs*EM;^FzwvZ=UB?tyM)|IwZ#-XNRM-}=QiBIHl)C~C2$JJ1{Hm|WRulO}8PiL~VIM#>3InIf${I&>tAW3dIw0#6y zMRBba-QVp7N7m-+6z>H`UttWt0v)YySEH4&9I2Q}!@w|^?qh4zCrQ?r%YcfUtmxSJ znl#NZv=5|N&k|@^H?70po}DwEY>;T<+*}lL40*}(hAH(#X?njiR1nz*qpk3>XpX;? z^DTC_B5H$iHH~}EKFbc1n>tqMhFYmFxR867EXI+e>c2Hw&ihHKE4q^Li%Tf)WM}1a zs+E#3yJqdh9F{v`?r*Bes}Ag3G@E|E6O}4#(hw{{?bmvrX47_I(s(n{g%zY1!7s6C z)#!uA{l0e1b?{3_#b6^_v6L5U+TzwCx(1ZZUV7yTJA%R3(-jt0nb&-g#Lz=iljsoA zVD%jN9?O1GzQH@vvPt8q(w!lrs;bJ?=j6Xg(^r32MkEAgb+ay_7mEr&yA=FZ>^`+W zUYYvq72h~a-1Zb(l_7OLb9zS91tjmKEl|Z*{h+Bf`)6RA##8-msCRHwC$EZT2Tre; zd{3QlsFB2{i2GG6G~y0dWOZn#`1l`ZZYe*HwEUtw%2J}x%P@(XTQj6fj9lS56@oXS zv}(r#Spu&;&SRpQDc`&ns&E+laOnJvK$h9au2_i6m%*&Tg1V_Pa4O*?E`vYMvhzvi zL#6{UYsx(AXJ~rS`DdG2X@1cf$z)?`inxx=%AEzBY-~*`aSzrAFU|sJiv)d_b;S@? z!r5Sx1d5ze00H46JxKMA)vj=Ynh7WfAmPdZt z`3ue60&^^p83!IeR}w8o ziskIiwN!@kxlqWm!+toF;_rRbG^KfrIg(iL4z>tN%K=G6TMkZ!5m&wS8sVE!RDej- z#BUc&sBL@>b~k&!J!5Yt%KSAj+>9^09#Of0y8M#ar>gx0(T+NtUI>Z(RcEIzX& z8e8D4N*|lhde=bsXr=X_MzCsln4kA6;`=;B`?nS->T(|%7<6@Mw1)H6A+&J|;RMob zfiePKR|9i>>_l~;)Fh@LB#KrwMDu_(ib^-`H<@Cn z8@TOQB-5+cBK^%Zw0khg^UTRAG=+H^wN~8eN1iJKIZv_^C+Q`r$ec>rP=?{EdKsNI zHX6}IXI(3blmhaOFW<-zipOAK5mg$Znq)hzgJkfTKo|;Zk)M4z(Th0`m}jH0e^1&pNv{p+nV?b-iv?$taWxKMt zLe9B*!Cti>C|T9smjd5c<>wPi`{zjgT}gwc@8XhGI62G0KNZ_0m`w_5}z1rvo@|{ z4UaX{GnI40%1TU_k}7C=x95`Mph#TSxZ4vf#J)>?0J@)7Yhau-@k8qGS#?p{lsJ6v@*Nv2L>KPoymOX1oDSvmO` zd@->LJcDMXGK+d-bAO&XUJ@2%OAvPJ<1uPB-6SqEY|}0hk58`Gg9HU^qF$N}jdy>c z+_GGWPsr9!Q)=2IHg!usOnM-Ap^21&Q^-CNdp`9Nb;rdDqbp7|%Nd|1u_{ehyYC9} zeB~oRApEC{zoNVw4 zfkeD>6^3PNVdHw|UqQV{_u?^COJ*e#m(PzvBO3(Xmk`pbiSFx|aMz>i=vr;F{>sL(kZ(t&gkk+xx~Ko;gp_tdmCchz6ij9FkZC-MlTb=^r7ZL~qe? zH1QVPm()W3f?m6OO1}`pux0u~4~AKtOFGV>ZFMi@Mz9UyytWSp!@lT6eZoZfCBtSq z^VQI}ZjBtB6TAXjTKasF{>z;%t0p%`a+RjCG5btBza@IH#CzjiuuWM5lU2f2fI-T7 zkPDx2H_Mda`2hK9vg1$>vb~~Dc%h#8yU58HE7js zC&%8ZYu%w^XVoE3fo8d>UPMwUX^&oc%bfAMj2m{sblzRuv4Z)1SHD6Z@1M~{?V-LN zvgG{R{gt64GVr4UL7D41Ws@Y`-`$k7e>!W=?>Ki>fe~mXANQs*fi~C`{ZSIH*JBr_a zhD-Xnekev?&vyd>(Da&#qrNn#(1}ZaOpw z7#ja5;FyTY8p2p1{m@{(7&g2H9b4cK{iM89K5J2EbyU6U{Bb6SB){MS(rAUPOzK+) zNJfaqVQ{YwNu7`E-H{5pZL4&lE^G&tq&U=6{t-b6%4j=+eU55r!oH@BRbC$cv1T~w zj$c8&{PX6$(*o*ZZ};e4(sZ@eLPb6Cv66`lrTdMTB}N)k;5+v;8uxO=ff~qTn@N=7LYtR$$ZAr~!jCe3L#IZLvY*9nRE&5)c5xi^4_i$Dy2Zke-!g z*w<9{m>dh*AThS2h>_MXeh1_eGY77YHHkc)e(*DNG)gQn-rim-yJ?TMW>F!S)&!9A zxmQ9rJyUJ(wMzzRHix1B^tYN5Z#?AFThZAn>-IWMf88plO8+nMn72Qq6Fv(Y+?KX{ z{AIZNo;p9prQy}uX1S|d=9zUB76y1&e364=DS+3Y?j7~~M}Xw7z&xfA=?%0-rP`#6 z7I9F+^mcPB7*p{#?3$}K+Wgqvic^mK$N8L$i-$G_^+32+)o<=oC1^qdYK1p@8TW$A zHOE5qqxAqP<#lUJI{%qtQINc@q1VbTsR50)bzZtK z7P7P<720xb7Nb(yFnmou+~LPS4c1j)ubx5E+Wq2M#cy)oueasoe?&|JYajRbI7XnC z`$`2OdZfmKn#1&VJWuss`!nRDie}XOL7cv+|M)+Tm{MoW5F_BH4WFJZJsnVEeLAY@ z`gAPp>3}5syve_FB&k9c|L4;tod4qpNvcN^igxNB3q(<9>}KO>a7TVFQswA9!W)EX z7>%T;0e~*vDy$3R=eIvdYus8|b-K=DDm5;6v)r2Nx|Ltv6Sw1EU%zYp<1oSly&s?E zRqv3~B*pA_*x0LqHvgVW<}r%&-8g3L|9n<69sTEiBretO^zdLBPcm_2?oW%JknXl+ zX{!c9vfExR^rM4$56;J;-4pS#B=iWqgwH&u;(b_iM7~Iyqn>{xSDT=mNgma&Y#zk} z2pC8m6dL8TP7JJ-%XXuKtTOXe`-0DP_H=rEswswptQJ8QA? z+3$uP9?p8x%+kDl#E(Ri>^MySP*-!u&Fy{u<`Qyl4nb#6_;xu0KgNRV_v@@L#=c0+ z^L9Ppm9B(`ZSU5|Dle2N+yuj;P%iCN=hE^Qs0=PNHljB*>YP1s0O4n)QF5jE$l4T&nA1S0=Z7%3LsHPYqvU#Pw(n(KB82dPpV9hGJWXci z+pDt5!Gqqkp%*`S`4#RU`v>nTdf8p1QXSy$^qAM}G-&PECt^*@k95sWnGk&?deQgD z0D|5%%~rgtkIAa(8w&Vr6BbxDD*KhGnwcNWFn2a?7@4FxZ%GLGM(&j#hu}j}Q|1(Q zceN~jIc`2J+H}XB=I>YprpQl6?tU{0v9qdxjw{=m=u_aIICJt&1+Fa!jNOqUdqP`c z3ho}W+XAMl=UDd)l$VRFlCCCt) z$ONRX=yHmVDp7wAYxqw4>m!XW>aP2oGV$SHnoc(BslpILj77g5eBbY`udK;jj>aO! zhn1WJG8<+_87`Q>$C~`UAeAqsgtRCb`ek;&G?ZHz^@DQCbKANp46Y`V+mDL+91KvC zoAvO5?QJ>plTvO{1OVH|y`R#R&z;obF%%iqw3dF+vc2VFu=M;D&O@skL)_$q7_Gwo zD$xXqldHP&Q@Cy*m|fi@`8*GWQ@yzCg5XPK)8|nu&ry)n z788%4dOxG;d>1N%=7(nH*>SNQZFBrnECE?1M^@OlK|p8LFVai{pWmk30$cMt)S(12 z;HVGu1}KN77ceu8B6pW{s!fxjb=`kRt+GFhWPLVNTL?ciZR-q_^D=FhTCZK`iJE*< zdx{dsn2gHk1ZIw@rHI#gGs~iPlGE{vSqGjTW*R71=`|h5IoYol)^#h;I93(Uxs^HV zG`NMT_}t5fv3V)OckwU3awm{LzYX>j3G9b6QBAxCfWHpQfzSIF9ZtexT@!L>4C2p| zj(j1K`6H-=HGOeNd3am}Ixp|ZE77{4s)d-JUQ}}6;UUW4%%5v?OH~m0jpopIxg%k4 zY7{*Gv0w;$ogSGQ%V!y)zO`;+l>+vt?i#9jM+MtN2#ndf7*C5WeW|JrW&GMUP)sO4 zin8j$$ES2!v@PuaZl-rDmO65d--St;nauT_>13P(n8yP{?^NOyiaX*2XZ`j4RpG2Ue_Uq``8wSx4LzBIu=cOs9|75H=Z+oZ zAB(Dlgi*i-9Iri5l4Q*op~SK1t{FD8-2{*1LeJ_0;@xG#u}sQ{XHv&3EruPv0x`_v zUtrxjb>nhr;M()MqlNk@#-WE3B_*SF zPo8&_X<&%lxD45= zx@Igi7=16rnu^&kAWU8&K15a6h~q`R#>Jt3CD=Gh{YLtOV7=NW)OsS^6B;{ZlTEgb z@+%+L<%(K7z7Kq#TMde{?9HTc{9n_fNy+E9-#?ab_8aE3Bc5)C93)sm28U)r&1 z{1Wfh&aSv=rUi9KWd9hu?#ef_C#x#*2AF&a>8eDto$cl@t6z3f{2CcnTF_ly?|K!_ z+j&+%V5`??%9kGXR(_^r>=SdFrL*DTP$tc%JMUdXb(vV6QOB2?LbTGmZ)8sXKlW6 z`u28$r~)wMEOepJsQ({GLn5b^ z8nANydlEG>cBB*->1q1PX$8eK!}1}Ni#_%Gq!I^&_h%5?BZ4=_-^{q?wDQ|JP*@@| zvKBoN0E@~}86q|@DyUqFbbVIaxQ+)|fL>l~w%yX*c*Biz=$VPn*0h(L?}9lR&>ri^ z00RrYcxN}A5En>uB-#!)U%vt1VwSzXzW%&jJ%q4Mzb%SS>e*eJNk;4MbjuO|eQWTF z$-dTSbwWcH$asFjfmQ&=@=3r5f<wFxAsf>;7S)vK+L8~TxtLYFr6p$8cJ!{^E93pD7#|LCb9=-Q41FibNa z#O`O{o}G&^2$)jxyI&5Oy)w+kF+6jSJ>xkNLXJ4AYyyApS2Cd@_*HWI*EQ3Gw2_ut zG7~~DO&(}MPW=!be%EkCEHnC3+uuOArWZr!PXK-XrlMlO__VyQl{*x09As6HGlC_# z(#if>=rm8tB{tK~h<5N#o!jxfZ?)K*@83ch$HF)8DVP}g^~8-5vu}U~)P}1RVyVV{ zc8Bd4TF@GgT*>Fhpp6L-r#ILgZ9^sS;(m{0Br4dG22*$U>sF8{@kHImY37oCAr*x}(L>%OUs1@rzxn*8Se{g{<4jBh)5 zbWyuLbLO`=F7yE56hGcRs|9KAS%szxNH~y=!c*I2@xw(-)>Y^&vKyypf_eEQ7}@i8+HLWB^EFDV5k&j4VH*BY>_ zwPpVVP$X2>MX%jlvXYjo$&IkFGlSY%6K005b^M$?IR9ltu&bXjEV~&KiLqkmZ0oGe zb(%i%5+BC)yxW(T^~agmn;|neN?dB}!^7Io@<-8h5hU!7IAVD-!Vq6M#%a36%Ih}2 z>fn&Di@BnlES)QLhXKvQ{MtB0@n)dXJXUgbsLx(lPcN^X4b^?vJ&2%f1f&S%O^a%G zm?BOf1&50)A>BAsk5{chucl~2X3(uO%$;87Jt)g*c^)i}^4u%tiGKcU3aR7=9!39S z)oH?S{O+Y^r%7d0p|oj^6m7j96Ch89RnEw?kt_{@ushOhw2Ch?%^kb6@*O~0vr}VU z>Q4glZO>+vg;@zBJMbzu1x;>3uN!L=(XpZ$ENS$@VO{dw-;J9EygkvMrcd`qF_$H) zbs<_A9x)Zhm98`KTaruS-?C6m>8nnx>DKIeGHZ2~K8bdXb;LgT6Z`(!hz(F7>H3N6 zuymOl+cx|UPjT01_tof1Ho?Hv{GVu{22EniCbh{umKB%^)q{Dh@p0>qXYf0`?6Q7$ zM}B5XdTv6zzj%H(KnLyR1}||?1eMuwW>fj;ptQv=M2(G2Ik^d8>&dlPbI?L#-TFe# zjS8f;?v}I(k%QeAT63KGX83{uC{y-ha|YmXh0oybtd1jcI+JU&lhc68uWdUssu_ne zxLs7z>$v^+I_mlFLGhj5lrF6^bLEt?vB7>`3|4C_R}jSxN43G-mEl{Z@pQBeB|mpe z;gKF^*h7&uE(7>aEO&cddA_AMR7}Kv)x2VON9%m?UA9ifdKp}&`}K)?)E%2G?74OS z9aPq~#Eb}~RVEJqyRZvvJNuihebX@}=W`hbc>+08jjRER%IQQqy56Q3;uMU&wa^Xw zH;jO4@Ll?xcq%5@-v3DRS2vlWJ&l833KLuSlSaY)izE~5=YElHBz}1_z1i@kB*X|| zA(3!Yb*v*&b+zKbw0U@bOn;{`57?*CC8&-qF?@c2qb>mv#h@cleHFQ_rSDWDdVT8) zr=?Joe9=0)Ta^5dBy!MS=|DqKt49H9+r22^EZ&f|mzearAA5&!3t732KARj&h=+vx zo3=5c2}${ez|Meo%y%?!>3s7C525{sm9dcQ4oMH;+S4QLLGkWL-=mPLb`BomCw%|o z7RO(M1o2m?zJacc>wj%b6=4b2X&(h%M~S_9R*YuxGPYioO+5Av$Krk3xMtzqQO;ie zMWn>UMO-rJlTM)N|8Yq9XXy3Mn`MFQ|Hb?H&i^;w$N4|;{{OO!NM~*YRZVwx`B%~A zO3!rx%>)u2M!IP!N~2cSg&qGZXsdo4>^|K6Js;!rIJ9Bj7xaC9xksNvX#72*;_&V9`>kCuG1eP#Ut@_j+RN!&lSM7p=#f?d!Sgx)fK z-4k7WoX=Y$}|3rFDBHBWMo$jn3Hm3o>EU zpam!5K(+FFSbinR3xyp-j{Qf7R?m8AE$yD!fow*JLOLN) zeS|m@Bg9w7@p)*J*M0>R2)TeCU#QXO8Qf4{YqF>0#}dUCq~32Qga$|2`F!&y7M^2zH z@ou4XsB<_-TdE>E@kQPIUosJ}IKpCV>sXJcw=;@VVrJ>bULv4}cBhhFe>wZBgdA7a zM7^CwfV1u8wl8y)wTf{<8^H={NQLx7Z1tV;t+yPgVaWU8`wVA4MtWX@pVK!335Seq2WKQU#9 zl?qjj$mp@D0Rdu!Y=CyaPv3Yc24=P44zIXDgpD2e$%9s#&JU6NgcRLDh1Jbdr?}5z zUiEOLcE^5@iPy21n4{w49F)0RNZH$fMN*in7o&t-*J&=rL@^i%BI)ucu?HyFP$1c& z#L=?K1=jyq!bn26NFKRFDwG^h78qoS}w^pYziX$<1{Rd%Ix;e(7aGH zuNtU&5pcu}iQrI{Ya9*tcr?-XLa501SU8Mh{e%+iNbo3`OP^gKJvPwLDf9*pwFY|V zL=p{pyb{P{(TaR5a1~5877V=6)<3e9Lfm*>d-#DI%DQMaz}7^NYF3}l0@FACC!Z|4n4+H2&@RaWMD|=$Y0mpK|s8~C;YYsJjT)RF_vuFCjhyzhnde~&3CRNwNaYISu6MYdS1WSOQjhj z4#`Q>-I&>tG=xjSI)Q>{D`*_ZEakHdvoCRH(wCrtd#q}oF)n;{A8$^D-q((QcYGac zj8AV$XTP(2znA0q*{P|8$QC@7f8wX3nQz52=9bHqNpeK9N}?M{!Sg0|fn%-0K1J(O z1;MZPqPyx^h5H(8+?*|D%m8{mCb9I5#+Z7vu_Q#?Z3=9`F@a$a(1u`J$sbTv9h}4m z`wH~coSQF)0yp+vnnV%XgL$@=$$JI!19a$`NJozzn+@^9jZ@nbju`3e4+wL?zWa>808dTA|u>8$q$+%5BH-;ioD^Lv+2Y5rN6Vpw*&^IrJJPLg&_tL>OQA!h^P3VEJ^ivRghp~( z8q{Kt8=i{);oxEWs6z>0pN*{uw{-x_oG~v;q_xnxk|TU*W5KUi!w8eQZ8;gKWa+`)rbY{g1@}4x{LkzVNT~aYd4s9-e^{E98(5To|{>$=}Q>b$i@decM;wVT~NO~8Zof8+PVANQMrnfu)0XrK{jXFGW34Jd<;CtD%YrCo;Y87 zt^5M^B2#3`-5q1B?RWU6+m>RP=`f{dgxx02X_bEn#F{teg41dl3_g+vUc2VfYWKT- zb_i3ZBFUQWp~2zX>gImf<3$fBe3j0JrFaY>H)9wzr=qRmbf?TOViex+6*S7tL1leN!C3_Y zfe>lq=qZ85HJccgcm2k44tCh42GC4p!-4}6X2i@RbdWt{o=|5lRg0Qpp zBX9;7ieUf1iyJvtYX{_y+li&Q^7BJ#8=L~*4ZD9TIPL#bLT~wHGKAGWO7?FjTK;4` zA&AC*z<-8gD3%tXVDhf}{@5E)i!a#&LWTxLfawXNW{z&!dsm^5jhd0V#U;U#Rmg8C z9@aAzF_H*jCLoK%iGp^>2sFB==1>!Y6fSQaNeNC|UvzCrNC_LDIwWXQ0ep3jtC*5i zg$kmU++yBIpenFWRiQi`%f+Kuk+UHvVgOr{XGDf{Z9G{Z6W4F}+oLQB(o-M6Ehhn# z1;t(rH@)r1>9v5dQzbv=)2N$srE52az_Na#uIXBX`ur+q1V@HeTP29a(BVg?w*W$3 zc~!yJA&x-R4)6sBzsGFthpXI`cOR~(sCnHj!A3h&nVQ#%wUK!wtna->6}nAigygxQ zWN3-7VxN=T`1h}(uD+we6KfY>x#wBLkHqk(u;Q}5&%McgK*q2oJ0%e(V0gE})r#CR zzU%6W8BP~)hWWw{8-U6Z%~gxhTg%cT6Qeu;Vi>3uG$z3;q-6;p!Gmz(5n^0aR39du za(oEnr>g(7>qCiQf(zI`3!2tihUoM(S)=m~J)o4BQ^pQI{3_oUBy0n6q<`*bz9Ve| znSDh$7qesRUJZsU&y7hTS7=z8Oth*I4?BGb3FyU-Za{w!Qjy|GOhwzVtlVQ9A&ubT zThd~>h<|r%9XEIl5C1jaa@s$D8C?3e`HpH|&%lHs(+7ahKCzrdqsUawO>3GNFrxDFXEfX_R zf*uP&HB>uy?mCviyvCsKN>eKwC*sE?6UL*I0~i!SO*FM7D%5QS*M6UqaB5RW!)J{$ zTC1qqp3XZgl`M<(%=6&%ZrhEHgRRGEbsW$($4eeDDH+H|Nb3L>&Cn%=3o684*Wksj z8I~IAJx-TJ8G{pBpRs2Q;?2MJgB+vapl*lPIgO2#5;owuaFMDgVtr&15hRZuE%0YP zzX$PNiV|HZ$FJN10Lq|mnD!)-Uo~jk`y76){_}M|sEDy;vt`~93KBi1u=_!ne~27} zsgAjUo7{TM!~=lc0<-vjgRVU6$|uEV`N^bpD$yfU{TJ0d{F3$z0g?Xjx_a#+p=KNE zuV%A$Ug7AE12n$|H3}6Uh`ob^cvU3yVhlQxCXPi7IBy*RqABk>RS|u>i%z|$Uvfwk zN#{G`EhS{7Olf||=f1gIBk7QK=P_%`{Nh3R{p zDW5n4p~txmIPGL&+8o!7Hm|=iflyx1T#Bc}OxJ`Jka6X;IP+6E74?Z&>hL%PeyG*z zHwbKQwQ=+}jZ)6udn0%XnmexjF_vuCk}7qCOGaEn&g&B(S21F`hLi7HeHVp!V$K3x zd9sxw6_CIMUfg@S)=wj9Hbgk$8r=ZKPC?4|zP|7)=)KFfm^O&N8c!>C1R2Kwpm z_F6`#@7@pgAa+AV=nJI*1zzJY_^yKl#{HS%%mLufre<0xCQ>|*54aLzjk z&G`pKvDm6rBo!5#To#MUzXPztzI5%`$90RcnkhOi)-p>qyFQ&eNGTb7N=9Um)2A6}se(Wt=1_WKa9uB5kA12T_oxn^K%tjG#29cH71 z2%|yXKU6fsvXKpYPeod@zmn0s^d zqvHM#QS=TXk*D9puzfcWUU%ST9zixJ*HF3m+sE7dLjV_PO$o9$LR|E*_Lb*ui43)* z_VkD);OA^5Z==CujOd^Ff(C_Co)G8sveDmQY~_eGFGh zEZsc5pfg!?2*lut8!O20KM$|P$$Z(3+cZ>7Gb|KsQFx_P&W#I^$y=iR1eoMFOiGT_ zgk;q%`iA<}Dq&pzOx)pHEaA6{ZX-n=TB1)G_|S zg_UIL&!;H1lKQt=d!{=@*L4iJDu=H8NV(DE`D4e3W-=g0POqT0BCAvJH=6VE1dBa9 z25K<9YDSrP^>&)-Vgja z2_q`4I>)(=M(!9Bg#sCr&-wz6fPxR^+Q~bDM-0tR!-(U!asUT5)G9RNQp;n-Gn}^P zG{EOfXEs8B51<^}pCVs6ETc!QQT|(m7=A}}lmd(Yrxv|nLx#u$R_w@8z&@)~M((hU zW!1?l;1LM&tKv4DJ{U9vk>#HU>OX62)_;D?Y^?t+V|@w+rTJfcd943SEckD_d~XQo zFfeRh4(}vcuUhEg@yIc=Tj6SxLZ01fkYf6%l53>ySTv{(fO67G} z$|dx%s;lUsz>IfoLl_3P zdr6RokIMai!OM8fkJyx@rGFDtl){R)fK}ziBz!G7a5mwS=hg!G_~2@4c$Zc|nu_>m zh*nn-bsp(yMA}Pm&2m2rIg)h zcK{uMU4Ea>OX>BVQ5aR!Nlq_xlXDm|L#ky>Twfdh531t{#0r?J{wl7NW*Blb&r4hq zy$vjIH%kV83Sbs!&CR5|9)H3nhiXfqmDJW8D#M zDXOFplFsioTi9=Vp+dMsKZCE4Pgfm4onC;vpy86DW<5#wx~A~OP{6J|`VG$-`(Y~( zs^w`Qb+A)D!PQyE$(KVRolKI8Q2dESTzLqc)mbkLLH>Zx8C*s4APcTk`htK_+6~ME zeMn6O(v3?A`I;wXGu#rGyNU`CuOkykm#7P3qXj2*pXT&}IQX#^ za=4}fU4TC?vFp66t-n3JpxuOwJG@(U2f3b~izA-^^}ASp;#LdT8#BjrWc0!ZNRvss zCD*F1B4~7#3TrB$P$d+;yvgi)a=#sRAI3{uV>|wME~(Uhk1hgju$li+=-4aSjgZ5% z&d#!Vaoz;|LT??wB|M@nq5(`&yniE6$^f&)SMT4JOf zS1QE)O!ASkz~zF!9`yW|UPj^jER{!+peQCz=GydNa7asrs%?)rJ|J@N9!YiC658JvKZMK`EU}d!4(tloYDQ2?d@@F^ZT)zmX zEP206#|!U~@n8%DVUEya?vC!#%UvmuzJL_YE9zP$H zcv3=Yg=kXvP3)1X$8qawM<)|v2GO#_Jke1Ocw9i3M~qa+s)GEuw- z(AW2eOqv72xiKd=Ozxk^_0BZS`AH=D!SLgfO!b?G8n(nG4_zL&`Ex_N$?t_?pW0h{n*+Gr z?+oDaxu_+YL^M~EM^^Rm`Q}1zt_nn1g$n*k7@8q)xNbe7Ou-}3aQtjMBUVNxw>#_H zO%A&e?k2%N`M7`$NRsd~0S-b$l3UzX0moB!5nlz(0Fn&6j$ceRsn&W0Iq_ju7cVl{F(%)`4Fhn*fH&!i@>8 zjrH#SvpsZYye>oI%0{{4r=bE~F5e?s6StMcD3-W$WUn!vziDFI&^tjHIsr#Rn!Y3@ z`?-)+zF{a*4Xkt9QH#B27Q@O$9Ux56D2(x){IhO6b?Yj?jQFJUh4^gJGW?d#AQ}nIn{OC`Dmp0jvnM1Wh1;cS1Yt4W4>}QZMnQL>#?DH*Zuiw=i`=}D z+JWkN01y^YzCWV#6F#A@t1d)Wb>Rg6~WHL_Z$?Ltq!cUjThNy*)WCXxJ_JnT8Z zSP7+bm^c<54rg&+sGdazG0@<+jBD7S3Ky%`K)?o$$xa;Ku~prfx0_E;q7(>!DT=rB zedl((-v`GaC8jpXArXUBGPI*9cS{r9u}JzS69dLI7z8G#Ah_X5wf5nC$=TvoOf-8m zkf2eZNlN(60*S!7B7S+?O;5ZmbRq}4W_DYAfn`uBYfS;;I_EY3u-xn6=#V z<}QVM!J%C5fm32qNYVxVp6?rsT6MM!zV~$;;o2BD=}n^1DjM!U2J9Y9Fbx1deYL{I z+t&Zq;>7QOwP`}{dLL-J9sSb z!pVRPy1YzkdYEjP_)>Ly!7%eSs?KK?w?|Rt-BPMV$IXV%hX_PZpEEPMs1+VY=_)2~ zpZXXAjxn^B=C4d z=2r<;I~T)Enh(D36WZJg%HOEt(sIoL+JD zi8q}2hU)bP!v{__k~JwyRHpPZ#uH}_9Qt-foO3gwkHz5BmA`8JT9x?0n+GchC2M73 zfZbIW$r^9vvr)2b0Fg1rY-frYmw{p6MehpHAv?VoE7GA3e>_{HYoYo;=<>t68U*ugTer zW!X{@`Yx7#iaNIOtV6~bTNOKjDoY;ifKAEJ+`&Gc`{EMbC+F5e?lTu-+(a5^xSD}m z_UNB!J_QU>_=T*nPIS|*;mg%7t7u3$$>*`|@K5lJS{*6LmsMGFxlP~Ylkx1fc}*2p z*GKm|BZ!POul4Xa>K;lbe(%l*9w5f;L1$30+#rl= zEpTV6c>l_6hZXIV?UD%Sh>c>+t@Cd9HQ^|~%x-WfX3rUo7p^3nltWIca ztceS8TKIE8;L56@BpdyTSL#kaXG{JM*DiJ`LSuS)0IW+2(!y9&Xz5j;@NA^0u<7e1 z0B{#pq`M=_jVZb+d+Z4k|C-n3!Ej*RL2N2YlEXL? z3A<>aZ+}yi6}ZuqAuFPexRIr#$-_!d1EGZJE>7>oQoArQhj0*1sSVt8J=U_RtOLr4 z4$zy}6oUYc3Hh4ly;mxRF}~a?yGWIEGleA=FL=-Z4~~WVw+xYX+n>)AhltU(NynG{ z!nJr?I}ILvM*;8`WCLd^CL!<|JEi!xr5{%V1Ymxl~|`<1jx0;yL>C{7EkZduJ1g7IHQIwMOs<= zgnFXra%zoGo$styHTRyaH{7jau=a5akY!p!oQw(o7o;5Goe)_>rpwA)IV@p9E7sd! z;dxCS4f&pt67+z10tT8eB&nh|k31$Q3++yv(1}<}#Lt?csR3^C8W1NspkjGs+Nd*N zlUw=JqX=12tvURX0QBH*~zRQz(Ra*_hG*z#vK>Uq#5r z*#_fR2lvWjU|NW^(UyeKMQm>H2|EXnb<%}DW$Ydq>=5zYW=&}8df&4W|nCKU6-QQ`LEhp)(?u08}K;Cjs;t%-mKkFd+RS!Qz+D`Y58GmCv^*tc`emrrS&U@u0EdFv8ya*L-u{<-Zza z`KNYP233!VaZ=51_X&&fX*~uYng~AlC1ZXX)~(h)v-ihTd_BrFKtT2DOK9vKjhvW) zJxbst`xX)A;YKw?0gpXZ?|#Zwsso-Sz16 zqh5rKe#bA8S-)Pnw{*5l3m~f#?RvfBj`RQ3 zln~C|0XCcd-3eWeMYMUQ{e~XLpNB~AN(EK^-zf;t|554Zq=C}?bIh7Z15E~6i?CX^ z=N%#NEl890m zWBI=D3+w7R7Df1a>&enAnaWAOd>@cKAEFmR_H zAJdSz8bse|KMkQo7U6xHX&49rO8Hd6_OdjbtV@5}w zt93IP!u{l!iRgrlxlbS9Dpt1e_V$2*Fmgfoc{C#fG6|>Hmw+3`{(hGV5?FXmlb~!A zO?LG&a*;*t4Zj_oIf#WLVV+a~sim=7}T=ENg{8#m8Jj!?1gu5{@Lx zW?+s)dsRdWsZZsLL@2M)|10y=%S0V~%rg62%N~{yW8Q8c_lgK?A5Ov|k8zeR0_>sv zf-`K6kS6(MqyJY#?x$ZRlQh&3vw(JciHEt23Cm={xCNE?tY7cjb0{5@^I}tmxVX;K zL_nH3{!48EK%PQeS1hLb6qrn=ai?J-p7O#oo^IsBCmKPCBxfz&bFG;;U&%wK5_j{D`eotNxU- zbxk6Nm+mOipr{S9x`Tun*LecDqIa_{oWg+Lr`1lRCx=eG6q6XS5z@jUF_gN;TTQP2 zb#6l)rJ2f7-UpVkVuL5!X<-MNJkP3Kxjj+#6P$(ormX;2dGJbhh&rNfRUBCL)aS=^ zU?ZefFX19%ZGCM?|9I^Yrd&m+QlAO zBISuuI28kADXl(^u^POM$Lp5g#QhCL*4#B5XT${)tkI;0S&a#*RI8g}97ExEhEqZ| z7u-8qq9U=Izq(;O!&pI^F2PpinFa-y-ag`RmP5*USls!m910v-_36Es7g82S)QIdi4{{R@UiX;Z{ZBR=LHV zNg$(D7bo>(&!k_07xIURMsm!WHBo+R7KBtaF;a{u$s#zq=zVgCJ9~9Q-_%jKISU6J zd!!f8jb^$k1tqHTJ)xf@hWKY&TGxwAp84CMx@f9z;XomSQVHs*rCX3#{4>#=eK+H@Y< zs05z(4N7{j)#`5MNVO-DGd+z8o>m6cX?z^8EMt9MkH5>wAXmDLe2*-tV&X?a+=^l%40v3Pv)BGw#bsY@Kfi!p9j>T<%fdOMXqRG@>y2O-}>pHZ}L#;^cH z9yFd=Atfj%Fxe%vVoN57j(q*ktpW=LvswqMYI3sdFCadG8Lz$g*BodjY3^*}M?e^5 zf_{hMB^N>Jb)!WJfL>jh5PJE^jFjW_Hjh>JE4tDn>>sl+FL-#=;VYr@^>&Ksg?Z~ELn;;jPj<%fnU0r@3i_MStP}E(yUBSPf@nE|A2%$`s-(8kY3LHMkrIP6E6UF z20WHsK2{RxI}dR_df8u@V1%Y7Oeg2pXRebv6}%zbE&#lLWL!wQ!cv3#H;07;;7LqZkY>Y@Hif5P<#p6(dgbqr&gF%!$Hg>l7`$(19fmsZ0BFzd=*Hha?B(Iq&Lp zZ;&Tm^H)aj3r2tLwQ!twOBSMXfNH$PC3H#>sV~vBx2mmY@OQsgi{ak}k6*{`Cs$L{ zK)bU+s-uHj8apOmDBvf*-Jfnm{DQ?We+j6uyw6a35wI@84g0QuS>@^Y2{QwFpI7hgu>3EMQC4d)>OEJK-Dv-3q?A`xhY^aTa-h2}>0XRhP73`qKYhN>W{K>q{0L((CMe^XIBz-kuJPVD=NyWBeP^~ZT z^ogFQxUB~`>t6W6x3smZFmi5p2Juc`{!h!%k|fiN^o;kuq^(}h))FH#B`=aS8lz|S zBYGs|^@r<8di5rT%E(mH7e?SLZMxna&tTP*KzszMwpTj>`*gXB$-1TkoTkg|F3?lY z^|oZ!^#P`cTwa5hgb^>ttB~Z-Edl{rBcXAcW4y!#Z1_K8$%d_YBa`bfj*P-`x_Y{& zsgW5;XATvQd8F&<^(HEvCPE3z*Lt-7ps1)YLsSBaPn0ST+x>z2g~rrmS;jNYsxI>3 zj?#P|F?kS+Ztr=xv8%1SK;c8EZxGZRr@-`?qW>>auP+820ERk&5k4i$QA00-**}xL zlYbBLou41?hg-H7wZXkBGB64X?je%4{4>LvH+d!JE}EL^PwywY2f3$3HJSV=!T!(u``vn4BFDRPUm- z6Gy}MTlW~;1r}*cGgG<+yYluB$JIrcNUwNcDqC^cTb?-{(y}6${U%>;?iSJDv0>nXLq;+})Qv{I&OAJoaxlJZC z{1AoFpr=TjC;hbi1AOm?k`c)sXd1c0us4=b zr;QxW2_$^auSddVnn<#a1PSH48?9g78D%O`MhY_08~)fa?g8N#Kd?M*iOjk@e*{(t z`m`)eVgdm&`6&D-9&%46pj&$ypkYtAY_%k=6EX>zxU(lKn{#>(XUKqCcu1Bae=!ID zoHmXZ3wtg^@?ek2cfF6^39^Y=ltvR#2@n03pDtqpp^|ad3J{ogJh8nt5MoR{EMi&X zgOedxo!ytR?c63s!#eE#2m@q3On)03n_Kf(vBVRlA%9j6{ zi{|_GR~jSY67r(Yo=3>^;?57Y2{80dPhj6HIc)K@sq3c&SPN`dZ@?d@dGu*QstFX_ za(`Fek<+tO)j|lt#s?B#;=7->>mET?A8};CpLZF0n;%@){+cv4LjBZf(RtBg;(ogq{b$~{JvkzZQ2ynbqfEok)7n}z^2vSPN(Vv)JMKz9-pI17-ZPQoNU1#&e;$6>M45sft16DN(01?>4wt;6I}B zaFLyRqHl+Zo;PR5Qj^#I{puEljbPnyc{9>W$b!t7jY*dw@!Hmh<`71X;M2rxWTiGQ zNdeYGw9v+iRFoa7r8rFDFNs$~-2f~clY}DZI7=AW?xxze0`DPVt<*cI3Y1pvr+T2V zFC$B@|D5xZtQ##rNA}hJyl7xe;auQ`ySdg*{pnnYDWL`@O+!%?tA&G}Ls%|=L{L2R zTDfRoVBttJ`7C=;!VveiWBTnX8mJW3i~UciKTgv+#J9%tsZC=g>b{!mJ_cO;u}VL~ z?lpKipq6g~0j%$WEOIb>1xfEh$pyGPr^Up|?KA1X9#}1PpJ`M`OL2Q)L9qW0ahZJh zL(h`-HbRA^J3~>)NsA4<$z(z8$+!<=VxLW5tI?uLZF5`4dgaL=bAfLD{39Yt-#}gg zrHtjnoa10-+yJMx-9bzwiwP7Wn;9CsGGa%_7=>byb459X+D9}Ary-pusLF)%m&zfW zeyE1k2>g&kJPYJuujp|W?8&czBt$I_BUCIV%LuxfP!$g3CZFG(nY$fDETuJ!X!^#l zj$DWH*nOjKp)#pE_D!o@zZcYm+ZWyN-9kIEVl)D*OdBY5{YjnK)dI@8PQ+B|7kqe0 zrGxH-ZMCIK<~gM*jiun?W--CdMAThp0`sCe&_?J;FI{>9X^{PL$OtI9>kZ+AVYIalHcNGBbMP zHB39LTHr{Nc4s<8CxJ|NltvSM8cw;%`m`A^?DQbIo&|d^DZHV1yE;y<6$;!rIOrxk=S~?4>zj}Gm56uuTE`01wRW!o9`Awn zMnJh=0~ne(c=b_L#p{OFf^Os!y(m3h*iCuL1@z8^wch7e z4_v=-h)+tSleUb%?0L_Q%qhFfNbq?p!$vmONDM~tli~!Fj6+9eVB`|DfR$3==rtvn zWgjpCR%j%N*yQi@rD=jD$E_Vk1rZ@1CP1IpWd^8=SphE6riNoe0Vka}mZ;MV0S@C| z=|?Hu7%kDZ7i2w+qL08~Q>ZoaP#0`$D!<0`yI#&#lY~a3o-Ukz$OyBd=dY2M$#N#N zG1{#g6R#E`c$soZD}TroUG()Bjqp5ORVRzTR32f>N-7BE_+08a;BC3!U^ICD(~SNs zf)B`k<%NeiL3b1=fC-Z!t`A>;kj7IF@uxOJ_mJ!8OTPcZ^@^Ro(jumGLmgxzp?f)T zFz!!C=OC3NKO3O0&~+t88uTzU4TEII)jWTy1U5EuRaSyO?L}DKa|pscad;_P`q56jeHkgB*B$8j*UP49trp8h*i;Ql``AHS$HUXt?Ug zJP;b~NHoI&#!U2U77CFPOGum*VmR%Tpvoi4#oj+fk!(1i^BP#GU?({Vfi6SM09u zlW%mx29Or6F7FG8-vY@KuE^A1tLI08ig@ksdNof|WR3|HzlyLW&rtvH9?qNjwr^_@ zeA&C6d24-kPZze|%>kgDw{B<8WjKNGrSR9BMLbK?6*o$A)991PX)~(h%UU=BpFtu; z;GrpDueK|UlXMAQ>p~4SP6U9m++YqBEB4qAc^@YVkoro`{8|yUMZ31F2$;g-$ke6z zP%%mU3MvY3${KHz4Bi1Yf@TTLpcIuKaq;=-eYVtpJ>AO6+-5_?ka%^H7Jh&ACXe<`r_wmj*VF;m%%O^cO#jj zuv>KH5I27csTewoaQ}Qy#^9vEYW|>u3zZ)miIu)15bNp0)F+xL2$~-!g{n3;fA(6R zPjP`!YKrjZb9$1$vT@R@of_>qG`_UbPgN2Ig*mWU!gmr@k+ zYm=i`{tqF}p(NO%^|OVmy`0q8?iSOb}bAe8cLL#~wH z->I~*7ta#Qjyn@0^>uMD`6sRlzo#>Vv_zp-JhRFDcbyBZ3!^14GADy`7zSSTpecQ! zM%1v1(=r#o|BJ474ze_8`UTrPZQHhO+qR}{8>g*l+qP{_+qP|Mn%nQU@7=h&arcjN z;>2@)k(EzXMrBr|K-G>pJW})PfR%q5p%DcGlmEA4_J3Uh!Sz2b0nXI=df-?9ZBRi* zN~836nM=k}2W=PC)++~Jul{yVUC3YRfmmIAK#!nnI9+Wny*z_`RfC=9r{lj2ree&* zWdk;SIAh*ZlO?FV8?NycRdW4*91|C{7_&A{MBlZLalf{6MW}HsP_Fkkem-AU6gGMC1Xk zaZF5$5bfu;#*$rZGvwhmfpBo1iLC3eQaMi&i;$DKiS*+pxu`FKooxHM9}*Ks5uAi41*;YdwT*-cvKd?89qs=-#<%t2gd#66%rw@`z*_IPLQd zKSc5^xNsLy@D8&12=je3uqqc9$^s&2bv=EM@vyvu`E5TKZ~47At)VLTk5`S>`cfdn zm3!_^?xE(`T83F*)Erb^$5DYD7z9g(C9a!rMDnSnWGl1cBB(DLbeU0~aT%FQQ=^p7S4h}bGJ(gK#`c=H8lKP2*SLd<( zlnNKqr{$s)X|&>Xad{Y*I4uk(T|v}!kb0%VB-@vYV?BpdeD{ZoeJ!Gk&`35ld5~s0 z5XohLR6;{4uCX~+nsTxUgHCetX2&sGmB(LS@v^KX$k54N&c6+o48rU9$YHL}{gLx51++Ia|HXC8 zH>B{NamBL5C_e|D6)x_LAu+@3I{fr2m*@~f=j`f3nYRg;PR50DYrRb|XV>h1`?O>8 z#LUad2OxE%Hjr?DL;g7nI-fzlcMfXrgZc(cv$s=}-N05Y#FKOb{`{QgPEa^~awBDo z70&m}rMIJ@dNCNR2g}MLTFtiQX>3VK?6WQmj1`+tZ2Kgc&CELI&42sk4V zCEp9c_pLQtW5o~y#|I#H^v=OBv1q4ZP%o*@gu!Ucz%J{3mrCJSm!Cw(kZ6Kg*>%Cc zS94nerChR6@Du;DTKdl(o7VLxK@m9~zhwWxEX3ysjN`-xCp1Fq69 z)ccV-#qwsxWyTy&f;;Ev(r^BsCmP`hAODuwQ`(u%CPol%WF4SuA`Hf|7}1r%B3AZD z_!jCrE{sHxLq|wXZ_!3zH%=T3CST>1A|k{el@tjE;WxbxF(j5JH)Jw-DQ?o|OjV-q zcmr~>=lZ*fFGqL&{jCtkMh+IrBgqs$x+D=+j4bEc6z$2c(Ibg}vYK&0R+4SpoI(T# zMD~+88}S;EGob)Bct{};Mx3)!6!|BWOwZFDPHTd{!4ZBi=FXh;B2F9#Y@*dDQZx1U zdm>!3t8fc`8>A_K0dwfqKQVCDw&nbMfep=9<=We)R*14VqtT`%+Is9wHpQNI+uwYp zRD?caNVUL5Zlkox9<^y=vrWggDVW8=^Xg5WMnCKGfC*R+=+OZcl~Rgu z{3pKDG8P5+A%nrp;BR+gdh*3q`nA}8+Tf?)%r{gdKW-uRNI;D_|o zahH?#9k)s4B$ zFrHzqb70y@aLK1w*}UioU~DXYhu2t)OTNKTmf(rCgQslXFn9OW=HCT8XpXF3Jt6SYz8^&T?hO8i%XV4*pWP`KI|PW9&)1n zSwrfvx&mx7vMn=OHc1slsN|MhNRs4i)s;7l zQ`Q==TL}z?W@rA53wI-(HScqMj8Gzs(dj zoi+OP_%zzLahMkjT3D5nj?I&#nzW(qbTM0N`)FpVjpF{;EG{c*{cNF7V;2!XaheAaCJ`5>uT~oBvzcP< zETF@y>H$ADBB*!=O?YCCnJ|i&KOgK6#OcU1b#q>*Z7dT+zQvyhHQlsm0INkmJSeY! zk(JlpB*WxPj5jX$jTMbzhLTW?cne54+?eO%z~UkQ689`#m83Ec-BzK0r9;Om3IkjV z?Ar$=!6Z+v6H2aGgdcZcHfs;0W3jQ&GEi>Ab1NbdLPEBw)aMLBOjZ!XxkZzMP5Y%L z@~rZ_PSAC&eMiM?exuxeaWrP?i;svpS?C_*0AjEm&nh&;e6hA}H)M?<`TP)UZnrE%P>;QF#>a&nFt5lIE_0!H|nO3CF=O zR)~heA#IFO`hcKVr8qr^I|92BdI`G6p(b?)@6@Om&F^@px3>0LM(?ODFMQ2`*~{wc-UZW z)R&~A$W|9?XQgm2TLx$#JDacNVbFP~u@E+w=r4A}jxzolhtd5KBuy^dLr^KUj{%QP z25v4Y!pr3ReZI~ad0Pv4odov@+4nN@fg%++r-a=V7~Q-5`B0n3C$XwLSGy!Kx7L9_ z#iH_)Bf|f51)F4|JpLDf67&J|hY)nF^zk3l|ek8xzo=2lmWM`@Z9M8-rM?eN)|c>ZA{9Nk$&CAljPq7y4~6vQ8{BUPoCUR<9I1rR33h|qUMmZx zhG<}Vu(jRCYDxxi2cq|kVfIzRFd`W3!CGSnj;o|k6o4Dm?gBtpDPjVpa~t#n^-xsT z*T$PdWF9h}G1DIel~rjx`zcO4O*9`(7wPpforCFG=+;KGGE%h0V+)n_)=JIro)403 z?8@fSPqgPy{3P{BRkAts#Bhp?5TF)S*El#5bkr8U<4(@uKEXUN;Et<6@WdK~DB1QZvuV4e&KLutrjn*Q>mSUeKIe?$|? zyVKB2E6yyS%)?+8ndBgI0dC&r7=t8nO@xin%~L8C4Hn$g^~Q&H6Jdn#3l}CZh6bBGoVwIIxYQtS%9mMjs`}q`Z?=gY4KEXZV}RQ zY3yO-?FiAgh_XdvGT17wo&olT%1Iob9}x`5j8UohEB}f#n?febHYcC(FmB}G2iV_1 zMO*BEal6K~IO29tq52Ncv&GJBNEA!bsOa3gN+ErB@vbZO6RbIXec!WJOn&MBqS?~A z$gH=E_ydxVflMj6ZFW+)mwAHP4{`?k3w1$sQFxCxGr>%$v>vEVwr-hk1jw9(AqywE zG6Tn2SKNIfbz{)cR~IsJiz@S{I%x@SVNZ5IgKZy9GVi%BETY}MypCh0yYS9*6snYA zNY``n`gm9`G9-J01_=MMrn~1Rn;)^oY_RnISh-NmA^=~BE1=Bpg$nRpWrNj9Wdlul z-@ASB!)z`6&UoD9vxah)@_9B^Nndjq7ki+miK`4M8!kj@krt&moMwFe!FOzdWx+@drB4 z>>_XsH>oIe);%lyhVaq2%RJO$X$>@To)c_K!ciYg`kfC+H-w=he&Vqwi>w;=mqA{r zD=(XbB+@^y&9=~^-$IQugAlxkXKbmut$?;qowwU_q(2WXhp0smqjC8|>^t<~T80Zd z)@NFAXl{$z(&nef>G!(%9!$))Eq$RdQF$aakP#u6iO0(?9;0MEtoeyl;7G~9juu_r zBH~FIyzXvC$u#yi;ibpOk#hfHhnTL51Se0M_=qUXp9egQ2uJ9_-N59Ne_LZWD*{#> zKdrSJX(i$!HH|9A5B0Wq3Wyr=W*3#x5;Zn&wTGN@t?r`ofhm4V1tTXI$;)oj_B*N_eTkypDc!Eu!M%eLSyfKO}3%; zgxrA>j23o}v#`eDNfJzVPbTi^LiJ?9%%pGt$mE$-I#5!hr}UR|hOLLyzv_#{>?R#p z7OK~U?qj=k-khQg$+%IY0liZSss18ta4uBEgB9RfF+ z;v-**L1Ac67M*i@%M#8UvRAS!%Y%U1hnBXuXsoPd9vA=|>Nu(Sm;XomQ#m#G3U~l8 z8hs~=&EjO{L#&t$$aHR0)bhGbmTCqrY+_y{SoLo^1D~u z{`Nv4$(63$w@w!SVt^0|0~?ddps)kz{Z|sXfw5D?46%0ghd^2OA1cf8X3xjxv&3-I zt-$=Z=I|m-Q9D5W>*PwImEqg(?c+!&eZ0w(IpSXeSg_#>F%Z32C~6Lp?Y@50wFQd{Bx3KuoA-HZx8fHL^%x+W|+Uu%QG~9A>wq4 zOe_hZU~lM>!#B(l^{PJBF8t3pQHy{^KYeJGOunCUq_YuNa6oUd3odxxFC{GYJS~rw zxEb=E*Gc6sMym#9DNHd%J6uyER!_653UdW>dl#L+pAgf*mxd_SCoGGCro;!8Ewja- zIj*Df4tzy-l&@8#A^PVaQ`~pJ9@gQmDY@qWo(UB{nXV~kV3tV&*6|#ri2nAcxQ z2FLMrmWvn6l;m43Y4cY5vF@m_0;s`O`q4ID#fPx%0ql8t9?D04JK^=!bra+KAL?G% z1L0!!i_Uvw_2MzZ_+k$DP#k-AXZi|DFuaN#W7z_^rHRfPB%0QWqXcn)OWZ_KE05$u z_pS7pKV`%@zBYu(5<_K?Y(R;46obs!>-4)=`Igx>&m? z$nffFEB3~YbkP}nnraT7)&N63fsF*!W%Wu}nh zjv(7YEjiHE6*hZHxH@zaMOPx1ujTdO#aqc?^gtEKvDarP>Pir2&U36W9E3HjqeQR6 z)a45$ibQ}KU0D#yZ7bo;o(tlPTS<^=FTl(uLd>5_sj9q@%kZTv!|5RAi4{I^J<*3@IjS?4^x1s9>6#MznXY|RezK4`hg%VWWy;!B z(_X14h}BK3kuTzcY^SSLu|J~ZzSM;+7^U+vCgnq*)t!JZ z+T|e{?}Qwq7)0NIvT_fB+ip?s0E4YZmRPh@t{i2y+7pM((kn}_rLaNQ!{uU8Fg|>18$^DMpxVS&OI3+RESKlm5U=}6w7P7j zmsM-&uiiE|K)d`~(?Lkj;ZhK&uUaenn5c4o^c=8vvuhO|KhOugDEwPu#IDPfe3f$a zGA`dtwX18b{|V-UhR1HdsVOWB_ya5CCs&G2D0}N zR|3*W)uqH@G$<}!nZ$@@%^(iOf<+&Io$;r+Uz~vf4m`2~{>pjL3gNx3i`_DJb@G_0r?vT;)Lju=w6wW7<+K}Gkt!L^?)zSl9A#RfNiP)HltgvPB0-f zf;H!qv_Cl#9RVUAMK6__SO7OR2ZY7=(W`91|Js?uY*JQ$Gc>goh_UB2`u=*hAT{9q z$g6{nb_Ln2_^g+9rn_pGNDFXFj3}Flh7jjGhj0tUH3F0yYuV6(_^eygv*b=5e3%WW z4PS)CXblL!Xk_$x5YgpwkNtlk{-Xf?3y?Gbb}n?}Nf6q-+-qr4mC1|Fdun3;@Bera zRzC#T>ZC=mz~pB-*&J}N7Ym-vEJ*|Z7vldOLf{`J@dgUtNsaptVBeC&f=4^?zf9(c z0$7VG`(UJF;-3ab*X$*lnlxpKqVrsv=>IziU4+f3-Gd;dKx?Yc#Kit>)Sur}dYS~} zId5F|RXXqwb?zO!EiXdP<$d>s8_;eRN46y&-Cr8$SsLrHFO8z zeeuse^lgKOOkRo%eK}|d{dW-FCU(d)j)mgro898~-QvSY`@i6DEH5m=02BVpLST@E z{FsX>*(tH-*jG*=ZBD-Tir8KlQG3@|%kOSp!Pd3}Q4Wgw`a`KI)EEEAuaos#e}uUF zFqD9bD|lBWHA~fLEk%ZsE1d9xb#RU-q7KDAQ=1BG17*V1=C&1GF-<+5A`&&18s^Z!gKUS+9r@tPIk2$e%jxj~}4u zD~<#*kSHyaW3;l%GjUsO`Wub$44Dw00GpyEo82lc>zv~c&J~dfwOGa}1SIaG3KXMz z|0S2lH-yA1c&CfSflC!USVE?j4Bj9GN{OfTrn8mIuV3D)X;> zb}WHF5=)vvr$Cy6^mL{-;mIyNF&rZVMxahMGCR!uE1ul%i|7cusO1?DimbTOlnsaZ zjcEHjb&r7(k>!bNAiqTkCE?3>NQzeU;ScM%qsD`5_j}w( z#L=!<45t{Sle#G%fGbnErq1%}x9R2X9W%bHd0Rxc4852=&*MrKVKiqu``{ltggaqu zVDV$}dSn_4ucd|V(jX}UyN4y2{xJRH@qkFkqXLSlMB`a$-N2kDRgo(K&+Fscp>`>I z0l#0i7$s#LfN8H9o4NDwrw!vN zJvdEuQFS~ENSHV=kmjS`+2)B;i`!tq@nK@2muPFj6%IpkpW7sdSIZ;+5m40jt9S#Iv%eE)(A!m` za+g$~QIi0<-(>2Gw@$sG^y{;^!(6^~7fP{zcU{$V$%`GbtcM@UYI5VP_kb{D2?kBT zuoK!+_*Xs^>D{+(xv)B5F?L!1L4^R{nSMIB%8t-jqYa%Y(}Y-f6LBwR1q)QNOt&1t zx8r+(U8D=@|UpP_d6I?eM~ z@qAM^>rUzGxdoq&1BDtx8&R|%iF2Z61Xi;_{DqeE`gopFP% z%^^SxE7tyTSNT{BPTn=#xB>aVt%Vj=lphRkME@$A#(1lmhpOU6-l9;?l|p=d`1wPY zQh( zO~pillOmmgTUdgufuW-#hD~E+M3_i=Pe3p)Gy+x&oi3+_et6UMiJx>mRek$~`PLcx zlB@G4CLY%S=iJMoA(EwJM`!c;XvISjseZUdL0P-Cb`)wgU609F>&u}!?R!AbdoEyc zx(4G!4M3D|*6|wpoO#9?L;I4DSk=7rknsXnn^QQ6nH|7rR20UDH7t1rAAR4|&fC>w zt)DDo88j^C{n`|PZ2(Wdl$k_B7eqqod-s(h)b8zp4_aOZ3 z=8jyGG{P*QlMReHsbGO%CM6=Y4FHHW?N*%eUfl1yHz#kjA2xwCW6$6S>1Z>_Y|{Rw z1w>_VM7%A%8lJR$qH{xeCc5{UDVuJE5lEikAl<0j1PZX*;VQI`-aF^#D466Z!E;9J7eH9mcYwQqI=f4Wx1e+RRaE=z0(Tx zSRbn`;mNs_PY9g=EC0>8j9aU$KiN8$*i7}ExAmCVev6jTHzxp9UqUW5U{<5}x?hr5 zQtO&(hMK9$k{d9F@2;xdh1D678ZA`|1WxxZ@+5ymasN-@piUgkP zI{8XH)BoE~804q)draoA>d_8Py&bq{aXl&aARBM!zVBVme>>-_sDE=SU!WnL zdn=aFr?cn7vqRilK{JOB&t0_`KVj%HSJAx-1Kk|}%sHU)C>23zJpp(=$y+^SM=#1uaC#iKMdC77+;z8xd5+(AqvO$k0VQ0{kX<^jBmg9Lc}-v zV70Fs;x58q$FJJE2C%h@DQG~d%hvSQjv|69!`BPm_yJp6Y(1dE_v<9l#VWzdje0j( zo1NhHIB!qJs!r?4cAPwc+ac z=J=p!yb#sgUT&&g?X>=))-uJMeBGXqlqjK2+hP@YN9p#LZwWb3FG_nkuqhdqpFn=! zcybN;0(|nf4ZSSGt?$TYJX=6_;$l=PgZYiim@mIc+caRBkL1dPHzXal82ZdbNKTqI z$G^fVweA~O5@3B3aKDmdZgs^#eG>wr9d}U_trI-{Sz=B;J78#}96au+o$PGgUWO~d zqV3pJOr{go+@E7F-kl|+$s>l;vncdu6b~%hkjQ1=wwzzMbZbEo#|4|4`D54t2G4Yk z0U`9+QH8G@7VtolK-apE7zS9L2!PaOHcs%^?#5G@0Qi_>%)zWQGX}esnVZq_D2&l| zI@&fCo|K;Nt;a0t(hVo_IYBb;RNvaE12^NLY*XbtZo8b*A_iO-GCpuTGXp}w+{Any1j@r00&HXA0~ctq+6XM_3rk^}b4tQVvQ*!F z1=U~zpcL^u=RSusf!#CVQ}Mn?aFywWX{p(KG@4K#(u?ro58W?)4@xZFIzblCiZ;n z^l*K~TkDp`k>38zm!V;Xp1Y_xEpZ0Qeq$RN0DN-R4m(XH0`<5)_)iWg^>!ylfm7knzGj0A`Mybztbh>6ZSRVe-fds>NHHJ3{ts5fmbbq-y z;9ti1Dvl@gCyyK^+ry&tn5KTpYy#E;D@?I#v(+$zKs}8y?ZJnB>aPBn>M|#G_DUd+ zf}(t>oa5VFK(s*&QJa}dvYL(8gI*)Fn|wC8=2=BX7WxHoY?s%23NSAhueLttcW$8mBx)xO0EU}}gNaLdgCxx$dB#+Wg8pSUSijUX-wTT} zgzFTX6qNBF!dSl=`|OGXUUl2TTwQ5~vQ687 z=bNju2Z_XRZ(Sf&6Q|gcGDUECdef&7U&!{P?u66^4)}V?1MEag%*Sgp8Lq>HlAjtd01r$1X}^G9UaM5%(gbludY)Jg=5o9_#dK|u6%Xu+}f=R z5Sn-{dR6Sw!x;rKvmR=Y)#^j(^BJ^i1eMkEshdEOE`|*&PkrnEGt-8yv##~)07@)t zZJ_RopGc#9*|83RcY)rw@;BsXmr7UoZ=bt9)qMs+t9DW(=~gHDuUN?UAtQIr5}=Cr z7^yVQmz79T^u1~cX$E6#Xl_mD>iNhozA51wt@{YDpxjYJ%p(2L@mf-|)_fP5*bt+o zMH6GO?dLRoiegxvfq+@sx`+cz04;S**G)h3MPS5y#V~0EIH*C=FOj+1HIpE5zjlvN zmFl6MQvCk$1+By{Fs@DvXcVKW+Q#)8&wvYt?ClX(Y?a!n-8UG1NtVS{huC83-hF9d z?U9HM42zv2C!%{7&Be3@Yb#!Mq*$r859vLnT+ZT`chW{VkJla(dT3=c069rXMjAHK zcuWx)#mItk4~2+KIMDnow^|Vxz44qlZUhjcatr$)IDgpL6v;OLrx5EUxm%xP&yU zv2xPiXX?ZIBvO`W2R|PKNhl*h{Df0;)NCT&#c&ZJApLQOQjS-(O~bCPq-aShx7fQx zJpv$PPsmw8X%I-ELBepc2u5Tm((=GTwuIk&a*IJZ#B^hq@<|H-XP`~d;QSsC6;qvN zc?sVp83jKNZ?tc<2rXD#P+=}zgvK-vUP>FyP`QcELJ`F;ze9dVa{(JwygMG=e@AqB zO=PQv$T$%1FIT*aDO&35=p*4hCp5xQ%Ey0~;;6Jpgx3O0D4VBimv{BZ@aMqg!yi_S ze~q?%7j#fag!%&k;s`vz=g%$HSI0@1By}~77#Cg|J*$@d!$56*i9}a-@R%; z9a;W+6@Nk`PQ%lXSHescIoZryXwdL~<{XW5#paA=EcppjGO=nJEmer!Io(RxsBESW zdgvtMr*IsP`yd*RminPMBZujYaaB8IjRO3hit>CbHkn&)lULGdtiH}OJr@wZIT3q= zsHdY?QR4*N(EFKIk`7MS^j_8dCht11giXU%%5PM7D}3E-HtmIX=fWhdigrN4J?7D} zSHn)EqT4P|@wVZ0E&kLe5-?_5A5EN@)bSgRCn*5JGD_K`LMAp24+oIsvFna0(PxQi z-v<|`tKVAG3&{;55{u1Rdy*|zIHo*v(by{0Bs?If;s@u7mh;GwxneJ#1zf0Uwh=kS zG3n>Sno)e*afaw-3U7c{KUoED6Em{75fu5aTl0j|tm;qUkgm_fdsch^+@d#ss?1S* z4Hkfk>=EE~;$%}KW$%sFTK$a_>Z$j!9=WjAw(FQG_uX_OVEy3;HtASXsq`WL9{s$~ z-kzzBRV#pY9oIc?HHI%=f+GifE@M;zc$>*mip=>!PYKLMR%g@?F zEK#q0Pc!Qwtkfnnb7OKrvnHv$tJKzxHCUp4Ib0QsSF66n2rtndEf`P)^4Eg~LI60O z(_H>eh4dF4C#=+3lR}hh_7@9@w;=31WvbNb8i`;$wNiJ)GI3!+Cm&GE4bW?--r?-5 z`x!$Ms*{wdae|gIvxyma+ z6uN%FsRy0J+}Z8BJZ-s6x(yU)YRu@2C0hngU0?JS{)HxP3NFn z+(h%VkNv%J^~;Ac`S;LYB?4$Zf&mSI4Ufmh;CbbS9?>T)-%`jLUHfG#S zi7n2LuW!o=C!>$j@@cU9F~H1h&h=S+m-ClOFONar#y?I5nMpLXrJY2xy?x5a&*=q? zuOCHc+?DRMOg7w@en;Q4%l#6MV^44UoG_RD$+hPitjf>OKE{@-4N=^?qK+lao*S0O z&3EFYe(XH!+;bo zvr4Wvaqh`FPnc6$8LCv9U+-2=*!rKJ4bQVE$4X0}Rde;jP3Ds;b?1k&zELbvZHy;o zoUQ57%44tsgILd&NhZVudcL8>+l41Z8Q!)jnJFHd;GfU#^!p52U|TH+GUx#cP&Huk4+zXUO%ixfvLZuNG~GZDlXJ2hmdvi`bqPY+ru_G_ zThI>hd0lyrgdbJcn&GS;*);*A;FRE-;IY3E>7>1RebW=3A3`B-3AO2=fFg_R&j^P!Ir8+`nOdTH@JVBZLWmNyf4P)m^KHiwLMH;?E3wE5j3m`|LiuB zk?*%w5)1XWCI%MdwK#yf8hrl2*hI?n~MS) zhamYIvfmDf=Nmy3L%A5IveK)`;rGq&);~5WqWDs!s!59<(*ry99Q27%3oApnEGR?la^7T`^RG6cqWXv@+0 zL^e}%F}D1&EI#J0AOpwAC|X9_e$|iTPx8?p#dLITOm4Kv?uaJ|7Da3UCGm;Q|G1Qc zwwhir_zNf|eHA zMXvl0eGos1E!0{esecR4gGCv@%NLa9k=HYOH!~b~*nN?btOj=Tm2yFkSfmV%s8{FK zO>ZZl(;%TB=tjN0-yR1%NDc4rshNNjX2}6=cfj}iXDlruit#y{&-v}yfB?={ z1fh4_&VXwi+Iq;1>+2!yDD_3+bijw(wcqnw>HB-H-A*sTyETXw#}{+Ni>YG!3sOh; zPO6SLHB_$9t}X@DMl&*IOg6yzb&Gnp}-4~8I0Qs{6rPaZ&w;3rZHN9#gon<3=Mm?SxZrYLX7YZ*m? zk~SOAiNdZ{oU{6?zfs(qi<0V^0ZeFDdB?2kVW+2=66a8zN`EKd8hd4k&HNh^)7i-q z5_vzOK$$f|hxtRDDaLp$%BnwBWaI=ZYZX97!UJJbG%?u`Eaa(!(Vqv7Ya$1WX*vjc zcqDZ+cVmWzeS^Wb9*?@b#__qe9@^{-1!2WC|-n1bU9 zOzA`!#Z1I}c8wl?p2y=5b^v!1WMvx81svXxR{6_*D3aSRIUgv?I?oEdEYGiNf2wUd zfvbmjQFLmNR0oaQB;kU9QZq})UVsKl9KCJ&9kW-WxMYcU+S0I%N2Lj9f*s7%P)L`% zh*=lWKcJ^mxe%hFish)7?%xs2k7zd)=-C>@tobuDSXh$V4uz8y)x7(rlNd~1(lyIn9FRah4S zP79#2oJKjGpYS8y-ZvLCLdu<3*V`yx03EDqe3e3RY@YA(X0!KbPK)KjG=Kv9RoUZrsv)(EjM&HmN z-9S27KDHpL_$|$}`A!7hkTIO!IvF&C;rJn?j9Ide#jNi1?f33j`qvKNWHi;8ltHGg ziVJ7Kjd=_2AkxbrAdq^_H&yU+yn{+DwOq@)EfV|ZIWDR^p))8yU8rfqu^`RKsG zrNVP7EeGZD125X-?Eh=K0A17b!{24ytr_jWrFahWodI`wb3uHY zJYF_g8o+Uc$w+JfgQ^n4jlZU(*nyWk`?YAhk0%AM;ZJO%(j{;w;V+(2!z``gwz;0v zR1jbjm8_iZPUtrJiwuSnN%CrXT;K#tuw@(OPQ$X2NS+L~0co%}XE(5%16*e5U6gR; zRz3n#J-WN5fpN|Fz-P^!XOE?qt3OlQ>(xDq@PNYuwdB&&{HV0lJ>Kt1gPQ$wivkLE zz?`(pv(u9!#>;K+Ok(BHCP6D2b8IF1y-9go(vyyubTwEC4c7SUJu$*fhMp5OgMF3> z!7Ud6Dp8Y(mH`7Sie&|qO8=y&@lI_D z!~{EO)|26MNd_=kB$C6FzxZ~=9T-bt12}XlGMjY@3W{9!To3C+lG9D0WUc9Dht|4{ zypA$1$A*SpN$O@Lf=L9J2Ek+#(Lg!444~yoxkJXKh8Hay_a=pDkH{1orr;2*fw^h9 z4A*_sojafIw2L+(qzVQczQc{K7e$%bsX!c;EBZSrJg&I14DgkUUjU6z z>cgU!X{9)0h}I<`I;YDX6~qj0bJs(`!&To>Lc|)_fAqQd_SB5v@*k?}vd}BzCDEZM zL|SxN_fS^|+e3$Y+DGk{d3Uyae_2Ov@nEixLX`$wp$Vd~jj+&(udJ)k)HYyfQ5Q}(R^yvw|7w8=%i2Vcn+)BoBPucFWV*yKPYk*C1RPdX=VC|tqr>x! zo|r)G3N6U%hNDLfKv%bR?<8e|tL^Nkl@f?wSOym@j{G_@O55v4g7%CiwH!9`xz?Z& z3JB=n(L`8$Yf@gb+v^B80h|hP?8LJ18;+2`*h1&Y%MCi6tBPzJFCc-X1eBIkJcz(4 z87`|FMNyWJj|a-%U8oxCOqUPyFF_n_PJ1c`MctNK-QUmmObSG+h47`Qya#EWTDTvx zuy3rXMj6uKgF%HMDJl2~iefJdvnFN>i9aOEcI7TAF}4mytz2w314=xxAZ9h>$V#W& zoU}$;z7QvM2`5c-8G(_AL@xC8p@`-m;P=AFrCd%0OP)x}!9a+I(`9jtOb0oyGau~# zw$=WWL|sahf3WBxaFylN(2}p%r(U86eAv;{B4yB3DGo8lL#A+3<8C7*sO?t4F^|!C zz9_LE^G!Iv)1oXN2FS4=@h+^XUL|XXxY#z&6d9{Yjf_iZy-F!A(0j)LLOGW&&MMva99lId2x%pikBq3W*V~gjm{2XKXJ-ujpt(Bh)w(sQr zN?kVh>drplf18Nt^F2P$#LOMYi;5TIbDpH_X=nYqd;3@H1K_lA`nq&-*5mh={BevR zv6a&kZ8Sq1OoX2eq{Z&|QJ~$|!Go|oG+P~42 zwB2VPZ#W@H(pN~jqZsH2*-)oAh=m}}u0PuTpY7p!TMCbN6P#N~-BJkao8U+FZ7Dk_ zGcD7;m;Cr-k7RF}nw*=&imDI*8&$FK96$~L~+9b ze3W`>cFYge?wU?_Wr=6*vl5FZ>G4eXfufB5r87zMH$J@aLAvtLD{t<7HZ!AW$qmk* ztR1A){h#OWR&RC3dHwpwae~nY#NboOA%^p6kxagw26QlLjB6cFY}0gF?}RSq>^66Z z+uMhfhkcD|zTL18R2}HO9TFP+znG4_hy=}Fwj%@kvZ<+#USY(lEMRwgw z%2M3~X^RRR2w*f{8Z>)r#b8>q^q!eZ0hfW8K-GrfZm}HcYy;z?0XA+78aX=i=fEJ6 z1a^C#n{_LtHL{eH4iHM%b{U?0kG!90T*3EZ}POU(?f!N6nHQ z)zEi~8~zQdlH&tCKi#K9n|*NNmfiS7ES;b$^+c-1N_zA$SrdNp>{v_6 zT~@L~^-NBFjh8_J0Uh*h;~kRpEI;*red`#s|A8TI3s`b;)|$ryt}TmAmzBgmb^a__k6 zx!%SV`JfyI0DrmzlcuiY|NoqSy9q$30i2wi|F7fkm7bP8X)BW7N^RN+klh10&My$j zbvywIO+o>}2t2TDAh$08MEs#ftt_)Y>u7ORgnz2`l%C?%h6*`LIDP~C@}32}%v*bX zec!Ielu%7`Zr=rRzTUz%dg)vj=2PJSfV|+V@#IpDmxt6`JEA+lJA;D2m#AIu#|XPf zyVS%(sFvh{`ePFtaahz0QzjIv$Y?V?`1Zf4uG@POO%{n6P7PdihG03vbuC(UJTQ}2tQaV~B4+N1TWu9eINs9c8=b<)Al z&4A1MeJw@Dgd7rpB>G~?ozV90yr9t$OoT5>(rI>ya6C+T#WFvDiwtGQln!-I&Xt<| z=*topnFeR^xVA6YkuIQ&nDO-Cm&tYGuULjsVE&~PIK^^b6!BYFv^qNWf^s~w_&uaA z&_*RGssjpYpL>Ga=%1`SMNd}EUb4GLwY*PgWfHvu-m6gnB&LFA#=jY?wYJUZad67N z+Jk90u4JI2N%p}iQ*w9ZLV_ZvlwiyaIvM8Rj%6@Nds?bUuSt8;w^q0 z4*(uN#y_?5+9ox1&vt!$~?VUUOyYCJ1aXfJF}u9 z*Sk1c4eQ0ZGW zw9Zn_*KU2xN7T1qT#+_euHtyJI+fdc9c2QyHdD`=#$HF{f3PDEf5Kd3EGb(0n%?@; zUNKBP&3d9_oc{ip|0(^T{Nqu*!3pUe2+wWNWr<3?Mr9T7D5Wc)qMOG-S46G;Bu*DA zwvT%5jv3(*&`4J(Y16TV(&cM<|2^u2+}>DJpL`8|yavM%R)-p9JX92>wB5&dz$yW$ z%!65@uR!7x0X+-*1FS-o#~gLx+1rfWU$%$)9P#5q9tN+ybq$daKsmfEiA_J-4*aA; zNHgc#^sWKSx*0TL!vY@dFl6P6&0y=%N2JBsh6@ z(pC}V+R>4(>|8;2`EIgMNWBM&w;ARqlUQPy4iz`WR-udl$mXO)H7v{Km!(5Pp|_6c>h zNl$FdBro3>xR-_K=!dXvB~D8)MBqi2((NT;In8h~sk9dVZnRzogxE9Tui1>plWR9( z9s2`{F}}mcr~FBUD}OSt@A#`OUOo!2L^A&|G{Ij3j};EekX|<;TWXw5FwU@&K&PS^ zH@-G0HVUIwYK1?g>5Xit%2KFn{8Le34>&#@k?0{s30+@WTr;as)=0m7x#u^ z@nfN>y)fsg)zs8!Sr*$_n{QWd5{}9M=NAK<P*wtd1%~yN4;|+mnTn5RMH_(^$S^Y!~P3GvT;a`-#@yw z({#gskTnVrW{qYhB+Nr7YChB_)u%r*{H%XXF!3zQ6pRwf93=5ITi93SPa6Mf9gKx8 z%gqS%g z73VD|&KoU{jmyYcA~Escd)Kp6GV+Kn6&Fv^1p`aV8Me8hkKxl8`W=jOBo3T{vS+>m zQTLAcS;qzTJs*xeNdCwl9fj0p;wVkpau=pBVc9l9HNGbqe^BHIMvry&=m*4!wHK2i zfyRm&hE){YPrGIeZ~9BUOzze^F{R6qdS2UgzIvv)csIwqdxha$jn$xI#46FVl`~86 zqD>-_ai--n;z(67OI2^WhX5V($n4aytvn~1N-WwKnnDH1xr!&7h9`D03fcJ5!1Pg@ zq|~KKbYdyfHxOd>?oGx}P6Cid&>bBRTOGei0ulAIp^0hJ$h61wos~_p^MBW;zf>Ei z=~9)Lzc>$<(iRT#4J1CEmGF*SOh=)oUCSW;tVqjcCJxTWUK8AIdMx-@4(`ijGH}F; zEn<_ol4MV-jgumcnz!!%o*0^z{m43Y{fZf3P?7y&8DNe>)W=OwR)Bjc10bXngB^pr z5%xaafkFq1VsV#fo$Agh+Z$vbpm-)FKR9&yI5bCk0`E4)F2rQ>Da2H?Nes#&Hbn(V zjZ^-K0PF5=At_7X#W=vMOO1~)Y?UJ#HK=fjhoZGC%Ev+_B01LXRINA`ttq#3)sy{Bw~zRFz42-yZ!BL z(n(LaO9Z|^SVy$Y?GYa3wC zdY3q|#-ihB?G-~+)@92{p$7Jek-3r70z0g_)z?*w;R+M?np=~09Jnb)fd6$KTWqEW z8FYvOa`gRg0b)4BCb!IYgJs88+noD^Mq$*=aN~*R7`D!|)Gxlgx?)crO#?$xW3N}q z73bNjsAyy7)jPZ>)*S**tD5mCz#BgT67DW~ufKSYIZC4*HKn@_J8WpVFS>5x>}rXy zSNNGT9X2x&2jV0XGL6X4eHTGjuPvr$u4U2JJT4Fh0T)`8?s1rSE_l+zyc^81xM5R0 zt3oIT^ZM~O1TFC=XnOk4nrq%PBl|UDzhS0J3R$C5VWe~r6A zf2Z3fse^u|nD}MvGu78;E%uw17P=rRL!M8UN!Nw)H+ppv%_etBD1qxQF$+x8iQq5M zppqzE0(9xFw)SQS;m=Vc6L@?PCn3~We}QXm>e4P76&s{u`R^9BS1qaKq3 zHQdC9rXG{d@0+Y!wG*6ow!4_ST~b%qy0HR~$1DB4PktWKu7LxYvT0tH$s~_kmP`bT z!JsRlOH?{1HjP-==o0Fz=`g`0#IFQELaLuKf-vkKKAAXL;(!E{gZsBx>31|?N*&WW z2Rf(RQ|nB)r+KGkYLaCwSWn=bBv`#$sn)|s!q+DVng>v6nke=qkC9#EERLnFUr++{ zkohXK6Y4;EQK}iOfPr)-CYrI%Bl~JHPZ%I`wSa>vT_mQUf2g&NRe}L8)B)`#aPIX7 zl!F;GAd-4e8tCj&HmIu4$Y!qQI_8JvL$?)XXxmD#jDN59^52;yo46XtBFXC)6sAes zr+F)qO+P$*Mj5*lpGp%oo}PbY?F9g09H7q7>?O)6niZ9Rf9lms*9?-BTkPHEr{_C@ zPyTcytwPo+D^x710}L zfI{R0X66uWMqMj(=GhVAQ=TjN7wUy7EuTGav2>^N0S-Dd*r7DPjEXMzO&v%^8^=j=9@42+adj};m1;R06 zga6GP`Q4<&jiE)q`{qXVU&M{d4uIY}=&=~PQY&;Hf2+O86ZSHxvAm~$7{{33G*akD* zcTte_5>g`G=ob;HY3lZ6?MHNa+y&JP+t%YTUr5PH_6+hdQ_qel8e)K=;8F z6N+vK9TzeiONp##?9A1@025Kta`K+V!6O?$GGMuXm`w?Kl%{&-04&>7mtq^^qCI zRo0wols5SmV-#Pnl0S>k>8O+NI$q-Lb+HdbE1k2&{@%+19u@*bAdo7Ls;t_$ZD*xD z^bP;)AC4a^a31t3n_P8&<%5b*s^jUbP{0XKpeM!@ls|Ab^1}_^Tf64%7ChzuI>V>J zozP;woAv>=dJDLU_u+C2Ll(62EO3Hm(#4HXacy)rK_x=25#!Eo7!Y3McCkrY&B~EF zqBbrNX|NB{uKaIB78T2sEf(9{g2<$&Pgkc!#)O!LG!IocYY42`jHQifZypB#y=w* zFKz`E#O|LDI_R08ZiO=1(-r%g_5ww!P`#4yoOty?aAW(r^gXBf;x3j>u7}qnET0<4 z_x<+t8qoeREPzHMwE1%FmV{{J?c;e1_<9;3;r)2J2h2b7#f?vYx#Z*tVmUA<>yXEf z0nSTq9N>1pQ+Z;l754vDU!_#kLfY2ww$Fk}reZ{SdtM}*LF@o~OMmE}e`a3qXGg#w zb+N_v{~L*=zwNmYse&Q0-R%zsqec&(2J&9<{(hc_9Ah%!v_Fo7Hpe%(N7rWVLH(9~ z=~Vqx1MsSpiR$$Aefzse&`bM`CeL^2j~hRxv+ewoydkcAnv=?hM94z0clMX*A30AK z2YR###k>~;Qvc`kHxTz_YG8w}sH%oa!^gJgoD_byn$gMLbly!j@y9@4j4utk| zc3~7-L04XpSM*hoeQ{&Kv|lzI>K7}LIQ0)dRu3>t;(nO!gEHUfuu+lLSE`9kTfu@< zfTV4MxhZ-VS9WjrH`86K2Y(c@n+LEj4QvXXG-Y|v8iRV+`tsa(3Zz4INNN7T0i0Id((C@h!K|fT&s6=o~{?@UD2BqW(N!3*RU~q?l zFcu3Nx@A~#k(!UKInUf*tr;T9j-<5O0F?$}kgTUw5FHuM_{ut8ReHO?AMlA;I*8pZ z{w^|NI>PAto>AlACsuQj^QpfAc&ME(1c;26YP(NMBOwc>A~5#qfxl-$zSg?~*iRg< z8OSu2N;}Ro!v3%ffRHvTzn)XHKHUHJi@r=3&Owu(2gZ^55Ro_luJ1d3Ra$-Dv1Tbf zDxzB&FT2E^$bs2c_98{eD4B18O;r<7#JFUiU1f77oS?UnfCdGDC9M!mOmvF+E7uVD zkdt!};WR4@T&cFJ;Gs~GE{I`ug)j~p#0Hq3H*gPi$pKwrr0k-ssd=OepyWQ0bO#q~ zS2ocaVWQVY#SI7=(5^!XB`AWhlo&w<`3-b#wj-nu3YAu>Uhu28F)K+6^tDpLqgOYc z$!nW#-1{X;KH5NPRIf;wbuQ zsl_=B|iFBWSYIrmKXSQFSH{ypf+hF7_SPWojP)W8Px>$IOnQ+Dh$Y@oPPm&c zawD^M-S+1A(PwCr^uk)rQlffzw-R>jYf9}^=-mcynl&Y}11k|y)L}_B-4r7+$GWrm zQ)=nRN`u|&;kGv-c4&1&e?|Bz5aVPEP&nAtUz~so@3r1tIR7!s#7Ev$ACJ)P$KG;)|>T~#$2^MvaJ89JO{WNSujg1|u zpsrm4>A%K5jSygdXY_u=V8P;>!Jbd}4#fdoR2c?GPiPz%L#>NAnk0Pyae`(><723# zC4>P`U}N@GKOY1VUUL1`DWLXrQ&kbM5sBwE)Z~Ie0tY!&k^Ju+6TrtT9M>GKate!cp#9#>q>KI=j^;WbsQXWxA>&itdOy1+)m` zd#LQ>drzUor-8;EW;wWNy*S}M$GEx5+0p=H{Nzry=OKTpZ{phGhqU_A*c^>B@yG01 zRFQQVCJ3uf;%lLtGiaw207Lr4$s z^kb}BQBnXy(FalAzIR_&>1!B+h*nl0uJsjamM|VsX(=IJfCxqjTa`1Eap<)obQA(? z1dVX!f%PU}-blT>SLuJk{vLwktSTe0WTh9Sg9>-`=I`zWhOz%=n#%d;Zng9 zM#n)v*%~735T%A#6bvo66T6cvd3)&q2IW(Ji64l`-3CONd};t;EXnfRbQ>`Ep>bzS zq4jr-^-wzm?RcvLUE{x|c7$~_C}5*g!aklq%)XiRO2KOgDZIPXLt|`E*Qur6lih@6 znq9M8N5IauLn|95qr%cBnnt{A>ib{7cL;+f5b37^l?m_|@O?nRqe=08gAD-yP;)Ce zao(*?`j(bBc{1(ydk_|^JB(^X9MSPvoMISXcCZR2JtR%W3l>IY879%2sUcIR&SH#2 zh*NiUnVkd(%WncH~}8^btPVXchZTC0yk zpLG#9asJB9Jebp=UWSeW@$Ody)wxmcDb%tk%cq`voD88BK9&wA@OAp>$n$L16ohkv zmP8HC<(F#qpO!d?SRIOwI&3!>xUjSVZQ_CVS8;iW&6)+OAS6xzlD{cf*XTN}Uqm}x zF+XThjk(n_Vh+#Wl_ix)JEqos{_3{UPia+RwYbLDg0cO(W~W+zwK*HU%XE$Odn2+7 zt}ClkM|Z-r^$A2xTv?$WV@YW~H;B}&yf})eQ)MGG_|9!aLBf76;c~!8(X-Ax`3H+4 z^*mVW5wkzEUK~IqpKSZ;*uDB0wW$;JxP>vWx&0n+G=gz|KLxDM<=0G>>3Tfi?6foi z--{Q@or2bd6va#T{N#RqJCS&P9TzQ3C2EiMog2*AZTj|OV7~<>+jWP&%->(e+nATw zhv5ZNRhe7=b1z?(0!$HQlz^o$0u!YA7p#AnD9&hM!V*C3Eky|Rus^X_SCy}SbxnA^ z{NR)fW=eV#_f$xTb$vw6YALft?c|Z()FXi7IM$W^x$j$j zbDagI&q1KHIe@go+4=*qqM*`V-{TW?ynlQgFX2Nbqm21FZO5r%<<_*3>cd5nd#!}2 zTd8lmE&#*^IeSAIH9-liRewC>0ynAR!zY78F7X`B{hDOe!ZV_P2;Ve>E|RbDk!_M~ zQ{WyVHrd3>nU*@l`elcbk~H6y(OE|S$;L+DXnAh$L$B0aFfEcMmshlQephBpPn9Gz zxZZ&@I=)MavD^~E{6{RoH8FT-WGIMw4mq9v2m_Ek{9DojG05}sJ}qe{sG2<9WuRN3 z7$@(B+{e2uN-;epx$XBKRLkb+k{G3Wj$w(VV9;u_EQ~8rfX#!R>!R^uBICJ4I+{Xx zPW2ev6~6ywyPs0KYLd6)qb85H%?+;YEUsS5^cD3SxvM)>wqRKp8BMvkWsXvn(okaV z5F+5)2=t84vPdUyMW+c8<9_>Ziw_6>V{^saR zP>zOxOhltoR9@vGh9(Sa$)}8FOP&jYd|W$bDoYSi>ATA<1rfslgTEG5!8N5Ut_x1T zyf53A&M(I*5%1|ISVkaGK@&mXC{Mr8_y9Q15(`Rtwoq5j%83~(m`d3F?dfm*Q74Y& zwkMjt&1#NHzn3cbBklf@#$g^uHduLB7N=*T`~5g% zNM>VfQc1Q^w}^ZvOCa%{oVnN+Tnu;^~IY%`E`a~9yW z$NPW;s{JCvIln4unQH~_la=Eb+AJ}xCG$*^2WP>}&Grl{pusH_pJwr3vD3!Kf2|yBg_~xvFpp;aHmVIC*XXE zMm6^3%32@JB<5i{|4T#h{fR+x*-qGtm5Fd`u2g+K9;hR7wHfPNM|`F+0oZ!_IErJH z$?v99;M*I~UPYszO?gOMf#;f9{(N9r#@NP1^`+$O|4nha3G|@10rb99 zp!h8D1Nj-n zT`TYOMo$Jr=}>9eh8t-j`%f{ zOWjt@`?bI%=rKv-3smhj0>#AE_oeD7)B6;3c&Ec zjbm-C*v)1H-)%jI?4RnppWh6SuFG58E%Y;ZGg1+R6mbtetxcXOvwpq%I~}W2Puty2 z>vi`WM(P24-QTXfT;F$l@-VBj4B3V!qnT_Bb-tvN#iE^~&=y z5pYSfIvfVjJHCCt_eKozk__@83EZU(Q_!w6Py-5N*xxX1`F(}e4IWQPdpH;A-O1c2 z7TlyH9+Bf;rP2;`6@o5Z5sXDF8eaQ<%pb>;>jMF`^CXE4wqdFz7gxAEB&%62LXDgx zHgcc_iob3wRT?R}MhUb-&2f_R4uJbbAxOnG;j04c+q@o-Yq`!s%yGWk#t9N&>8(&x zC`R7Q8OX`W0jaWnGZisT%gMg$dHv!GI50_Z998X4_-Yr^{7BxdF_G>Hm>6h+25f)((?70DUp!v2PloS!#cWlSkQg4>Fv>bPp1@AyN!(g@|lB>kj6U6!haw3s$P z$iDvVuEgS!LJ#vDFy=`?*#AO{KXbq1KnRFwG4}{g8YLIj5&Uy}uB>X>mRk(O-~`2B z@ycPyNvtePjjs?25f-LI{S6izl75R+NTTPAF4PwFg*N1i)wla8n zo0mFw%ot>pfIEC(>YTv52xN_%mh=3WRBf(kmYt$&%4l1*<+my(?WHCFcC@vcItK_- zcO-!bv1-Wr7s&>IAO!S#`~tg+WBhr|(ys|5ZAKju9YFw^*PZ~G%mqP)fK8ZK2InuK z7#^Zti;%Jxpxg@a=Us^)T!WB(UY;NT*btZ!)h4K@lmJ6FqL@O^yITCVjquO$HZq5% zE7_a>?T?C8gh9dB2)2inaCLVAK1=}Wix~r-ste+Wy8H@8or!o6Wr%f96Z-F|t&<+l zQ2}+3v4eADXMQLOcK1J$!mGN4;$AUwhTR~trb7WTs0^fvv!d$IGNz+r%HDhrB5GOe zZY;AX?Gf4`w7F4#i~6H$7gnWhvl_k=wr+zh$3xV32AGolB2E)_2B}_^O*jO6_9KHn z7P~v~TXwfsE6$Cigxnn9Hk{38*UwB<@bHvOVcFTHS6P8HrM=|f@L*sH;%FdWp?W9Y z^0_#+*f}O`IMfwp!61kUB-NNN2* z+KRlE(!ZMd5q1;9We2tmm=pyB0B5j8ICXDpYS7YXX6FpBqUfTips2zJ+kz_}YDb>s z$KMyNPHyEwO^1^SrE{eKHXV+&tjPf-i#mml0h4ZZ z@K2Jh@YG($NUYp+f+FJ_JP-cHC%NdhNfw>k8YC!)c|Cs$mELUCjo%Z}j#RkeWks>HuZ>F!>bvTelKMNJ}f^%;ELHVSZ%$(SX+hXEp(_>$EBR${Wm++}q*5YbNx`ct2-1w{o5d9sa8}R&b+*8E5!v zcETi(5bH4?{IGj9AnU{l#@bZkAf4fSEd4o0|i$-=d}dB4q8$RH-~$ zQQ%=%g80|2Qs!lQ`TP$1V z*W7%L^Qy0tJ>g4)&ZauJaG%W8pg*qfXKsm|`EbL@Qqm>(6R}7XE6+?7`-bzB@;=TB zjF0VutrtF3k9`5^p<997D}&B%m-P1EQTIZm#;~3=+nL2)M#SMAS}*HlODdn<`pNID zfqID-LmCteq4DIL*8t0d9n3rf!n3ywz? zr|{y047Bu9tI3x>m4Q`-ndJmft{Ncelz=7{*oG|${8QY}D>&ae7*=vDJLPA=|J0R6 zb^Qhs*+-LjL2Bu+a-4>IEAM}OtlyMi6aEgXdTRVeZ36u#z_k#vg;)|YX?4+`q9go0 zMW-@r)H-K6qub=jNfE!sY*FL)gu&&3gX_ zp5D3|0BtQBJ<9X^Fcu{yF7RYtJ7i+4NzC#w!#v7yEz2_#>h6Sc!9co_@-Eqca(M6^ z(ubdeFAUaXC90Y~1&YfzH%#}>OQc0kF(Gp4mbVo8u6pCb!3_8@1&`(bJcaIMwIW03 z7C}dZnuoh`#7jA#o0qb~Fna!mX6sip^G`W(1=NsHJT+f0Z$o(MJ2>9GaI|VeZVyu0PiTK-_tnngYY}f13Z30=y9A(`qH~Vuiyy%|%&C0j!gns`z=*0}x${ z%3fGH|67hm+;ES@Ua6j>FI0wvN%~lsUE#47gIZ%F(Y=tH zVo@$YXJ94L#4f1Tms%R3Q*2&jtc52q8!;4JH8P_i7@$h%gn)V}Ox}@@g|a`s>QUn~ zF%`ydYV-h2ylWt5O}iE@g)nlU4IuFI*yQFP`-nLXSDkg*(RYRrF}EdOm!#r>;H~Bc zxbYUpe`jECCHMrf#g`0K?$oOq{8?&sQouR zi@xptX@;xs7m;XsAd><;e9XFg7oV;rAN*^>v%uZ)Po7k!&-`)m#S@sZl_mL3q}2A9 zi>hwxt2kGT-^kPD^i>1+T&jw)cWw>pav!;-%H811Cpsq&?Y_>8Z>dcOB)l9;E)_GJ{@?}Op z(vm?*)8&xLq;Ix}tP5Yv>G=yh@EO*Gy6e=D)~VV%e}H>s{eq$5R4xk|)mz#c6foOgpT8@A0 z7=rTI0&1d367>FC2|7CZ^7|@9=2EdCs)b@N@5jDd#mepsN9JIEwPQL^Vy)s-qsbT> zWK%5pl}pWjrV_a~!R$v4kQ)3B*5S*m0Hboim*^${#B<|*OjdS=i-$b+%w)oDvj<5b z@qGpFJWUpEdPL`{qIsE)yY+~gZQAC15^0L-kVo)$%JrxRS#!IX4{vh)^NgIF(N|-r z{~?yyM(cZ>kWF8X9dTC=VPGQo7{kTjZ|l`C@6B1T0TB?hDjJ*R4LGpKkNl2MB^{sA zWR-Kk4TGg^dd1goXd&z#imJl)#0cOb*m=mQ0Yahho}mhi-`Y;c;mw@tI|EVae919rDQ}6SmPOC){HT)5 z;P8u1Jo@A;s&`8nhx5brKi_pK<<_8KB+o{cOXvP= z*kY2hi!%2RAq8s>!}I+wx37lK*3bRa61|+xL3@NBJ)buZ&wQJI_X{%?^K3uff1&*e zdHXm5{C)bQ!TorepKsZ2SeN^9N!>N&o3J@P`jf``SCcO!(kmRWfgzXgD`E><;-88e za@dg8qrq*@=JopUa4F`BPh3fuPm)od8r1+}Hk{B<&pqpu>MK--f#emKqaTp5p>B~sJdTuz5T z`bNB26_YOj*BxHd(1xsY#?uW!b~Sj2_Q3aPWJV1jlU*mkvzT`n9QyeW_nBna=eQ)N z=L<%J)qe(1WzLVC0oE?6-3+<6hcI)y3CCr7Xfm%!+i|uM?DZx}{_E`tHXuK*ZCIKp z=Apz0&5_AhXtptB%Cl15j`xy zy-9|!w=`@01*YQ72a~A|ailV=8DAL|mb;}S?Kyl$S%2{}5(!a)+<;K``1)v~^N0pK z!w;UU&(7TWo6LfMH*~;&$8-}JW;f2T?WMvkD>op8DOIuhj$ex`oBLABv=EK#BRDSB z5N8ssF+H!3F&X1htH)K!P6mMR$dc`F7-V27uG;s5;_~cj$Nv7d~{aqYvIRo<%n@ngL#cf+r-Rx@1XA@AJ7+(wK=<~1n z;ke;R0i!!rYyQO!)*Qw-IJglshH{hOia!8hNHF^lg(%(IXme2L;rrZ62sa**Y}6m! zf@^o_N~qYKl!-7_pDzbKWVn2gETgVQR}-KJ0XB+w9c?=T4FjU{-tY@^$~&2O4NN&Ixt`fW`MiX_*3VV6q=^0c8tq_!?W2g?L zLqjkU@B=ZD;Kf{}yB)Ei8^{Rt=q4-qjcUF3C$_uKkbc&CN&3IW1QPg*fb{|LA1+5p zrJIsWHs?=gk>;Ap5IWTCgO-sg+T^)ooxtVXjRW@2uQcF9jewz_)0mf1#v^0;%!jy3 z6z(}-j}eUtph~SFlQt8jGE@c1I1cEH+8y2on^C|V zweKs&+t=RuC%~>*s`}`YQ(XuIoB-ADUjT17Jm=ON#U37Q>%h&}3^8p})L2 zxhGw%OUdbZ>RGXV{P}F4t1WlS?p#ijEhN9^II*%s#yM_FxLG*exZ&{^F#Y;s@zksg z>%iu6p8N|p6vHM%9?lFQUu3zRasd5`I@&hgE1~YCD+yzwLLiX!4>ycMFgI55rOfm zxbU5LM0=lilz5pO2~`d}ufhpc)$I9dZ&;uI=;AneM(>um@IeB=7%GOW5ndu1UojIw zu7a8TD|kub#Of|%OA69TLwPmMys7`~VoN7~D@3>gCE<-&18Df0P)4|rvT6)j)68J_ zr_6B~7GhOm?Xx&n>{gt4R!|ae6Iwd2ZdI6Kk%ETOcR~ApaQpoNOSmf4LY7!LSFCQL zd6S@G&e~5Gyc&S0aQR%hbe;>UYp1+hc01`TCzMxgzS9sghUT)&Amtf+cgj zeYe$3+9RPMs6L)QCa@$@fwJ`7Bg9A8dRon@xCOFN5O&>#z6yl+@dsA=Hi zdQGcvjenlM2rc1bN%xQss~a7rT%@A0#;a+T*GNWNX_8x?>hdjaMT3_ca93Al zo+pbFf(izcXSF`&UMmK1Cr_^;fK1c!@=fRD#Bi9xK7K@Gct$jO zHUcoA{}VjCXb|6U8b%RUs45wTP$yA)68|;*M_}%4IHUCtejS)GxW%}XK^Tl;FF%9$ z{U4leof7>AtsZToUjxJNB%HP3EHgXyFn|3P)AuCJ{aEVDW9z_eER8|6YQfLoNa$%7 zsAAPLp(-7=fjw(6j}&E`Ce_f94qzJIeBES`gGv17@Ib zuWOLUy{j1!%oepUFL^*K5bPifaejYwJUd&DgC2*s5}2lxtj==ZUf2lvfU?$}O1>Tu zhTq1MRqjihOx_%~;6^$*++p!GymmS!a7(-E8Q%*ny1K4z^f+qFcuXe*zH^GeUAJ5XlPz4=GnMC@brgHDddHCN;(QQcLF%?Gc1KfO9&i zI)M~9!X0s$W?e2=-kRi5s6NeonvQ&r50YjJc5cll8EYT4?xe z;}%dYlQZQFEABaEF&@65Thfr+f2zwJou>atE4Urm)JH>gIpZ2yv+)ZKrY zs?O7L@Wn~oapDaD(ZI}wgnW{yd(QUk307O!{HbKevO}%X# z=pxz{hP;B$a}yvsWK*@dUFsRS}8{T_(KM*h(e^H#U!t#3oT?^2m)@I zQpglUILjkHq39xE18bKr}o6rX0X9xf4wUlunQSQ|SQ@)$4iqu6ntlk=2B0mBkg`}WeQeCCmY8KF z^b?Lw5m@yQGd(S@MF-uvD716qzGJ#=>Iy_*q%%Yj_mrawwswUrT}@dw3@*(2Jp7c% z7=%4(#SRuXAI!HZ^VrFwtPK9ON;dG6+`wjwgVZcZdp7&I70IMg*rC@yol>KkP4rC% z5IM1>70N%U4HKJ> z7aKq|T2?q94FgMp8HP-aRm}&pR?1xzrt(>h-{QM_#2Oje2vU$cL-eK4b60ZiXzkwn zMWjdy8=G$6yYF2!VVC>cu$MOCqnJ{EsK@}{t#c{Z-|JOI5GWjvX5db@-d9CE(%U`;c*&SeiaunU3RH^=bnkVZt%Y)mqXHhk0HdDeFQ9+9<=y?qKn+ z0WykywFQkj{@@;6)3*i)V?soyG2)M3LzZAc~}KG91|-aPwmX!h7|>u`y&Z-0GNnj3D+ z_Aa`#C*GF2wjZ1jqHY{g-);A^*S(QC4$5EZVX{0AnXt^N->+g#w1B33_YaLav}Jv3 zP;9m?mNjJob+~N|#7zRHVtbN5-SktlKd=1h9(lqN^^%%htzM^lj4sec&!}LEd!h{M z^SW%PuB0+*=eQCS;UfO35=fTKn)Z&fnfAQt2zOKlP7o1T)@-%3B1Rm!>L1<~{q4G! z91Kd>^KORw`U3SMFv(AqHu}G9gwPv*1fQIm)@k64BUx7cAL!9M zzOwY+nk=&Jv1j!2sEf4vyCZZ@@Y z*xF`VAdS6IpyD#mF=VUUM{O`1=DV_0a!(4HQ0!8@-#k5BR!mp0ekayiUzd~XWFNA% z!^?5q2OEy+?E2h)!Z8|q$$|ST#!%e$^|kuN{wHYJD&Cp1ukv4g+LviY=s8cWv%8wV?0lb@@!%l@9HV%)-TfwizFfG zN!0OF>h|I3eoeL1O+Rw#@+5so{Y(@VND|=uiW!fVuq~?a9j}M_wob37M&9KWMMK*a zE550DNwFJ3);pqeUGpj1U1(W>bl?xAPwwbO5t=OkB|-N@L|;qB-t61n*QT;+CdJ1G zq>a0xX`vm%2FHT}OwO|9DMkfNA?=xXA4?n8nyFpHT*$|28G4$f{YrW9#Sir8bve8< z)m~yz(h>bY(Rf?3b@j8&MJDtg2mAbIvZhAqqJ56JJ+ZE(WoQbd1$L7Dr;u5zDD+#P!Mh{9e@)xPrOU#;xJH9FT zRKHzkqwSEg@-jEyWLV!|5MK@!5i8}lOdkN9wTr&vjLa-%(&T)DX75#QMn228gKJF} zT^Xs<6UF4)$@V*Hm7^NCu^Ww*lU_sm&jt4KKY8?9{wq)7(V;^gD9y@~Oq)xa$jm5U zAs3p$?N?3xcAHUXcGdfMs!G*!o&94Pnaf7)&rRQ1EE89%zoPqlZ6~L_0+{3*6<%@m zc^C=$68Jz7AxMNw<3eEiI^U9oeX?Qy6><7;yo}`gcYk8B;+DQEgkrIe7s}aE9d2U$ z;b&Lz1Y-#)e9+p@AKL6aeiXKO)KO@LQwf^q?UxfUS0N~1)wEN#ctwFW$5LQgE56;C zA<|EiGeV?ImGW=sJLaCSV}KPkdH@}rh&<(zrj9(vaZ}2$?s+fBN&N$tzcm1PrtNnX zLQ4DTGi_oFqs2`ta&$E8F?c(*1`DkQM-0hG&HSsNbcSVRS^WafGJ>3d?FPVXLc_?Ei)9cypHYvK$fNDMU+2k90>eFEP<-zg@=1xZ4z8vO7u zc3;8o?mzJaQ!jOI6~>4qnR?l&5fr(l?}3Lclac0Q*5{Y86xzN05gy zf_>3qBgLIoNSa064`6d{1Yw&h6py-iRf3{Tawx~3-XER>5-!pZa+H`LHuD&;{MU(u zOq6p8+Efk_j-cE)O({oJf~MpJ&1L_C`ZO~M*^B+vIOJR}|8TVIX&)LP4_hC?7lt5l z^Dsh0e8M2cC!C4xaVZ25LF%kBQeiKD_)A7XVuYxJkQ)&ItT1){j&Lso`!^6qFeFI* zo6`|~u~3Py@|e@qCD#Mi&or5Iav3}(rI;oIU%v-^^5T46yeptg zy3vL6P-C<;;QTO3Yb=w|_5tIRh4V*%KI!9iTor=qTh>YQU4}p;07!Bu+wv}YaMPvW zVAz*vQe+wM|Iqc8QE>%Lw=e+$1b26LcXzko?gV$&!QEXl5ZoPtyL)hVcXtSP@;vWa z-&*f?@4xv`-F@bCpX#daU3({@6(|uGN`~3S*8XwZ9yB=|u{rwjl`MWk!HgpDPd+qB zDn48{Ls{tG-hdn~yYpH2h*)*A1$M54RPzJgPSTD!&6BW$if8#BEjsX?-9O2G>l5t7 zKpL|}hPYCq?7&9OpJZ6jL{hish&yMpp~?taY}R5#N^2xalhNPfNf!d18C2tEYO^Bd ze#)G*xcd;4bitLFie3$8m>t%J8YOj84-5_8^;kLJBCw$HE$aKQMkP#Qg9ic&mL?qHHBxO+#Z)ho z8+b=23|p$>#yHtoxfo1CLjJcN#^?bHFd!isMJSK`;?liP19 z){Bt1Kf|%JU10UObTTDs#V>vA%G1A^!&o^xU>2lhOlmwSMX84Vw94vcj=GWcB*O8v zjvFH*8z{9DsrRR)PBK|H7jYV!l4~Pep)#O`CxUqD+Y$@;!9+VxkqUX}*6p35)M}@+I=KBV^uK4T_e=nA}oIM9#{{ zmQl%4hW`O-P&GjT>v^Q9PJ9D{tG(Pcq*`>qfM^twQX+u`Nwvjr>)&X*WorstMV%W~>#+fzAJEfvkdIKoTK_rFB{~;-)@!L-}^EajS zYITIO;;%|%g?tgt;hoeptRDp)p-f_i@}{ze&*7p?J0-8_Iivee2Dv&)Lh$%_k$@?> zg87aHl<@VuP%u3v#uLK92@j~96J_L~ECzlp=@{&(2H|TvhqKx{KnS!{jov7L!;A&xJc8v`Jjog&zK%|tRtC6s~B0U^S6;`4JC>6LV+ zzY30OcY$>Xx0C1%@=R8UEeNvj{2@=A8jDtlx3y~=c!uI>wX;;*tcWW*`&Qa^XjU9?5g&kb zEXp+A4a$F(bl$0VVGs7yH|kPL&5#+VdBvu;V)N=N;R9XChLe8xmi4W%4DY5>%+^)! zxFdR)D-avnaASOg{2r;Jh+g`$R7|p7MEa9)R}q}MGCUq>{?UEY({gc!hxB^jY@{V- zR4&~<4Cm4-tBGlX+g3FWZ|8DPCk-%K#&@hhU92>r?iz^||1#PoOqjUE6DqXAtZIf5N7?aL>!{<1vQd<>uLddlEYoJi#E1ULY2G%=cRy1=Abi4kVekq#RxnHe$V1+pm7WDa=pUkq) zaacKL160DgANr`Y&5Y7W23LI)m1JzM6@TVpzE^^fXwtz>sOHxPh*wms+=F^c~eQ7H7}aN z+^9=sEujx3CT1whDuQpw%sjm}ISQnSy32j@S6Kf7l_}XY5n>ShvmJ8(>Y$05gw5*F zYC_x_cr3{=ks=Uh;?8Vl7cy84&X$UJgR#*&%2#m7w$-c6H@g{H;vsdOb=^bJw{r0l z@Po;`z?UJPx#MFl!|8S*%?wni;9kQ?~=hxaG5 zBSvXV8N}k8o3l`Fk;*pN#+SBqB5nFg+xO9kH8EHeSV#N0nNZ!3R5ECCZ#SAjpi(DEEozpF` zDss$uJv7bno1cl(1;#?a9YOrycYJXK;X==Tcai8xmRAKyJ9eoH21g_aAA%4?3DQTp zgWDBsUfv!N?%ayg$JHrLIa44+DdErr2vMqC)V>K|?ofY1@;`pbhS0V`vb!0`B?xy!9+0M`LJ)x_Z zB$0ozU&8+3_{){a6mRFO52bN8f)BWY zgN>G=w@z(U(b!xtNQfBgG?Fa+iL4&GI*yLl=kbJ&z1t)NieljFppFZqSP})`Gx3b8 z8n}bTst?CwiNR|>!Obs0LO3q}_XN)uz{&Q%YPR*(>_N$TmoN~AGY`W@)seRp?+&IT_W40HUw zqHy~qRNi0XOS=E=JYN0Us8lq++fvf|W@qB%A1wrU*-2vp_o94xIULQd0ev^C&xv$P-vCp*FUa>D>e_EPWC^^felLgyMy z`+pyB9S`(Tn4%f8XL~nmh9&W(^AR+nx~X2dk5&KA0Fnge@-rVi@9($d+|hSm>2^O2 zb8ffZKc|VkGAXEeBeWiKpNdJCPdvQfZpE{;*-NZa$xH z7x6JPX#R$MS2oXnaNTJvH)-aR{aaVTF-tpa2YnCYx%O9|-miZ@6m{bs>{ucnSlLy| zt4PVXx5}HfMX8-f4RoTS9sPU0`Yt}E)Fefk8a9~>s?t1AmO~Kdd(@fvbj~Xkg~ z_!r-#kFFCnLII=x9@zj;9>AGdv~$PG#(jevCbYe5|6 z(Q=+IV2g(j7G3&Va2F+tet2JS3p$LM42zb}F@2uu_4WAXFR~p+I3UF-s*#{!Nj>X$ zo$V_;@4C#jSw=BoPb)Ic$WPS{*}qKtphu5rQP9Yhi#rX%5wB}>o^Rd@ zX2w#S5nfP{smViBGQFD+X^8be*dZ7xGPTxu#zJBGMwd!mz6&$@t`xwI75|V>ovtr% zpYUvrq9t4zW2{N80vrLIaG*$-1S7h)`wMN-_Ls@FBAq}0gt<5!#$`xR4+&dz9npw9 zYHc6KX5~_SNC&!nBVD7&K)sxd)%(o*oF;c)E@UPsgR+C}hgw{MJ+a?5E7?I`eRxFK z|H__N*`a*|;#M+aVi-jA(zU(tv|+klWZYwj)Ga1;(2RwFiil97Uol`Bgs0Ixe-|E0 z(!wAdbKd~Kn2=N{Z}2)%fpB>p2zO%+!)wscdU>`EYd;&lDi)U6F6Dd`q~?#1>lNR{ z3^aQfzr^0&lsca{74lW~^F@4k8F%{cLYaU}KzX&;SP3<#5G6frf zEA%k?J4l!YCI(Apj@CkT)bZOP{+H2scbe}vDC#*7bI*}pljC%zi|@|v@|=8N8a;t( zl1G_*r;cKR^~Nwth~)9=4Y1b^R1`2hrSnM1QTe1zQp)g5xhEvCq)|x@`Gt3#Nt$`P z^ari$s|sBZ(&Tvz|4x1q#YJqt#hve*%K@_vyCV5YA2Qs5Dm+Ym*muf7@Z_4gkJ$tu z{k{gkVLjv7H9%xq=IY;xQvIo6vLKXyzryjMx&CM*tbH}K<@^x+6Ju|JSt8zi|cg7#cal2>*<|FKM4?dLG-35CkJPO7~G+6zq8dk*)gIMs2(TaPCTl~jg zXWtQegm`MTf4n7Lx%2uH9q(OnITz-~kbul89Haxi&1X5IC;*5h2*{+s~Ntukf%T0axRPYq?gDTR7R zorSr~lAbEEBtYyaBEnG;$$d{I$U11TG+&;k?PtN!7nl?M_D^`yOH-Q52JC2e zQJNNKI=QoY?Whu7wK!-R!R@r6Q8JyehbR1I>K3IV3pnuJDn#&v)DeIb+OKC~#-Uz# z&NDh6)PZ8`rD1NEQ9R@h8|3S1!3V8Mw8b_?`m0G_$16s8lemr8cBjFOZKCavtRYq*t%20zfao9 zSRn!zTrPIa4*TI|?hIVfzo z&MN2o!$D$9v!#ULQkWHKSm8BjtYd)~yRB6!-mqn^cvXSNMIk3L@W0$giFlIT z8P4b)u7wG`f4){&uld=Tn*%vdZN~CrX{W#vO*%5NO9zfTJoCb*pqm%Lg$&1R4Jh zN8H=GE(;NAd3Ct^t!v0Dah!*~bBNfep%lkZ>cUn4XDOeXY`&bkt(eILaGZvs6jqkCLB;|LI7+Ei%MqQ4XEz!-D4qalH7s`p{UL`(die%L)0&6Al}qC;f)6?E z>7t%acXFctGfO$;6?fDV#RiUe3U^YS12gT%q)}I6mVfo_e7$bJ&vT7GKf+9E(Ln zoEA4pD!5@AE#6Y*@#8&z!AE?lY8uLAu_N^GYqjZig%HQ*jtOBXS8GJ8-5x_3NNuiJ zj3u_emDJ=4LWeY3r_RZ%6enQ!HU=<2c_CXdZ`XpG{`qS3ut@1TNOz`T)KKktYi_Xf zLD10`@V#fuR8|B`{G6oBl8QbQb|}mGbg&bWVxz8t**~Dd+>GWgxpu>AxieFx+alrz z_Li&CwC4ODmJLn2S7buWg*F0ON<5T(x}O|U?N`xMVoAjTLZN{y7ZBZRS4sc}70aF1 zHzhIi<6#QLurpNhs-9n3HM2)@rh8l&`t3dqXXmU?efwyz8g30Izz$?Em>3K&O+G)^ zn2TnDZ4c(UtiC?gIjSuwti{bQR8Wl}@FAW1bb2L>39|DQZdykB6%FUZq+2`ZxW4_& z!!{EQdLl6unsl8FV$CsIoC$y*Nja%@`OXssAAh3`V_joOdO3W6$y{wJw|7NTe==>o zHDsc4_*qG5)TW=$&g8S|ZWZ9np`LXtdh|<&9CT`9J12EtXx{zoMIU=mPh&4x3ymWD z=m#?1H;DiCYPVo%cBgspvd50vor`G^z9Ckt;&rcaePa5xe=%XrOw85o6JPx?=yq(; zU@iYB*x>CCrV0A1MSnE4?leqk=;+eNl()8l#UzMVF3t;9K8B1YzuM6_TH4${Tr#U; zZZfC@ryunOY+@-sxH9yzBs1`V6|sJf&c%kGx#`g=#BQ>l}_zsIM8GS8b_Vf_vTx4W&HLX01=4+ms_ zKgT`deE~OjPfUgYD#EQ#E`G^xI}@gL;NWVbst&?5fwtjVOh5*{uEi7CQ@v(5R>K34#lC+mzEcu&~_sWMo3M) z*@4(TEo7{nWsQ?xtTwI}hkhLs_>w7#K!!(AM8KbiJL zq`ZUo7pU35MsL)))UNTdWmD~oh`M6m$)x=tF9S@Lw>rz>`RQ)OnsCW~g zgQ`GIAYDP`q<_+mAA68j={}&PDySj#b$Qk~oeVUDKvnzGuh{jo`F}%1fFenTNXngl z1090MGua|g!ufe3amsOQHUN6#pnUTUn%a&x-9*4Uw(0K!Jna{3Az$B@R{{1KLLxB_ zTCnKhVX%@u{w~-LU9pp^cp+GTF$A{`fqw_`A;K7|UiS6f-;&{BK)3JP%_v)}O)d@l zW;)MOQtg{5NLmGHka(P^ma?-e{bSpu@w|Pa%M1E37+dX~PMF^2Fa09hj?URTSES|S zL)GN&sYI#i3xsc1ADiI*w5pH4bjJ>h(twS5VpW=V8S6NOTCrBV!4@q*yTEo$t|4$A zUDhH(7cGnbU=jCwYg1A=40_S;R{RRiP#>O0;Hr)1^vOoP;6Q!6UO;uJFM~mYJw|8N ze7|S+JEaiaV*Kn7XMS9!oAl~by_iSD)8saH7B*JdG+qir3c@{6H5tJbTlH;xZjq0k z-;Z*e0M25oscHr!mkv5WU4HSLe@oia0M|XzmU<=GwSF)naaD(qs=2!5{-#Ou;=16e z@M}Bb8s?Gw_;?|FO5fAx{9>p@x7e0B0kqU(^GM{}hqTXEgRMKIHt2(5iGuj5uGmrY z1_nT~^GtOzTwJhACxWRCVv}jC?b=C|nJa#wyPO-R^EV)Z)khEjQPKsW>C%-mrJ1)8TlAjN<}0L$fma0* zxf;h%H8lD01(_6KL>@brfz>TgMA=m5Eml$M0W;qK${B8=$QprOkowzj(TkiY>(!t+ z2Mdu)pB8;B#m~T$xp$yLl`wCkQ>Z*ZW07q9iUW>pBattxmZb*zerR|G_Gw#{WYO-{ zf3&Ex+2f-5GjCk)F6tkIE&RcRsVh%8jpS=`uLf zGI==9MKgqLD5tT)bduH2gl`d_oo%cq!$BC%!_MLaG|ZsWhUF1kWhVLYwLP=y`pJ3!)@^=MGr2xp6hAvlOpfMZd&AAojXAZ92}fz({D#JgMq9tWOgh2K=dW zR&B}DzIvQUYxa#-1f^3Y{&3vPKu8E zoEY8cg4CX80)L+oTlvh?NS(230BCBt_xU=PD5*R>Poy->DJ?0+3qV{ zm;_meG;bBbPLOu2n>dVnVG#x>5Y;LOr#~rZh5bcXx*uCt z))bO%9oX-;mbt6Gzt~o7aO(W6zU+{n|z4W4Cg9VsuZl{s;voXH(d?7(QDz|f70P7Tj6pZDTkRW;^ys{=U1^hA@I$ndV?9^2sv(3<8qo9B@BF=(hLoJxtC*ubwO>9qF z`9Iq>jD010lUOF4UyP z-7nzf<3&A>yL52M8M6|vH%#(|rB!LHb^N9lllSi23JXpsLm3Vi zJ*AUeVV~VTuPunff-K=K>i!5Fcj(pC$!;v&9&GMS#oUD8Y~*qSwnWDVdjzQ zY)y7}aOp)a6A9=hHbC~WyHk?>Z)Wmy4Jn#TRJgHI%^Ir__tiBV?Ll8xvPwFpvF!T& zI>WIDZR!!76V307zu3|EOJhYF$9I(L?N{Cp_rdxU*02SkxDm3iLa}@ZdvYZjZ6luP zc=f!zNNt{0bFOS}{4S?jwH(BbUIviTU0yyB{uEIRo&5&$;{{aaOfAW`V>@k&?b`cp zPg9|lOkzy)l-T;>v#!xxBU18yjc8%m)Gd*6*3^_bBTi}U=xQ=qp&+l!##j6q`2z_X zm~(mP=#B^Bt_b(5K&LP<8#}V;icLD1CUec!!k`;A_dy1VRpi$|{>AS$rSNekUZ3fM zzsr?>QwtI4u2uj&Tul7tF-J5pru*(-O8LthAACm&D~&v@bUa=Qx;vXl!Kzf5c$7K< z3VrK51drrrg4T8F7A{QM=L?*(SmxO?^FPg-3s&;YHL<5txFw;=vJ!Vjg6=vUXllYu zW0B6#r(S{SlKt=S>A!8mEfg@QSYj2=r?BfW^M9;7Vafu~_T2d=U$dF*ec_ItIm;B! z*Y~8!J@~T(s&Y#q2(qMn>X2=w>+bm`| zWSjVm?%M{$d^wuf#7SDu;967kjj8lqRuj4#)&`HubK&dh%55fHfS@|o(QOVLn)`w3 z{J3|2GDtZQJn+WuFsG2K7~1esf5Ji0@bh!4vtwtF>i1x#9CeYqF3U3hJfYt`rF*;N z_;1SfVzFlRfa%Nqd`<@qR?um3N=))Q{rBrb{&q)p(Ks)Z_PS4RKQrXD7BdCx|5gZK)(bx?C~{egWi5SQo&gIn|vVU^eIX z)>zQ5tx?z41#J`!fmY!g&NIKOlq-u7Z$OxO=VXz_cK!ZOf#9okMtnK^Ht?kjgft4^( zTfd`D;Py@G#br9_YWojT?IL2H@e!4G z-;y@qQS@h3x1tb78oG2i;HS&1F^@e%IDtMMn4r6=P5^?>}uxAWnnvN_fEO`FMY&1E$QlZerxIyU8H7Q z8?@s3;At3N z?AvHZUClpy1J3WD-OxXch3z*3cGCuT?mm^^6#?{E0-5uUS3i1;mAVe31^73RyXnAh z4c*B0=R);^OV~786~=t%qh6t=}b^rfM~E}3;9yI0jh-x(+JTnFt_h#l~AH@z$V|B=$? zC4f?THa6z}#c}pu73$o7D%84*AK;)WYHtuw_+J&Z6aIgzs6i^!&8QV}olWhC$V{tq zCKYP?C~neag}YpsfBm+10E^LUTmD`z4-~TSSTfgZ@l1e^{);V~7 zev=;XjVpO9JZg34jQ33rv_T9^=<&z-M|`UMD71$5BTdq|xv(E**6M$hv{Kvnun9{4lyO+W<8RSp3cj zBAh30EMtvdptOu7l}-I_K6IpY5gKzPP@5b$Cc+6}Lv>aS+<<6|s|OveljKbv2a2$Z z*r0zeho>E`69lzJmoc=^0rSz;;2Ha26kGpybw!|lQ3lj6y2`3r=CCzdBNR%RY$7Nj z2fRHWfeiJF%d4Dsy4cIEU4`%8hR!%=oyN8~3=%LvVUSM=wVS*%17= zC2i{TgTa+`dAt8diDv2$V>PT*8|wtMW!RtY^V|`xlwdQS0sD|LZhjCf9}u?k@2G4F2|-g9>)H?ZmW;c$hVu+tS?F0|C4JUYEw7 za^r4T77?CDRF_DqvwGcR!ugKz+`OQ5=|?0MxppU}Pl{X4uIfs&zfbF95sxm(=+?yp zUWQ|8*k8EvwjCO|-Wh`?S^xTlD%Gmrz6<a8szp1H{{jw}x=e4hK#E#Jl;I z(v7j*Uzt`3Q0Z&mWZse{0^#rD-SVqO{TosK4*i~UyXZuJu7%iQDft+LguOa1eY8;A z6{R?2(KRcYU~9c+OKVi1C|ybabx6@MkQvn`+w1ghS*zXq+^U&bUvhpl_FxzH2sc$e zn%DIwyVTtnC1z+$>_!Fo988oPFmCBdisV=*PD-Dq6i6&;I!uhc8HAklQS6Wx!YQ_p z=SczC_tJ|5KL8cWPx!Yh2XFXY%qyu!okm8K57t(b>*l(+uyQYn^s zd1S^7Zmj%{^?dAc(G_>lkmY{%YyHaw0&5_pXgbW6_&H~kM`j=2@q-Q{u$e0)kouRA~hXgXtISYj}(3^3<$^4a*CQ1w)wv30J zJ$=TpQYfuPqE9g)!oE^4$S250M*0+$7aK+oF`woe%MtgVT4-vLx-YWQK8PaQRW3#s zb-px`(jgK@>}Hp4$Fbiy07(UcSolRLAYkaMm~a3RN`jtiS7yCys9c_K7=3y1!(Ih$U4SkyZ>eikfel?=-W1~!CR3m0X{u0|NO6l5fYZ01fL3vq@xWom>96_@9D z)02PqGn!6E2n>c40u0g#Qhur^NUE9_ohcMrO!m76hZ(bzt$n_KBS$z)BS-3=7Ok2O z|FYB(Enuqo!Z#^!0Bd;}8Ch&xn0{Mo1?Q8UhU?g|H7UyBaOlb!jByq<^UPPxc3DD1 z#ELElQs`r^w841@Dt(_{?5=^U^6%4Am*;4H1L}0N`#)QBen%_mGY?doD*Up?f;G%8 zgA$F4hQ$oZkZei*u?}f~hz4tFPjRMlg4OIa*_zNy;#(f84Y*Vw-bxy~efg?`?40kf z6Fu4O)Eb)Eom%}DHu-ZyotbTO{2QCm{?(-N(|s^JygfKQM#A}|HdANWHv5=>WT<^y zP_#-+*C3x89Jm)Mootsi#6kk(Gx!M)hV+ZL+@UlYJm)2DsJ z!fJ`RsHt;W1&}dUb;4n5B_09id`&!0!57joPIq9}s3~wG#qAQyu6{BCfgTKwE#Rc$Il2Sq>0Mj-4oSR>>D6enwItCQWU)*}dX=tjI zc8hoZ*~{#^`{ei|=f^MP#zD*^cp}P{bhZbyn;2YPF92f}$DuC!%*iKojRRW8VurBO zCf|cUeYS5a4>l?yv>I-^`R)Qe_)6BL6c!e@nikah7_)8W4H>?O2UW@vNiY-GDe6_o zI=u~=j`AiH*1Q2npu}PA&|dzJmTo~8BE=8zk!gRP#n-rQovWXBC6`TPEd`emGo@$o z7BEvOJb>7+NIh?uU?h!An|M~OKxqLhsGxou$21d{)h))*qT$_oL_QnNv%&^bfFg{P zX6+LijB_ojSQxGk(q(>hko}zwwiRw#@hx=}X0<{z=8>tH*sRJU!?f3>8~W;`OWw0R zdd}k0Yux@%=KF7!r75`~=gi)u5>fvy=K<$(04IUa`y%K(Z=U-(K~MJdu+WblkGM=^ zKVB{#<#^Z}=z?;)89NQ`UL|t&0We--^1fe8SF3dJ4z1@jf6KtWAM&?A(^s{dVnzq{ z^rNEFn>M{|jClYdB&?yIL;^Z4niIYbFY0Uw{d`y?ApZ{x0g6!>9qSJP{kM0Tat;o_ zw$kkALs8iR#qT0^<*Yo5rFT)CN1pUxUB5-!c`a)O_1p=W@%z|?6Rpu7mkV{{^Aol+ zCYOY-FfzK~g8A>|@d;1blSHNG2N^&sP6|z{G_N!OfohsVvUWl~K57Op9ZWNnVWM<061+zjPx>n4~ zRy|&sqm+n5^?|P*1)b`-uB>wW-rkD(#yk27{&~3|N|bM=@LoZ?d;F0u{1i`$^t#lv zQ_GW&xXR`Hh}_it`A^9HR`V}tbX`Vcg8OFKjuW_ld0a%Dg;l!hx=KIS3%Y6m*I>tG zWwZo`)MH-NtsMuCnfF|NM*BvvZP>~j*F$`$W8&k;IB^!HbeV3LR?O$DCl-^GGl)JW4Y9~+c zU+1>qu3mONp!b2uUltC;ousRdX?`AK_(72m z3+VZ^G@LiCp!tJktzXfSHFQ>h4}acA@JQzpl{i|Y?{%C5w`s7F-YQZ7(QkU4@Qn21 ztuDwqJSd6=%iG~x*yx$850wJJm`{C|rz`p`46LftL%Q=$OojI+hAYStac(7hrY;2$ zD(1>7JbY3%R52VR(PGQkzQ3R*^_w!B5;o{buOPwT8ORzD@p9I3{3zAN$3A5j zXk#jf)B@Y6Ma5-(0YE$4F@d>iqr0eV?w3C0tZfbuD?k){oToG)5{o6pT?O849U}EE z4H5yiAV%Gz*3hXY;e+FW)|i`A5rNk{1)&=?u_H~nLRkP*iM9TY&K&T3p^#8|VD1sO zuW`Wdt|e){=%r*EWeUHa43rg-0^v{IA;)157Kz5w^C^ZE0fWgfCj{V=G9gk@a9(#E z_2*;#g-7cs@?7)SBq@V6$%vk~yZ-4&w{OIF$Oc1o#gU z8TJzo*j3tbZc`T^7OqN$t7i&ba_Z+UXZ_}THTYJ6#Z>KjM|0op>y_7CDmYTL`k(sB zH#yN)F;uGP0Hf@egq>OPHrcAI3K~?m@{5HIqa*h=AMSZonF19C=svQ#1i#Or$qrb~5>&SE**+QtOsj}=gjKH{-4qo`? z?|V;Mn)#NRZqRd9f@-+qp5-$=S-vu<{A#_!p**FM0m$vk??~D8x+Gd8t==&!5U(NX z9Sw7Hm<%9gZ9sX>f-el2wOV$jw;@Q$-_e?<-*EV`GTOh(AL*f3}L#IF034L zQGYfbR($%VJ$2BcK_~`JudDn;kP*`qXQ$`Y^hG6Pe>t%mB45zANHP%VWrc*dj5@p7 z@;+3~7$BBYUK#)7XwjDB!!Ebq9vcuGeXaG$@X1iUNMEufWnT+<&WVntjx*OuO=Z|G-;~LB5j{CzGKgxB=kbLISP*XeEG!)czeCS zQ@!ObtKUlp@P9lYrGJWFEv(_|{`F6oI>BdRIyqtz(v#gu&&}z26Vda3b+DBLF>)Uy zT#|;ml~obB?2Q%xkVqR^WW#YxX5!O8LS`UGNxxPEnA^=QS$ZukvdICxa|rHLO>Q<5Dd7LN56REw+*>W=74~kTdk) zenVkpk7YQk%~EJKut_RHq7oJ2`_a`?5|y>{LYV=8zH-%+RLPUlMy?FY|9UkY)2VLF z0_sftFU$Xn;mvLHzO_3n2b#2Rg7baVNS1Hm+(0Nd${U{FhbrU&WEjJceWEWQepdMVESKuKjmx8K#2a8qw0C7S>LNXUMPQ2uk zPEF}GiRtV`42#_}&Lq0nycx)E)4DFE8Q=EiMXC?2b8cqK(7w;cgEZ{~1| zXAqA%ueo0K^H8_Q2?gsfQm9fbv!s(8YofDoYB9bH0Kp^#f&&)O9ax zswP$K(Kux9JZv}QRTJU^A18s7*NJ3rw~F>LxZZzQE#PhwTOA#Jc2+MW9``Q7OPa~b zD)nrdH{E+O(?5{Y?Wb>XEb{=lwG15(1Jk}XL~q57UYegR{W(uav}sr;N*L`X8clHZ z8Q21=*j=jEF)C|cYnn#C5#A=KBO04Su$b;!ULE`@H5hNsfv)EBpeWsOg=@EE+w{nB zNx=B_4QxkL&4~0EUpA)dT4ap(Iaz#zYTXIf85 zvBFljdaR3G!$3!V(dD7^_l86*!r!0U<=Ewsa`XlD)MeQ*$OYnd80d6QaI$vEXesa= zFcIK1G~6Ts*nA?vLF|7#zj}8mG339Y8zq7*6p|hpjD1y$vMh>SRwlHzcSwN-IoO-> zxiEO}m>`D1##zafQs`&^;dvS}#e|{Y^msul{9P!zs*)4_Q?Btjk@G)4|K- zN`3O*p9`GpXbgtg=!HV+IE^%vlJT5j4yh4h=jjovlw>HW(0`ypyx1qOc~*URzy>Yx zw_EpbGJAkyJ5!(;MgODDjI7OxVu?sGq%lHG&auD+`wb39JYN`KfBW4jadWbFU>O$I z?VvE1Xg=}MNp>+R*jl=ViBnjA>5$_3`mDG*0`Ev&9d@m14ZWf~%I!mR(o*zXQKpX6 zHa%sLl8Q!H1O-KR$qtz*4B=4YSwex@_tA>9fZW_IFkE-P*Zqt!;tM@k#@_3#Vj(dp z!+3KfO#JWTpo=Ad3NlPq0E^V)0nk%Ks3m8kg21yoNeFPcX#2kQAb#S~RU!TCZwEP1 zPW_kIh9o(5M^{3E=uJXmTB)e4lo&}u##a}wEQ7_l@yQu%Y?eFVELs-d*Y;`RvVYj%*Bi*cS-|udPsiSeLax9$G$YZz-5O9YL%Zqe^V^O=Xs(a{D6F_<<(|2Umt{CW zim#ZTdIS7%r!5kTV%1H!&EkEit)i`Mv7B3gU@X@Tm1dVcZ$(RW(Y-RSXgp|0$@6w71ZE+YWu%{z;Id7RHH|0c$Il)Jxr8u-q!vP*_Xc zGG(Hq+l>2RAvVLUG`!pBbsnc5rTB;>x}qP|mJLYr%U3PDy+)I?>KNxwc_I*EMKJ#{ zY}`FFGn{3x=JUiO7^G$+lh^el9msa5yCJx&;)B7=wX`^9sCG{0GSl0rfU{zC-$ygq zco+PdGPmu5c^1UP$^9Y?@^54A(ffSl8+(bX*}n3O{ax|v_#69)x_El>q^5m;YeC%k z7Jw-HlY*`!=i91MT)#$;_oO)6*Zt1%+M);b>g>X%85}KVCd)mQoi0B)h0QY~^&dxD z`ah1g$xW`Dk|=px+R)nm(At$HQvTcUC&*Iqz~VImNhPieL;XLS2t@sVe~y|LDk-e_ zYR0fe#(Zn%w$fwe0Q}oMi2l2KEd0;zLA4cCJ~Mp4`X@a*yA@YYk5sjfu`)9YXurv= z;P=nbgT`m1Z^-=rdYx9#^~H*Dj%3z_+LJHP^=8CmL_Z;ZYdV|>Sq4^!UoLmwudn{p z7zfWIu7V>e)syT9>_fT&>!wErG^yR}Sa$VxBQeqo+&QM!LE0a0he2WWL%C4t9Z0p* z=mIo)e~Kx}@kVG4>e7lQj)O4|-yZ;_n|@mmz%_V6H}ihTvQ>&l$LC)VrPf9m8)E9D)6zD5y0?}>7kHKiL}(BpdRgHd%+n{jf5#- zgY;(AiFK@q1XIHBfG-!L!Khr4G6XLln|#a_(pplFs|p}rs1A4aSRrATtO~dP#Vr4# z(DRC0 z&>9;842NIW{d_%4eKWo3U<>n9ATa~gbDnkDZ(Y@HYAt!agSEZu->_T@ie5Q4wn?x= zuHC92zVEYwO|bX@yr@(X;HypBsnT+@+2^T#IskO(HCkDq9Bsq>FTmx|gEFYJE3iQ` zrw-S+QuEc@|5&yO%!?Wvd39Cde`XFWNcoOqhlK_C5#NE}AcE`OQ!E^dRLY0RKn*hL z=^?6Tm$5*gks~^a3XZI%{AN?sVdl@nMtaOdDZlhI!vh(Pq z$j&hFYmMke_xG|j+>!zHHOCg8N9>O-j?1Sir%xo^y~+gFknSHgdX^4G@5R4|Qft8G z4_a<;X;PG{-?F-||7`L&&|uZ9m|)5aaMN0rl!xfg=*ubxBIpH@Aa-AoGF5q8McilY z?y~a&S`0Rplh3v>V9mVpl#%FAgoJUb=$2BQeSKmz{mkRms(N3iaAQp#9??o{;CT+! z7CkxktD(Ag#)&*$TfFIMsvnt8VJ<0+?%qpj*({LOzIMbk5Y<9J(&C3Z&X%uXVE?fN z2>7NoXkv1zSBoZ^msQK+Z$|L-I1yjwPxE;L4to|Z6VXt*Iyv+@n-x8DdJ%akS^ny| zq}FOD9;UxcgZSf=@7u1+E279U{cM*E?);uK6uHuuYQ>|*^Jonu(7TLbsH;`sNbbwuDTM>`)bYY72Y;zGg#L1tn%HD${zA;v29IHF7geTfp}lbtG-dC`2EVCMKays&fanC z3%_p|#jG;BFy|MUHX%ze;Yu>P>fEn!oF*88l7BBtEUs1*lzKko>OfN2)kW(ai2eSI zL%<}ms~N0H!b!rkQoT;9nV}hbG~P%CfCAE!yg{@dRu>E3WjDp5sV3@Q)C?&tEE6cw z6n@C-_=MGrmVL;R-iXXL{*M{4!|Lw023tXh$VQPgEzV39D`T84%92{P$N^}XIn3z{ ziY85|zz(ZuiwWl!c=A~&FOycYawNi2{GHvDQ$j~9xLg~ag7Lj+^rdtFiS^zdJ;VH? z)S76wt6 z$wWUdDn+u5m^%!l+8D$m&$)i;0le?`o->d!JoQXh12&yH+o2Aq$K9~apXDa6b`Tyn zJGaU8Xo6$QZXeiO)kJ%Msb;5*bQ0?`?B=!RF?T!0VQ%7@;MGKyOVR&B*IS0w5j0_< zxVyW%ySuwfaCdj-Kmr7JcXxM(1b2tv?(Pumo_yc#b9eXd{Wo)_PIpyJ&vf@x)%$W+ zM>L=d#@=SqUfKQ5`gGj9dji+@i|vdyl^*5~5=Hmr{kLjKcj;c|cFY;No!(r zBr^LyI*;1_kRtYqgK+NC^}})VtIl#`x@)IoKIXl1%^g^oQ`0xv`qBmDV!atnoUiG} zdicvCLUH$&L0Qgj-cSuMuPho@b3Y7(Q4!wE%^8e(1e$w)7l_jri3KMBDS#Es`M1*E z;Mv;#>q`{-ys&bQ!i?k$^4;>;l!*3vFls;N^4M#uWUpKJxFXtR!A`VQ1-`r4QFHx@7nyuYJCY<5o;9a6M;vq`L81OUtTh>BDTkgD`l#$ zFDXlvDmAU`gP&%n1L6tS<< zr$Zy=yk27m%4@z)R_GS5Y6rssBj%9J5EUkZEN2E0tETEL5vzK@dkQ@r^}0L~RGu@p z=M29ses#@{tRrzx4< zcHi3Tsh?F?I!AEPl9tDKrpooZFqqxgj&9fC5-?|TT2PlBA2tTK1y7E@7cJfgUYf|X zRlF#_U*AdKupr%;^pg&08B3>kTB0FqUOrle_}be;JTIgGWCtIcM%CTo**UoOc)|-1 z0VcH(Zjmwf6MDIEdjcs(<=+g4+Tr`Q^YyFA3#x;koR$23G}gv%A6-jb8VX&2cy`|k z)~gFExAPWE4;`w5LZ$X%Q~?vC_7?tq6vy$ zGa>Q~^{H4l8gi?s4v*KkPXqJ$!KJ}OFRXR1$LSFbxW{heG1HQMf7!(n)i;Je+i-D; z-!!BCvF*O@)xN$f*hu+Koi+3kw2s|)Xd!eYwf&0-i)!D+P%tz4Jg2aSp8R5eluf$o z?HoR10>0Huia%57MRTih?qy1R-#fFT_h)5W);!XBT$5h(R2#$_f}o!01Hw88yoSBd zz8Z%UfS19Z*7T)RBbEMv@bUH=xB+Q_?23;dFxw;hSefn1^(+@*K-1pvwE{3d}xG*-$gorn2KgU8;}1!(zLo zrv9@h$YhP)f!q15{#P~>#qNQDd;_lEtvYm<%qGgA%oyN`8$rVF}z>07K$*^e< zKu+nnY=+)Na<^bHytjGE^Eb{)HMg2b?h*9xGe0cwz@)38Kz$2ncd<@$3-0oFDx^nOuPIR^zQe+10D!f52Nhe!4J4w%@hO zOchTRJw0QW%MmD{Vekpl0R$fE%}^HVex8^>;x%9oa?`m;{{h9S;!*ca`oRN4_OftYfQCcZOo5WLjKhjMnZ<(_e^zhb-#s1S&N5R@D*6u$|>is*U z2MQM8ggb@NS;<-59a%PW4{)Yl08znK4~hZ*fdyM@sxt3N`UeYUerZD*T?uQL6Uhnm zfU>nyKzYY7MoQl|TNEn}@2I zdqgvOLADC~e`u1BrAPRO@!!uWO=Uk+5C*x$Q`ke@0Z77q-4OIwbbqcMH@AAB%=Z9A zgF1h4DH!$NAK6ncEf_v#q?IWL*hkx2w3`Hb5d4`!?5U-ZB5Ej<5d7)*T>7;kuFVK|#ezFOfmzF=bf4A=T!)LJG{mdoXTEhzhKv(V z?NYBOQtaKA)cGab8ZY&8!efDuO;{*i#R|)f%f-{`5@T)p#H=}jsx?xrQ6jleQl7R4 zp(IT$GU=Q)bj_RwQgoD~5mQd|XM;X7Gb9L2X!MY@9$HPe7)7p|KCRmY&+QOEs`>kL zvDqQM?&)BPBY6!*TV4_7vZj1*043R~tuE-X{b5_p%{MuE%FZe)mjtNjw~zUVwK!F( z$au~iiinfJ%v2#?Tsh_vbYIkPKNtq^z(ghebt-9U5V2Aeof8PcVb`8+43PXJuzn=f zqkCIPar2T97H3!f4qH$|i(nBzAqWXtNs!y=pUN<0J{L*^8D{fJ1g41|ft*CB;L3a+ zZjy)6Skn3f_Bo^%NHiV?dI9^;1+_KWEhnEB`EH|CNXdCcaPnR~h-1Q8=q-4U!`Ixu zfz|?b%8&*sNM01j9L*VKixIl^isG_lcx(Rh{6G(B&(C7587PXED8>T9KtdD*TW3-D zq7Qw2XhAZ<=s?_k$R_nxZd9pjL!eJ8(mPXgyCuKj%Za2Y0S&M!Qa=a+j4pP^Le3>UN#<6EOu5EUQUQVr$w zJoS|I7OAB5fDWq6u?9pDgaJK-1(MIm#uYo@Nlq0a#=?M2dVDe-VP+iu^GQs5$6f%* zK;>SYnkf|Wv~qCBP(Q5}fh%MJjN%0^4AeI1Y7@iiE;Z!m6q=HROORwL3XPtLHNAbB z+J*@UCB-sClI9T(W?>v(N;YL7-co5Sv`)1$rBk4hGUul#9ROE!^g&H+?0_Zp{ICQB zWGTKuy|SY1FD<^0Yf))zFv&E{sf9ZeVHH*0Mijk?h%K$l&AK`~d=_PPFIvW8g)PLm z7S0;nddZ?I4$q@p8N^IF{(Rn^G_zR#t3aJ(^O9Z3{VQd3aa`w(-jA(t*;-hl{GsPZ z=Os#yzzXsYLco@8#@`OufDL>Jbq_jzc?p|VMFZqU-MsN9Ii@lo7QeJjWpU$Ng}eRw z;v)$&B#F8%>yz_i2s)vZypP7$!FU98sCQLy$K0H|eP*{Ob8QI3NzHfj{4zIu{lFOxVuVOO_Ri8LyOIsXzTgH z@>Z>~UK$tgSv{pgj8e&djiNg8of=3G9~=l0*{=f{Igsw$BIue}!jWJ{`AobV*%7^@ zw5uWD(<2yPF|!G|Z_sjpKli<6VeTZm=Dih@NZ#hx@|d@;VzX|>B){Of3n7j++Crz= ztX+veKY;q$R}hC+0@kCGS6+hHFUyeVz#*V>_3iQW2xvU9o-B8f`l+|m!o-h%j}bDP zXXjl%b`OcXb$9*Kyc{%+bWAQf+2 zq%>w3K{Nd72biMCv0kP&->2S8MUMu=$4kPnRV0Tn{EZsobE$X}VIB%VM1{cRjSlh7 z?hU!^h>Luuj82L(sCvJFMMiXyl$|IXIQ_%v^T$vh7Evt{u)Q$SU6txjPRHuOw;Z-a z7%$DMdrCSlvrk&0!}|1QWl9nK^RHC%41LDug2Cx4F2Fw%X9T^}J|N}iudbxrd z>B-b=DxueC#C7zto7HpZ#c({~ltqp`)<9+}r3A6o%clg?iJY%Kvd-GTmtUCV$;QDv zs_WfVtwqdp-TV0bQ$<(!3|Wj2Wk0Sj+TVK5H*;S~cOQ{An}{>`{wm;n`5b-yTESYq zw)pr8^aqs3m6z?!#kJJja9b3^eaXczTYP7;&zCBRtaIcdCO&f?$F-mPRt+TQ0s>6g z&eSIM!Y6B-qJyU}HFKZfnEjOxNzeA_yOj#tcwv9-$AcZuO1rMpmoKoFmEhwv!k+*8o;S7kAHpvy*Z&Uj zduZ^#WbQhiGhw1Yq+f2{x_yVd1C6*O3I7icRA+o=Q)i`ClVLyCuz_g<#cg;o#hED( z;&=PH{VQ&B@RGQ%`~5E(O<0u7%jHN~A8-q5q}-!N=(BL`wE^o0CfpYa_<9;(6a>6K z-A_CV*RRif-LJw>W_R(ZPA{n!PaVUI!hr(0MD1b3J zo{#w_oXAPW%|SzXz?0-i!DTc9kdrNhm{;h|mC`6>CMzG%=nTf;dDC*VsYp)WSLh7> z6DUYe8Hpy#e#?ianIZO8_4T}h-P@6c`RgdqN4D>@?<;tbN}cXzX=e1X&guw$`0p;z z9;b_=n$LS>=58KH&$kQ3?22_SL!__!*St1i_EJu>v!$}tnaCJ>Xy7_6tb*QOBc*({~ARq8A-LZ9bR#?8vd7+_|!+; zO*5n5g!1QVpE@XJ3QCmw7rlTSng2c4F=`!V-dB?UPwtynFEnpVU^d>JoD2y72Ks8J zi-h|5aYx|ebR{IJ5jG8=V)TT1cDb`@CpYpuaz@|cFmcH#NuSC&)D~Dn8$UUY`Ymfv zO>u4`djUhRAx{LkhVXT3-pTql9$Gxmkb}-zdN%U~J`?qBW}9^uZ?-dWg!F-Noyi8? zG(nH?FJj6WQAQTBg+{2&q~KuyWZG$BRpe|Co8%#S1k+qi*tHPliXSQ$se@ix1umKW z(97B{6jRI$pf`4A>D(;xbPtO_UO8(LP6Jea&1ag3hrunZY3_$nHDG9POoN>TBRO$- z_ltsoMdVa($&pKnaB^f<;W5k#i5WJq#(Ct&Li~-N#1{u-h^jW4{dHy_E?M{g8zzK3 zf08M`srWK7EvK|^eYq(_`4U`5`P#DMh5M<>Z^ZwOC#_MiYq9hP50iQl{frlaCPgM@ zGNzNiHvQVi)vdf5Y{L)TszhsPf;|Nj-_Fhtl6FA#7e%Luwp1WbW3&wihVv;ZG&`PH zjG{mG?U*;E$Hzew7J_@ z$c<;47QT*&%-Oz;83%7uLrM9@XsViL39kyA#IaQCD6|;L{FWk9*u7tRZWs9{c)Y;L zbxcytK;NRls6gsGihq!(C87VUruKKUn)E=%P1*Nl4>Rfq)Uv03UZe23qw}IVPH|BV0K)1jTM|tuk;m z{!NFwZTivkSrMK&CSXnG0K{3@E9=<^V$-vNiGEsjJw+a zYae)c-ugdC5@pm9gj|R+I@hSyHosveRg*VCz}PQrrrMg=+C62=eEdLBa&l23)-ZH8 zA)hkr&O)3|nw!!An3f zcONXS;^5dH9@Py4K52Y+T+;k1QJz%>J{uEifyZl24E5M64lWOcD1cyixT__=KBOKp zrasmT-)eljzyg zT3u!7<5y#iYosl-JNjq2?-(`BiiT0OSh@=&@A-ag4!I$IV6RQWYk1EZo*9xyOdS~D z3rpOwQ$qa;SZQa*k778fE4t@^p;L9H@vHr$p6TUw8VH!ge2mczN^P(ZCOYkx!YDFG zr7J6XCOBK-Jkk15b>X^X6oW-l%+V+VbWZDyMeI(Rr|~<_%5>qo!Y+Toqu7uw>8~7Z zOG5mQorpR}YD+C%WBZX+%v#2$+(0kvoq8%*JHETCRd-CD{G-D+Q4l(S`^_hPrUZu5 z>iAr!$iYfPk49Bc(w~WW&3>nr%Q{BV97BjNLbI~6mF<~2k$96v_$s!ED<8JB-kuN*9Bj0C`Trlk1Y7dW@}!c-gqr|1f)1bn@o{m$d8S# zQN+7gJWOPCD|`e7+gx=vhLy)fC1gb-WYdhInc?kF(4g%vbl62jVVup~Y*m+8jI223v>@zd7V z-eGJrb2c(MB?9PO0mJP4D@p_}ys}x$7AmS2_JZAPB{WQpoDm*-MUa@cbvh`tmTZWz zN9cA$d4(dk4nDfn*qI2c)h&E!r8TBr^>geO*9SO7=SUj}M+H%@BKbQNHZo0d#592c zcu0w>BKjWHeTwN`JO_Od{-b$3RHQfQ5!TpM91?NjapfDP;&^D zm>Uv6o?#>oj&{W(=YC-c)V(a(56uFB6efvQss;^(`j+EJREL8I*L(v^$l${;WLcNJ z0H^|Zzw8EPyx-;=mAdB&w9QOY&ZnE4Govkw&F+T3e?KZpz;IJ)+2#J6aXRO68g~Z? zv8O#V#6^lk0s!9=?B@ZEOCHhmy~%>90vtTvycV6&Cpo9aZL#@ ziT`*H@CEjB2g#_OOddCH7?%|YK%Z81<6al?9ZOcsK(-_>6vzWA9>z37F1od%2I0cv=!#7F7*qz zmL&8+W?Xb~A5pwPwYVV7TIOxfh-`Z-++YO(gl}Qj|Dxy*`}ekvA4Av1{M>{#;@_d< zKEK<6PY9m@Q9G!}(=JTOmW)}h9as2EYa8Ff{UfvDe4VpwOvtu^kKi*``O`|H3{7h>N5aeOf$1fE zqY={W&608pB%Yuqm8W8yy~qK{QU>gVv>n=zN?D(E7!G6?;oYyS1ehZH%uF)rh61k` z$1rp!cex50QL3~PpQvDFSzU>Qy85}#M={B`*9{g|)!opo9MBFM$+F*`1Skst+kU%* zd`63T_RD?IJ>YkGJAF#J{Oi*^T1iWIxa1;-#aKoe=(vz+16?e5S?Z8HT{w*h(=-QXeVoN-AI(DPi z?^G&ZUi;_V)aR96O(^Lzzq*5>BcD*sZ5K9ecF*cTkK^7>=bB*86%pN?6!jfee3EzZ z8xKvEetU@k-j{Q%^USl}GB4mu9*DJCcTUvaTdT^U2mh^m)`xkPgryR{^=FDGCASHt zH+m}{vqTOgiROnp^X;Vp%-xkXVhw*`p{w61SV|I))Dw)3I;;>Vu9;C6uHU zp3IYy5{{8|1JTO_PZM-epI(~x&gv2Ln7oL? z9hNu8)=mc|71MTbgq;D|uM4%6wR~iqFMroOR70PI(ce?Pvs86z_21k~b=P{lrST!A z@gr(k3h^30>GB2pehthak@x(>MeV9W$$v}qliW5iQ;Sb?mMdAwb^Cb~5qrYd$% zd_|J}V$q*^W61Vff{NqgwA5>JAF7Dx?q$)7n}UwHxg&%*71%Tmq6d2vlFdMkASE7C z5X}0vobcgdhVBj{R&qk{!bEy4HR_Dh!hZ52lbn0Ca+-1|OM-eJa_tK=TG}Mf!qME# z-POXx0S17u|!>z)ikqjd?_Y{sjRB{oD2^@d~b;!BZ=#@%0z0uu`V?P z7hLukvtV=!Fe$MAa`$^%Niw!i01We?=cN+mYjoaztdl;OtC)`vCsiHkGg5svHM{eb z)3&9m!X=a#Czye6-03gJ98?I@#0(O)`Q9px#ww?2OVLq?*zrc4EU<5I{_TqF5MDDvNaeuKJf4P`{DY$P>`p@tbOm}v=`uhFe4A-x z9|DGLbf*34JjRb@?Q`A%gfl{N+rO?Q^A30Wz+-f8e6YIt{)!~Mg?sD^ejo^`BfnGB zea`SKpZuAgS_*)P^2(q%qVf|3Afk?vwRjnsT{aPgaiEx#_HeJGQqan(%AtAL-ZjqK z=V$9U;W3`2;K88@msd!(lc*IDpG=mJ+Bo-My}@C%M;vwk759#M++(1Ml~jm47fv$ECxM& zY72hvN&%d|RV#5!Fz+q1%FIwA7bu{@MSj1fnM(UtLPg($PJg;z$tL&KVH7F{O~33{ zl+oViFI)G^6 z159H{=H+9G>#!Hj&*9#S-^jzlm--a=;daxVNq_|ImCRN10%XJw9&7S@_6ep@`kR8Y zkM5n?E|Sw;!l5B?-T^REfB;)13>6;7IHd$Rsre7#DzwFJj2JL|!&s@38C1N22gpE) zpHgDn){B@-DMYj7&UlQhF`gO0xGss1I z3C@aT zj+AEIk`Q2-Y^YB?{gor!iDvfC&Au(p_5l!OISvmjHjMGQ8EfZ9ww0zsFxJMn$ne!EBP*y+J>_T zEUYgHKe&7h*Z507h9(n-0wHEHHx3oj3DgLjO!E|<-oEIMOqaQ)Ik7d>9-=jr2>=#i znCy?(f4qS$QStj&Hks^D!TX2nnIo7ns<}Mp`Z@ifL^2=8=eDcGU~XF#dB@25{nptj zj;(C3uw}SprDTl;UHPF$lsa(08Aj-8y-cW9J@HB~#`pFopQ%i&LzVyQ-D=UcIE`g( zXC;v`)1OfxrZweUTkEH)JV0nx;Wyb*0TxWOWPRv=e83!}n=<28E;*6WAmdRU3e*Iu z_&?(Z%$5-UE75|tJ{YN`R)k?xL-xbWU_*PY+nVrt`vkhlnF-XpWP0RUtY+)?_AQ6u zh<#JPAk-GSGU}?>x!H90mB)MvL)hh~UN@7D41X?*1-T6lz)8zyEY~p0msaX$HAO3g zcI`gOWnWDhJLJ(CuW>`7#3O7fehA(`E8b?lpf~DCDA4Aq) z;@6V>#+W&&E^l&X#crlj9J#uXRT=i?f;-&Z+c98nHCKa(Get)7P)doK7!}=t`!aL- zjqQeb9(f22;B2%8exEZQ%w_>^#uCsgi}s}7m~y?jL~B)Mkl_fO>iC14*0$$;V2aY; zM3bwc(NYm-)cCu;z~X`qv$lgNS(GvtZ1}!VoxI3}(jJ3hdV9J5iASIxwaby~t;W_< z6;@jeiK3&UwcjHFHzH(dK;QBX;SWEA#-a~cghhK!0DKWvNl9BTc#C#^;q-QAAk&x&I-`OwL)kPlxGXc|d{Z}T71 zoeQtUfP0@f#UV~}^IDy>zB+7Fgb$fN_n$h83#cm$O7p(kuz!fndy;nF?cK%Mr9;L2 z&O`aP;6au9)4X6lgqVb=MgqJ9MvwcaW5anSJJ z3UGDSJ=wV#;^7m6QmVTkYp!!VQ@h)pXZ^$Ze9;dL5op90I6Cj*C`_O0baru)jEQ7; zKopo~o6cBww~oqj-~5W_`gyZr820OYkTjIw(WZyW+X^r>AhtpvBBS?uWBs zk(*W$0qaIFmxu8T?laW0;h(e_#byteI)E<2ByACXe&>Zc|5sn#43WS5QDfapyr9kZ z&kVE>wWZn-p|`Q@=WU0~fZr8u3+7J9&&}2)2G6w6bjB2AD;8ZgA-4&=)>zO&7Zw-I z=FC>c#w$3d$P$W93W~2}6B5_aN*!!ED zBW~jbsI3)=}Udy@%mMa>`W^=)J&Bp z6zY68=Ipn9ACf1ZD@O>Y65k)>^gU$gQq4&B!r!~q94X7Jfs*jmM?coS&r>Vgk*@Y+^%$>A# zF}o#Fxio6#O-aYn&laoBi#7d+2*XHNi+AQ0cIWD-jH)g=e^U$WbB=(lG+h;o1TJ~Y zsAme-M|odR*wI-R*aG0-JBgG|YwH$LTTOwrh7gusf4n@aiHQ3@EI^wExgKwEYVABn zBvv(jyxXUMCC<|3DAE2I8>?@uhH8d(3&%(K1`?DGdl8LbrXAm$C)e~9G`qmGy3uAO zWPkM_%?^^(w1IM95St(j{bn1_rt=Dw#{_xN${^g+)9oZ0Vr3BPUot~_ z*YPCo(h<^bh3k*Uv}jk?uw0UVyryhnqfp||Sa<)lC_2j?kS9J1K8Ct4LPJy7-2hy# zR9u96X+Ehx3+ggpZm-CTan8d3CWb+fT$HQ^E)6QNL&Uu9*j?ma0(jZUEO_B{J4!&A zlNp!o>zGr}tpcd2f4|VY#_(OO=fpQy#NCmKed{PI`vMbq6}d|D+yYbkziqg5xBo?h zx&Kd2p#LQS+PkoeLqyfM=jo^;6o|~+DyupOnfM9F?^H#jbeW#ialpfFNbnvNH;}n4 zy4vGD`U>3n1bAY%^#ug{eWi6qz)rZG5YGMl`*Xcd(5s1Wyc8gOv&o8e@XGl9G4b5? za618rQ{E1kaTNX>u_BMYV~fqgw^|G74h+wLj&+a5Ue=#=^Fr_FGU4Qe4=q79O6Q`3 zcXbed6=h&;*^stO?xs!g)~XLKOUHLpm}DA}YAnu8A#29@?}@8c-tYUtc#{KCp4+Bak2j!_TUeWT zzX$tJ?>tHO0WYzuR5c40a8Yf3Em&Y&BP*UQ<3QSip!m0etHgJD>iAV{=O|jSHWBt$ z^ql>StQKU3vaC?L_WCz=$JgO(&9-@n(#6dCDXY%x=J~GP zT`5lCZo>~!>^d&XjyPwS5 z2cBRK` zVarli^wP8g?yW7CtPUl-}{M83#@_ zL}J8n?~d_YZuaH=0UK(IoAInQTVu4AQ^XS;bh}4}O1jXrBO-wQpQ*BqDXgO;o51w) zJT}Vq7>&e13>l^j<-ZxW2;8x0IBC=`H2Tfii^ANLo>hGG>`04Du(h99~a z5IIQtqS#t<4w+AdET;YVmXbe&S$YL_UDXZ zr^~t-3{MR;ea!$`Y#n-pUPuW*3N}v1JIbKj(vd9SH9Rpm!G#FD~ zEg>{%%k6Bm&k~lqu@Ji{q7$yI0@h0c$D&m@1tGN1zEl9bhv_}Sj%9=~X}gp(Nu~fw zSHkp3vOd~|@nA&`t_;cCA8K`oMloYVa7NAJv^2rLvEE>2^Gz_M26Zj`zFw%z{_q-2 zvPL_m6a4H>kO#Tnru2PP)s4`+^h(yjYd+`|vQ80*$j596gTd4UBRk71S-TGPwPLRJ zojAaC8TkcRT>88rT(;d~dy;<|ztE&*%ZZZn?K4By69g4g(ZCKjht>-yDE&qdCPzq& zAYL5Hnofb}uy7_KQB$b!p<8aSz1P6$<(pSAh_mIWbl{}7FB>1VecgMkxxXISL*oWr za@~z>5#u{RR^<`zJ5*R1SSyb4xaJ|s#VOfEyH5zv^5O4VzxHFRw@7r|_f_9A(r7_w z0Tp9@LBsNMHw*hVK($0Y<*%7wxqToP8d?=~;<-MM7%M5ILJX_^wIveuB-j`_bL~gq zq?i;|9NE!b@~pRE-oBx9=99AafJNOBA-A?~t^6>L6gdU%@SJKm)4U8*rfKG&)pPuu2!+^-IwTJv~K8lEk=Qp z;l-<4Uv5XS1wWkz7(*+TGoD&J_tCKUOZM(;U%5GYV5)(8>q;BUz2s>8ua!i)U{3YA zW7U*jlIfdc9iD>ha!>1g>DcnJ-4&jMfF^lhx{YJK#Il0mWYNDk8h>1cC;5Ur5*@iA z6Xi|m8lplnFr24GS#NpvC{W23fExG-Y}!1mQONarDbN}-fOHBfa~hgA zP@YN-s7VFdH}=Q>ntOT#6kz5pkM{0J?$5I2W>G!Up_NVP&#YLvFCTx9tan)y{SzD` zEy}{2_Ip?r+64MPiiRQ%#CG5U1@w-oYFFeevwH3&e(Ba?FgZ|U(Pmg^*PimJYIP!| zN)AqsqizBO!1}s+v$SGuKL>Ozc_I@We#LB524;+pOLsi^m0*U<=3v&=Si+sgwji7* z<(Je2tVfGjZWfxq^{6RVbS=}sYbUh~Csi#)j+t#nVP9V!*-=GJ*rj@rPGv*gmKfF% zHb1{*NAFDUxR!1qhk^e58E`D|owSgKEHx8?L`4yBhXWy_nPg_A8MSaNNxXQbii0Yj z0!a{mNsR3QOB@u?-&o6hw$+b6%|hcf5(J6c{axlhl7t?worFw|5i+(Z4(xctk_MzK znH>@c1l}K_Jt}cnB=MnZ1ui1j^2VK0vrbitNDvbi8%*I`k7ama^j4=3FfpcEdy?L2w7|LRETfO4HwWsAty zj{}L3??55?N)s7gVmWGTGkJsZ&03QkC9x8d3~0doe+-!VQ?TAGC^p~v*5O#}_!hQl zP}^uP6p0q*7|-Phn$;K<@C;X^G9twU2v@z#rc?`J8uH+mJ(Y-XJrp)tL)@}azY+q*Knf-;JGeiOcpjwy? zjRgJA{Q%q1R0LJut4~=W=%c;*Lqu!85u0_Uc3U22e8{uwydEDER6k-V55i$>s5uGB z@rMqM+_YjBq^_jVYQ{)SXgOE=j9;`r;9#Jm%>SvW+NPVupXjW^l%LBGpo9_F#0jvj zPd@IrS5qVA))j58+IilFd(GgIR&2V;oIAnHL)U1`txb!v>jYim zWV#`7gfmOFV^FUt-Pu-of9O*B8A|jR6-lT{FaS7_A%fMGwnb1# zrcyy;k2;13M1Is1vXG_XA({TB?TZ{H^FOD-nyj^KzW&uLUAdp3ujzth<)MtE*y1uW z%xrx)_0FvtWIrXrzkB)b_Sp?6ryG5{=tALJdR;~E;%9P#JGI9TVsSbeG>#@&31n`8 z%U{jctA~j>21|Dx0jyCu-+DSCM4F?yBLL?+wE)nNvThQoGI3>`U~c!FOTjY7Sp6qt z3vh{{;pwjys1O{RJpPU%HVS%f+i{aO8{V?D)iNH(^O*Nyz_f|1_K# znFg=2w)cWOP2GRDl3|7db)N8yHAFy>L~U5a0C`qh;{FZD(clgKR`}|n3TZvpo%%DP zL=ODux)l(Y_uZwRdZ(hJqBN5SH0_%uA(L+j43WLv9)h2vsX{C)nklT=;no6&P&U7& zDFwe{Gs$z{a{|M$llQ}z>uXqBErZvhp7zcMB@VOyc_sZ{)Rv)N6Oq(v@-mEunL?K( zNKgIG9#_zSx87<6B9p=s96X6aS+g5;Z^m)Q*vmN!wv$?+Opn*Z;W}qTioft4#6P-! zsdgof9p*b-Dk*o$_;mbUVXi{K79TwxFE3lH?Zx+Q+3-j!9F>>qyeA&O$;j`76zO$N&CD3|!v1 z#sHpN(d{%IPDPqq4LNtP=n6T}YbLgqS;#rz$+nz0%@2v$*X8G1>rda|yICS1_MF4q z*(Ft-4n`#eyd!y*4(Sc<5|4FqA|u;(fX|%AYt!$vx7TxKCA9dy+yo}eT#2i5ye*$E z^`>rRK%StZcf-9mP2&^m{5h!iYKvwiJmBK{mnO5Sv{dhwT{!kQZmsX>Bj}yk$4n)5 zYRmNFqZ!122jQP)rO()vUt@P8p#}ReGNC)$O7*(zAkU;D`iG`g~QGX7=0iAji6Cmb62Uay+1?$a#xyhy4~)3cb`D+ z`vAN@>?>b9-2=o~f73ZQ{@c>+k|saSXm~HmjCiZYpu<(Q$mlwKo0>AUcqP@KN`Z%s zN#(Y&s1~LIFF^+{iG_nb)cNJfw~KkwJlvfR4|(OTxTQ+C;kpPLnjwk{w?R+6tdYZ= z-w4%YsYz3-J*9A}cw`^FWQePFm!*an1c*UWK&Ux)>6)@(bGSANeNf|Nw9v&BB{s`LaWa1KK5)>i+U5K%8<9I^gLLVQ>02=5m+v_ z{KJ~C5KsLI#NOSwaqH(f%p%uyIa0kYa-m1~*<>b>NKe!XXsNn-2vg zzmY=C7v^`(8O^ebJV&F?kB8TZ95(R<4hy!3S2hT-`WmwSP-dYaD|hZP+me=Ez3o?~ z?{RZ0$~$$ieE5@b-p+u2Fc;Xbh~seCmnx-Qvgn>4QM-_sq&yDxDDZfslmUj3QRam$ z?5|VgSY_|Y`owRzEY*Q{O5h+84~(V7Gj<;cZt3cmGvs>I=av?tJ~tH-XUlljrC z#Wp_B9u08~%AtKTWjD)rNL!=iwpGzd5EKN{k5V|L=%lA|y{v#}=Ho2gqjabK4+&OV z@m5hIw@fYFGjA&Vy_X{MqPqAgP?`iWHVPRgTXGHce3;XddpVULo63YZ)~SuLLE;?> zmZ&wDnS3)=!T`fF^U{nr#xK0gh()z=G?ihU%DLkTsVcL6_#f#n$9B7E6j+@JTv6$r zX{@hmixI#?g9@H62L!Ao9xa-<@tDhwBeS9`uV4q7c z%z8jLNz7?}JJcA!6TX}(W6^>uinbz1ybPDc-G&MjZ2MEXO*4&Tnb5sA^h&#){9NO} zzNQtcfZC)Xv;JZk`zIpalh#a6R!Sjeb1x&>nQr(>c9_c{1AQ0@0!{jd@+s~{s76im zq8G{eS=S_>Aiuz_Oebh;=C}Ek9G`ZVRxW*RHgzL^y96ARMts#T6AaXt^hBY$K}esj zKd(C)E@xJy#?r@;L&_+>+L9B6m><=%dh$Xm8?MO_lU5B2Ad7{iErU{3P-iXi?pbmv z9>|Lc^Cu;^a|NWweKXd-Cr2g!4A2ay9ROSNN$ey8SP{0aw>ZSt!Y*3w343ZZ%^;$N z{aEF37H&IC*9$0Dh&9RD5h=fYytXb*kA||)m^xS4xSQg|Cb$Y?XFb^| z9kwC>z~qxpZ|+^D=B=%5Kq8**Kr3HFgK;vftMbmX) zla?L*B{w?T1-ZFfEUvt7#(a`*?E1k0i3t!jMLOc=FwQ9)O*I1?5F(1e3POj$c582R z9kW!?$*od}d!hY4LID&an$8#>4^Q@K!dm*0y2Szirr>C0 zVZ+3iXh;wfM{p)Qia%=0=gBksLR=W`d%TJh9D*ZF6GV{`UONy;b*ob#B%DV^?+U_wBV;_wKI6=UF}q zC7h@8=Q+;1Z{O)Bezx&jPvhD3Bs+7T)K?Ok6X6xy11enBS$o~1ukKXRF|x!JT27{D8b3U(fBggnS@ zgfI=y2%p>wmknIHnOBUL{z+8yfSxst^tDLxRhM%nbQfI+wnmfNps{*vJo;8R)_zE> zOAj;$fPePDC1%NR^ohz%4>-rsU98b#jPmI>77*ebW_^*&=DP+Spu*8x@y~R~dnm@v zuF;r{{Vzx`DG(7nDNs(ap5rFg=yR~}4-t$9L6mWGpy3?R~!o#y|^ zj~Ugvl<_XXvowQOL|tGV_Em+10x(8C!$*}9pb|vdi8%X#fFWqvq=@wM;Z)GA9&A>u zcJe_cFnfZ)U21q4^Od*8u#zRBarLP>8;3^)?w!RUQ1MZXj zTG|Oh@GJEy208Y19--WeswbY;Ta_hb(nz68krf$?S*uoCv3qxp$H9;UThs`%Mx9rA z&Z&L{P3V4&Zt!_TW0IFFvQTEEk#CwvNvS|!sLH-}q9O0sL=9g}8>vmOQdmsD8H~o( zWB*N7ojXcNCw0fYRPV#G#4 zZt}*Lg_zO;+CfDvXsYN!%cyi5+j5^y0OPVsN!=RE)wg8}S`KZpcdWF_Qo7UmdG!Y3 z5XE+?!w<1}qh*O-P7GZaCZSpcWM1K7ZVd;oT*GHUUC{M}LrvV_JA4<@hU>k| z6D=EWD6SR$j=1_LfVeC#j-E=G;JLe?x%28nPu@S#ifi>l*(tfm$t7LcJvD>an9FV| z+-b{amP7X%(maojHOUlQAb1Ff45Mjy2{T7oq=q zL;a{g`5^Y)_!IS%uj+{gai8Ggq@upgUAN=>f1~vAs@wPV-Kq2!Au|OeT z#K4*Iv<;qZvmy*CT=$Np_AdWx{ojvp`8OigjLOQi&w-Ftvr`xTjpd`d6qoOG&LKtM zy{FiDjlFO^L$0o{Yx(>o02zMfc2>?E!@3JP%J-dypX_1?J&CE?9DX$3Ag*Q%Flb_; zy~jLuY$Ce>BbSr%YHrl(68>iGP^%xn-`VdEXPwhbffP8TO{QWcJ;I{~9wV4_@bl2! z+lZ_pGtZTLr`)!i*N3s3-Dx~WJSCsh!kV7~K#J*ac*GZ`^6*i|ocWsmEqEv)A2hjB z*5-7c_lnuEgh6h(%kHc?3c3CnAl{vVvYgdQb`#JrL=Q4VI1)CtvZbsCUlzuyWQ~s*#pS+YNk-rv<#e0(U zokxII%0Q1&43RqAjYonZ;`4S`vAJQj3y2g}EV%Pw;P&l*3p z>>XYE*LjEPV!V=PLbD!7z@QSEQ#8qbm{j%zF*wq!u(;YFPQ0%qRqgY4|$)dMzCp z^(|oZGg;WAe>08=I({_F)kD4p`8F_0@@^gl6A{J+6{0mB5pfg;8k9ea;QrxR{bs+$ z*}>Gztmr)o%g6?RiStW1DWn~Ul;SKXIvgj#dDz#+68^?HokG#|@cj7*-f^_ta*50p zaFhCeorHD0neb6O$489G-DCACK$!WPm?AyjWn-y947OoBitS@R^KS9}%DLt3S#fhV zjptWN4FQkW8xq^w>8M-$me$kLjr$8o|9SJ-Iv{cX_9OtoJ|mC9{~P)Z&s`@<6t20^AYyL0|Gd6rbE#S3av*f-}x2Z=&QtvZV%1< zvrh|mGu?CRjq6xOOGqW9^rB(*E(Z_rX^vIhq$KU`!*6Vf>a>u5L-h`Zn{*Prf0P=N{&LGgbV7X>N15P#qvx(s z1ZN8W+Hv@J(Q;aurN4N4F9}TSzKFdr{qqF^4l)RuCinI~1)0EZ&39n&kc)-uzlWLz ztJNE=sQyn{_pX7n&Qy>Ppnf&}M?676e!{7+KjZ^5-i1&YH8uuRqa7agsc`T;DrA$@ z-3NFjR51pfCcZx6-oDNm9RV*V{nNxhhMZ9`d)_bl^8lW2Ez6FY!}TXme1D47^7(s0 zdjPLHsQ}J^mz(~7Skm~fn^IK8w|Qw?G zobQ80Y~8;wPbrI$mXQaA%MOH3fU}}Q?sR}uYdf2Y?E=K`ynw#oY90?aL`RC#_eHP5 zdn$ffSi304;b`sf@XKT8ngXEDz`0dJstH{Th=gebX>K=nnThQ^b-$=9v?H%5bd1ob zDXKgHK>!AuIZ^DzT&w9Uno`9~-XOKJL8FFTU}wMV;s_1EE0NlPGJx~dk$-6+&YWr_ z({zo_#ntiB`j3JK0z=qGUAbbCs55Ld) z{KA&*kVnI~5T}2O_vJxn-5*aw-tO_99=wQdsW3P7c-y_BRr`do3hD5FIlFj@v6)PF z`P6y=d}?)J<Z28^quwZ|l&V|zK=>#cY36Ty?FPd`swsgxn z({v%2K5CwHp)j~f04t^RcGf8MmWjZxUZ>g?$lB*a;lNN+PyW|lis z^mBdBROq`e?a@-Pe$V>`Z4@;3iK+;r?dm&Wp1F}> z7>tRmRUiHGn?i*Sx)bIdEhPWdlCR#?wctSV%f8?hLW49sr$v|2;J2ZQ(~g!fuItZ; z0YYxHHge$vuLaFn(EpN8wij)B*G6JE7JZoNRHY=%pCWxZ+T}VAXZ271xF`$x{BQOz0}g6KA(G9;!|;6e+MbI?i6k>q z6?^=bivEBc--)$Nu%?Xb;kfEfDx{k#j#gAC9vETCElo)0AdUubhRfhTT>JIT-_V3- zNgW58T`iuBnU#Y^FI~D{#M19hesVC>H)=V`yU^v(`>NUhj@9YL*Cb3u`cD~tHCxg3 z)~&RJnnRF^;5$2*m;UPr>xNhJ6rW)vVOfp{EY!l$^7q`?ojP;}40 zc8f-ZWb9;xx~X)1Cy4c;tsI-HI~LaIK5?4OAsN`2NFb(qwy&rV(Z3Ph`cvl}5)3U* z?lIy`r@C|FM1gtA4IormL!>ADboRwo%lVzVyK;U$4|67Yf$D6OTVxk_+R z1mGa7X>(s+$`-)H#=n#Noe6-fUTfh_1>{GeEeJyfy-FX;4E=gO&*ldbDlrW_&Uov0yXBy(b;m>(GHE z`MT1P>Q*L;)_)z^S}~t5Ml3vtlo9#Z09cdU&}cVJ!c2%FM1P%`9s%bt&hSiO`d-t?s@;sp}maO%`w~cEDLMs9Pmh2 zsf|NNh5PtNpJScY>(^@o!G5r2^%N@i=~;FiS<1Ziy&{ih%fc=^&h~1JTqRkQy8vm1 zZtI(6)sp7gn`a8eRfv=ETdv=taY;E=#%$SI0Gh_2_BT6YC0lm`?@h~4^iYEVI!NZl zD!v*Jak$DKXSAVwtBKcQ7`b_}v49R)iwS9q>~a>F$uShp3DB`d#9^WiT;V;-JxN|e zlYW;f!VqU0F(ePhGn47CZEsbt;pUE7^}W!zHFPKnaJN*V!F6(Qcv6%XI%Y?Esk`f*?!k>7I{1n%^?)nZEZg|$ zzf*Hj7QR_pM5D5N!`MTDvkQYBV|GKgMWf%ILcr`JytRoo|4$7wfO&a94NLnd!9{uIU{6*{X zTpfS&Lup0NXetv@4jk= zj}q?hs~R5^1Y~E2{xKzR59oDB@os_8{d<-URc+frIgT$sJzwxibmJ5s#pRxqE&1N> zP^CfSPmi)t#)tBc^h7J#n~&lRiEv2Y-6g4ILbe%jr?zQN;q1a=@{9nX$8^fzlE@x$ zaeUmta!+R9M=!VMLA$&JJD-L`*5(eUKGZh{R0=OT@n+t-{?djokfOFo3{%2k-s*Mh z;RgJE;4tXaQ-;HBnwIMqj?a+xOM;^OzWQKgHnz`jY~p#7BO_ihh&=*mS&oz4cIR9s zf;b8W_=lAELcgsS2(tiHlMC8M;6dVw;J@l&QnJeUBsJStLDz@Z5bij_2BMT&2C=6b z`MV>XGij6UM?dq`RdTJnYTs2OhXhr<(z0bCxwTgRSm$-R$Sb1iUyPl?b9h>PQ=ey@pd@GrGdc!*{)A|)Hwx|_96tIg zHF*_wwaPo93~uwexn=S$7XGrt9Yf22TmsVdGoSk;PN=UuOC;6 zpspCV>A$ES+11J6$9kb3T0K74hG9}2lB%&xC0GVFmY9_?u`pQ}PP9=2%-m%SbgyPO z=_@m;TKVwcryBv_0F_vGO6rDeJNf{mn_O3f(rxp6hXN>t(R;qEL?W*<%U84p#R)-* z>}jt%Cn#@Ddz;&5N91ku=R)bkP5*9@@$Scu4sh5~oCiT`x(P!QO}u=MhN-dk__PzB zp|pEl--8M87fY)lLBuFtVv%mt+{mZvTmFh_A5J!xZY_XV-ST|tOP(OVmig7b+Y~A8 z537q$xGA%|{RP>2)M=qfb%sF)y%wVKj7zV^xl2lqlRkK7H0(rq*#mzbYB8ArwQ^mB zhWSv>17WJWIUrx)l$Ua|RD5-x{}qwjSZXmFM{b=~;-k5NHVs=jK?U}7OzD|=5ztZ0 zjGyJDM$gIOC%gXi0`{XCj9hLdKsym1H|YJCzD( za_o*f?#@-MG=1_(aYy;7)oIYWdR@xA|Ou!Q^b_-%>3!$^kN=|o`F10 zjZ7qf3d;1t;}z)$(k?H-S5TPg1s95M!r(lj=xMi@;v}+AiIJA8-HkWf;d9MG!K~vDrEf}}^Ux3czIr>p$O9`Y7e@uRCv7>aL_Y%qp96(Nr>I8Y@iN$9 z=Vv*{!z``BpQLk(*Zhq@xn#>Q905&Rx;(#NZtXlRxryUE8K-!?`q5TV^co zh0Q)dh?y80t30>XBrNDC&Tb@8T&GyeagF##wEZk@;U)(bM=P?EWDNlkViUT@niw-y z^sD1`EYfY2E509)k#;gYs?*Bb@0-PrJZ_{eKXi_Im$D)j z!SIgIKpH3xBmux;2zL{rk%-9WUu1qi0p7j{-G8q#s5m7_?4WjPG$AFOu7k#l(2Gy^dK;vA~eMT3>LXl2%pt4pt#bP=Ar!oMvYof zO+5zV!R^^eaJB=W1#K}77I}5%Of`cfgI=LQ=F=bCCA`B_!|no0DgIEXq(Q*<5QF5` z57TS2BrWT3Qu3_tW#?dHikc@asHwd0DjU3SJr6b$(Pl`A?KElEJCmj6J)h{=nH7(n z{uHo)gWM=< ziM>g6Z1{Pr7*vNsZ_4B^cf%ZcxVkSnrzo+G;~=DmH^8lu}tqct|^?x&!4Hn|m%B%&&T!C-!v-Cz`*{ z9|DQcY$Hf<)8Y}pixAjIIJme;*jTtpICzqFsHxK8jX-JAa+$zz(rOUFSrCBVvjf*T zf%`at>)+C@>Y)(Qz9E6r{hwX)h+HJhB&sA#k}M=F%*;tQ0z7HR?Vu>(yGY=`4@Ao@ z5@fw6fQ_B?zvGt|^>yO+n^6PujPj2_mToD5DKQ@(kN0fjz=j=rJU?v-qO;H4E5s*CanI8Pu%3CWzwMO-lBi| z3a3!F?bhx4*XQjA8c_h?$AzrH&VZE;v29( z=RO-haI>%;pA^sK-T+xlQT#?rDIH%nFVD;4NAY4+tP-b|uukOwHPrGmkx~lplIF0r zcgs;PL~|Luk>pD&8FbeAzXG4~B+Dr`MHSEXU$R)I9eGwi;VeRLx(YL^2dwLaJ4E07 z8dPOy_Tagu^Q}0fSPg+7B zL^|L6x>?J9qn!!^j?67tjbKYNv#8c0-7by(zW0=FskG~wqkM~QAvo!^6Ec!)0}D8F zFO*l#prb|URPL?J#Fe~*RzD2a4_(ygTQF-X28*fGca*#-2l37WO|BiQ6-~U%DUwQf>*< z3a%HPu3ehy&%gHDN*Wr99oNKz) zqdAzEv694D^j*Or6ZLdClu&5R|BWy>*HBi=?wRTB1CShs^tV^qQs(pf)jM!hDMIfc zYrh}JLFU*H2et&s8%khdyDAi#y-)0ed_^R{COpd^3(noF=V5E2yYB6MZHTF9L4Zi1 zIhw&i3y>=Op3x7pCpx^>*VbHa(U9cE!B0LqWP5RAagfba@jX9=Hs>2&INpx?w{yZB znsQoZZh#ryxjW3-EXIXKG@k4Li?+buo?6Ys8C98>uME#i0fU%&S}jM_j^jn<5w{|P z)fm2Pq^5A8ego*ZAFB!PcID0v@e42+IgtGC8Zs>X|(Pqrlnkw{Tw+FG|iJ`4tj3oE1T4PO+fmrt0@7+n?muxq%CbEPv zxdG_mOQKxiI0xvq$+VjnHRuqW7ySEp_|i$g^}a^LD)w*9?%KS;=qHU}Oh94MhqMZU zW@!mF=&1EY7i#I&_lO{sak@-^WRK*g%HdKGMnymvh?g-F^OG zv`SUkj^ld9U#FNyA2WAD*_(J@xO2b)gkKVuLdm)ZCdW4p4wx=H!5hU72XAVe1WAnvxjV3F+U1rR!&q+~Vrld8FXQ zPj9iLk|kYb)BWw%F6-d2D2wne@mXkEXKMm-YnW}9px~jF4(Y<4$+@mH%IO@wdypt38OnyCN zG0@=jF{61uZl9K^dH1$`;exdSCGnnvpjlYsj0o@JV|I{O++FZ^h2V3{X+u(F< zqTQngQ%Uw2D1{RF0w^WXA1FljQl|RWl#a1RZj-U0eAA910kA8yLRvG~&pXfgMPCF%rA2gl>r_mIHAF-o(q%>~Qq9>e)gI_PlF&g|TkV*7s zlJdbB;>ENKL*ROps{%TmzDjf8p5*cHue5lTOfk0pQfDB}@mf==8EU33{MDs1s&V9H>VyFA%Q_}F9HOP zLhWouI!Jh}R^wDX2RZY`yX}5ymRC1crnzid>tb&HnaP7&2@kO9mJBGzYOsN}dUBl{ zquP(E_p2&-_+Ute01$c^&2h?MWn9Fw1u)ez^+0E9trCW!TQlbUDdW&-Ew1ab1+XFC<9AoNb}-xKU$Sf( z4|wf^>}0kI$?$}j&mrL>%202X|G*!dSdu=KSSNeO>t9p=STS}LeO5qf5c4=E8@3{phcB6 zD5rzS<2aC5Dw7#<`W`6n_XWqzQ^M4zs&NTl!o=VIBfwZi4dQbEOk-EnGU&(1#2V;3 zPJU(#EaGpAKzpSiU$~IAmX{OJSCGk!Zs=eHy@xwtAWx)aejHB>PTdWQ5i5?Y5jQ2e zBM<_=ZGabL1V=JCmnr#cm4*karbBudl&lu%;`k5!b(JGBsLZa4xYT1by3jB4tnOr? zz>I}$*8mnpCvmaIXtghYu!y_C@_}M=Ft>J767p3AKVv!=aq+n!H+vxu zCI>JsL4f*OO;i?vq7$zerJ%!*SZW{*JbK+%VGEZr?L3E{U7`C#Di< z+VX|*NUS}qcFL$H6p?Tpr8k8fnYF9dbPyI5$1fF10JhIn-Zzu~JOrVrH6J3xI~tr| zHyuM|IPt1rd5r$+>GINxCASuyHq-$$+INBge{ld2WbxmJCuU_ZWH2=MM-}ug<$47p zSs@a(dBF7EWj4_(UQSkFH|>UxvfuDqXG=^_p8?;z&5SLrCf zrOhSJ?|E;9FY;}d_s2gv*2EPOQ^46vtHVBRy~Gp`sIs|72~ugely}7m-a_$!VdfHY z=ocE>Zu#4!Ajgdyc;aJ5UY2Ed2drN$f1G(VPx>nKnoWpIjLAYOXv$9V_OqmSl6JL? z_)-rJNI=a ziL`ShOXx~dM|PRloILS(40-1OJtA6~=$h85HKN}iCW!8w-5>>!f8;3RY_WJ;5Jomo zt$x-xr9QtxGbn9&hi6kqu+?kFl15=k)y}H?aT?ALAPOdw$>uvC(I`~$2xw)^?b$odPqMm`9`tYoGPA4q269kgFc=Psjop8PdU zHx=^#4|)FH0;!fJm({N`UvsjewULUqq^?$gKQR$w>821EKIVUs$dXOTaAm zH>%9R3C*9k>^H>G*q3I+f&w2mDH}KftzX|9^8x}22B}@%?q5dB*O4zRWVZxA_8zHr z1w|s5FIy->^q#)Knix`M#}xUpmb68^^a*?%t(O9XR1}a4Lp47yc0&6?@QH;CRKs!S zPQ|>QxG}?T0rvxVPiJyfkxwx3Hh>#E0J*Es^sMS2@&%k!y?yzY?p)ejzkp;6#(|@_ zG=aF9mh~bcmScLbtSs*I?S1(laN2&^1JZ0JIM*+>=d)U>f$%!hll5gxEKnDDlf> z2A`+}-}X74Kk~%g`jk{zEmX)^!f{_JLtM7+{!YAd0-+R|(OIm3)z>B%nwVLLLY-HD=PJSLvwA_Mt zZ)1oQqG!=F!7HT7KG`IWrvo0RMGSB9*}o^2zUK#|4CzPqM>ZB4)zLB}E%G(n)yW01 z8*D2AAs}lmJDog5bBZ*EmV{I8I%L~@5we|RwSUJ13ZoR(4(|y)r)?@6XzVI6wU4+S z>vfHhxyKtlI}qyCi=#ctA@zI_+-pRLQ&~kUW|bIEyDn$fUq8lq{Q+Hdy^D_t3C$9| zzXkTM*%40s@WT+#T-MX)g8YS2^K+cO$=H5{Oy8NE?7luKQLFG+TI+CV!j7D=ZqeQ? zwP8VM2vusLHX1!Df8?NZl)u=v(5Ame)zKYpM^ZESAh)!;=Y?l01C^L;n}=Ef{cde}i%6oUaOdO*Jb)902Y zbv(>ECuDNIu!g*=%RXXBCgLQ?0+oOYSkZ`P*6>N;!7X&hYR{(nANK+xPUc09Re^O9 z)DqbmR@}u^(rS?zk(H6eF>`gR@K#Qx`0m7e%0gbg0nGW*;Dl_u3lI(Y6#BR5x3{c4 zTVGdm|B)UkIPYfgMrPWP%5Gy8FCN5A=)e8q-P zn-Z2O#Ycxf&pDz^SM-1?;l^xKm5Gn@*z&4yb5>kd&(SK90rye35cXoc06*eS_E6nm zS6B?nX95gGc(Rz0!j*JY*uaFE?yX1&wnnkOA=F6XK9%k1K$$~Xq@;OO&0q)o8XLT> zXLfn}e(59rb-@K06kaJsxWu2X5et`~qd#sD%_g7-cBs6Eky@Ya^MNVD4y6>YZrsyI-a_njVhbBGyBwRxu zLq61A!L;xs@<-H3u#Eebd;!<|!IQ6$8kM59@(8>VMq={I=mgrXH?J4~j9qAVGcHs}oS*Bip4QP}4oZxZL@Ji93Duqz9p^=~@f=B~-ew#(nGs;ytxS_hH`ZOmL6k<>n z81xeX7dO}&8QFYv3Z^x6Kh1f~f=nqEU`XP8lrS7*sPyBdL&$F7-`eN!bCD4eD9u{u+$Q`z4`9{|mU#fp!F%of;Eu_!N z50+wnHXhA3+CfDbmY4=8>cMU}Ig&{Tqt-72I-jLecq-`{=0$VWHknN*s+vvk&K2*G zwQ(2p6Y90oCg#GO88w`Q{?@Ww8Hd^EGGXoz(~kc*Lhd3X?&J9D-4)d!)@Enu0j>Eq zpI&iXou$U0laiubjoeqsX@RXcclF*DsZ;xX*t$5f%GuyM?5NurIx@Yb%Gg=hh}Ppd zK&2*>{+Fk#ZWFXAnFiCaW)}%bnFo#pVTvpxElOI8@lN!~vCr|iJ*baa2sllgn=a=Q zIHKFpDEQmjQp*T~BYU=!US3r%`pTup+F7fU8g4x-DhJvsb2y`n89wvUlk8+mn4+iZ zMFpOa;J%*|5piv2FzDND^F{1iGsJWuKoF+63iLs`ab}yZV8^tgP`{_ACiZza7r4xW#`!SJr5xNd6y3Wx0a*rRNi zQ%~thQK=<6KU0~5GsdQJ*B_cc7D}hnsAy%XDpvYiU3bMT-&V^+ZXMr-@nOL%04?d0 zdTqow%LKba!wBo8v_}0V@~owxomCNldru9nON|U!CZ2tWTH|aSnqq{qE`fH~9;=n2l z&gx5~h>5mFhIAO<*GY2(0i_HffOKlbB;xQDPHl^(yj*sv<42FEIZ-5SgP5L}#Q`Y4 zpb2tS@h-M0d-qCCTVHo;XO<6^*^k0lksHFfH;X6=1{p!|x+QhPT&-)HBJ~J?>Z51@ zgWJ(HxmG|XvC_RQ(qL5?koA+lSR=G&uJI+GaRt~B?qZGym7v`I}gVC?b&rK=KJ zCu1pXO6}e=zA(Q#Q%o$WQ)!sy#iz-F-G5ttJ}H=5Mq#qN%{q0eunfbe$h5Ared3B9 zV)1b41FOe~WPHxl(g0R0G&CT(K?=o@N&aB+h+=kLL^D2BJ9kp_2&Z&@dYm+7CEe5i z(E$&WH#)L!uW5^a#(^Ul;G#f2-z|Aa%T9*fQ7>f zV_=l$C9>5h$W=E1ZpxX{Ow`%F;HswDs4yUg7&D1DG0dujj~BDN!f2_ZtB&B3;o~NA z=?$OSk-vk>$vLfofA-|6t+~u*uW762d46GcTMur+Ic*tzGyi7`a6?exPc=9JH8u~| z!oOMOLhO!#(RC&L`vBy1^5^~vj{AC~q0!m9s9P#AzWO&8KVet@%o0c2>!!FCLj-`a zzgc&H?+ZWHS~GEcqhR)$er<8F4m@pXOmmHoG-^PAuCmYGg2s1Z)tr9CLgmb$nFF^T zZ_Mbm(R3`5J&lzzfV2}od=}8+M&9g+NP6L`6K#2+nZBCqM36icF#g`?sm3-bccX>x z9|qc3K`ZRE?a_iU5l-<6>}H^4M0-H02cl(A7E2??kqdx*0WccHS~_zqx>or`R8003 zG8Rnu1@377Wker=Td7D(l+Hp8*?TL1V()2_L;yL2d$Nk9Vs78eBz-YAJV*kc#P5UlY1$TIf}jD#H~)fmhiDzL7BN2T}FBCHOAu zKrJd!pnrg6`XB!wm&D%uf7AdvA06@fR3e>LM-#AXTSVfnuOKU`AA5G4tenXSit9PF z=uC0?*+xtyc04O5P;%KpA*~;4v+W&Maic#DkNKLrj)9Yb>sDV&sbF2Xgy#QuUj;pSMNW^pjQB9b$b; zTL|DdKp;Y_m$b82R8B?;D*VsJ(V72PL#p>7R7tFl%}FG%2bIE07A|HB@xT6StqC_b zsgrQ6pv~iBlcv}AGK$jmuFFu@i-q2*b;fY&X-F%ma9Jy2&OMuukA{egr*mWU&xViI zz9YlEjW|2+Yl(${2$S}tBE-@_Xd7JtAW43jXf{7_AlnGVsX zHh>jphsLv~*mr00lQ~ORv$zEtZrGuu@b~D|c=-p;x0PN_}a4!McH8W#p2$r@6bd6!%w})Y$ntGo*0O zh@2-3bCe<0sCIO{Du(Mpru~9HZe(8Rp$B*(QA?Z~3ssm&EoB;IK1PJK0 zO)WfHel4k9(u$R!vn|WlK;-gs!bn@&&tq${eru6dxUkTU1KT`*6Q(ckq6*VbtiHSCK& z{AND)odA@{z~o*(Y(b^wOw5(!Idek-Qy_;3BI5{UqZCQG_siDa@Sj<+hGkbmPeR^-sh=PBROxYEJa8mG$tv zJTKR%O+i1u+rvjjjKi0Uejz7-rF_}-^daC+oU(;ioDhdu-=P&|uKW87fm_Yakz9gz zz_7Vjz!dL8<`)GZC+_OYlIt8CqS94_?Sj7MTqr-jqgQyW z5UNHQG6()Y|*(J z63ST7)5*v-e)|cnyb4H+=)FV0rXT&L*`VLF0^zDzml}-FKivLsklMLHI12UcTL@g) z_;0npnYw&dSst?7fP&Wvc_BY;jscv~YaF#o{tSV5<+!`Gps@%H84Y2(Jc24yt!4(H zBQ1K={1!5RnnxUv)a+S`klU1q(6;y@Ou0p7GkoW5El5fC8^Q1){{pQEUb5?W+8mw* z(l2=r<|+8Z4W6t+@RA}chpk?PCnDW4o*{9M! z;TADbD(?ugg^lzD7-#>r@84hVhwIlM1$)-Gl6i0dGE6P9`;n?C>z!DVVai?jpviX& zF~`62h>hPr{-Ee@idSfnPTAFPu$MQ z|8eCn=Vzt#W~2>tXzuOlQANWhzidn`( zs=_5)5emmq6zkilhdhtX~8!)3!1mR+|`AA~Ng2 zB=W$K!`c#AteNyrEPR6;#ROp9Gnh#Sf|jMNNdHmbKZkRVzl0UbVF8APz=p=tPrT31 z$ARLGQ0%O3e}vir|9AQiU2@c+H|jyR54NJ$*|H)J-RH z#Y1|UOc~`+lQn*qUj+y;J!p76SsGEa40nfhtN9}m-B;;}Uo(}Q=cT>krG`s&KN3go zu9f?S8L({K_EM^3{>^&S=SsC7MJ6uEz2kfAW`LXXP4R3|6GY|GZJ(@QbXeINY)wjI8Q1b6C_2Td%K^eSX6z4MQG3Vx6N>U1O;r%Rolcq_80sBUQb>T2>r40iSX3xn zz;M~tm@~fjNen<_O!{R6@(ZoH#?TVRym0-~n*k)!*B1a1Cded942cx^p+4kfanqkG zINWuJL=q_hie#+kjBb7mLBoQU3YG}l3cc@&ehumzs?Fvc>q5sVnRW3~E9Mum7)atT)vocpkfEsqtu>IyFD^p;UkOpUO568~G$w^WPGh~As`W|p_M zHj6dZJWjv_O$-qIL>@4F7I_N-ubR}w7TrAKb-8JW4(Z%8{|om6l%4u7SNOI zD7JLqrZ-N0%;}A=k*QDn!<=_mT#-A1u8T>3y_5K;jakWN`{vT6VqtiTDonl`{3m62 zRDvE)iH#Dx02FK0(#7cYhL7I0853JeWE^A?x&&aPdyxIYCO-{jagmot&%($_&tf#! zpDIsCl5V)A3;`vN4jcv^VFoxOB?STHiCBwGn9g+yWOWbkzQhb<2NfJ)SM-VvoL$ZY zE&ne!=C58x=0M&@L8%rSgakq`(k2(#`P?OMeVku+&k6{_z8Qt<>`)_$fg}!_CSucP z{0sp4nTK;nVg>~mi!7AKJ7R{84~C^l=&+YjM-I5~&hYvYIzypKTRYAjSpR zKQF0pr7rzYZtV;ram|}!+GI=^owg~3Y3+_a^J0J8uXfx3=Z2tW;pzoHM`8>{$RVSU z1Oop9A1msFnM;Lgug$F3eqvkEjdq+O!-Xf~z{=%79*Rya2@H;+8o(eMzkJe30Wbhu zC34f1m2O5ID8URc;W~UQMOV2U4AB`3)_JNP^p9d(?bq`SsN+}nbLp4w2GyXS9m74M zzdDAI<6$pJpUj2_Zj4fs*gktOM33BD=q{zXGmP&A z9sV?-l|LMs2kZAah;L6_%((4sq9+AR^zSjy54qt=O6cMXfB37^!@+i>zjisd*Xa!+qP|UV%yflHg9a(wrwX9+qOM%CduUG z_uIEyyIb|%AGhjMoqM}a^{vz0-~LEOaB05>;4BE-HZUX}C2pguN$Rrtb9rX`I_+x` zP!Nh^RWbi{zg*lLUI3B#k&yhDjMJq#G-@-*Y~2YYE%zlo|8#tgu!a`ni3Bc%q$s#)_UbgU?W%!IsjH~~u_qu*#3tWtlwccu z>v17NJS8GdnQ^tj?s-mUw;1LX?5ASaHH*LcrF`ZQwzNDMB8L5ENI#>t#A;=C`WFwf z%@mLI#ph`CKPF66x7D#o(_*Ip>zzW_<7<~-dbu>ac=42hG-(sdqDUrFHm=|$yo&GD z9?w3^MDIJn`ln(HPqw?dL@Up~mlLV`KRs0C>Ty()iFt#DfVjo1>for|?}+u7xzBzo zUjN&JvFqG){>C|!j`(Y!Rp4?t3EVn%wjcZnSVa%Z-=9;+0>uE@Z><4bWe&n|&azUq ze4n>7;+^Dz|R%0K>25X zy{JlP^`J-=Q+Hgx=rry2zv_y}`#wpv8m7j|WI}@}r&+46^N71w*J&(WEbgOS-I3l9N#92a^DRsIaZ9UoO<*)yj&b@yN*!LB`3HSQb6=! zgtIkjN)1iKQpW!?$%L|9N{J-8d(t2pE&$C6wUz=7p~5K3T}Co7&L~1!8U~ZX^P}}tB@EVFal(}nV2t`^daDOpX6eR*B^@sw{eUH2;5}v+1M2&1991RHlD>F9K zasn{QigEmS{t(biw|k$U2tZ&3UGxTq4THNK7p-@6z#YGU3~#tZ2u;~yq&Ei5qRhlX zBMlZ>RYM3uLB*Ji&b2ds(D5>^kMlywc#IPXfrM17>&I~XFKIYwcU^xl$@XL{fdPBM z`J>xti-y<;U_Q|GC7|(h2~T>I5CR+&M7>g;FvSX)v6(c@?L_tS#HLpao)Dy^Y1oU;jr9$L6C=%qJGJISlt+iB3B{WWK2O zFJN&)FV+7@Qc62%1(*Hr%;fI?rEhTC7r@E>KdVwbtvI|6_;2R%{4B6;)jLoi&|!ml z9xB!t;#h-lJbZoD7osR+Mb+?yy4?EucrD~1b%Sd>+S56a%=C9v>a({mc=_v^QBdIX z5sf-DO7!*3UIFlT`+7H^Q!D5Gq>nIof#>+N?e(GT*8Xk(ln{{H`<}b)_o`4X4nsRV z?dW_co29wBt8$$19qSyzHcJ(fM55GV)WQ}Oa~w984hJqGJ|q&u(@NL`JUlX)i&vfu#|TjemJL z7t0BPq!zG+YtB?D;OF`0CS`l@?gM45q9|>h$9+*WnVv(I7zc>`(E9~br@t!`SM*pykzWLJ5r z7WW(h%%AZVXaE?1BwOrq(j!zu_X^n$+LVkRw*0Q$%eGBKci5dTY}KmOX|eb z)}pT|L^rU-+~3|@!a^**InF{L1IYeMEB(lb+&Ex3iD@)I zcjYufKR2T}l5NO0^2TRLN(}-|9I9)LlJ?yJ$*9PbRS*qSQLxm_!Rd9ry~@;3vLWM1 z{h}}#dl11(HOC?_;8AZIr?erWsu#hk1o04Zgi2#e1&TF_G}g5y1&l(>{Z{V) zKP&@E$eD%7QanT(KEaZfV#-(LW#Lqz^>QeyhKbwg;3Q~ekHF$defKzOxe@2$9@hlm z@Y+1-qu~aVe*`js#Sb2jkhLu=E2Lzm1^!$bp+od$QG;#w1Xg_M70R{J*wjePKZRC- zh{3i~En<~N^Uyy|n=85(1@5F!4kL^JP^7xbV8N_cb^36eM|BHH<-xQ{UFUcP2@kh& z8DIxZRQVz0;tWR8(Z5n03c4z8ywBKV1;D0zb>B}`vb!BFNN#HzWp5g_+plOQ-0AT-QkwzY&c8i4o{(I6S54mw?#fcO3nr+_ODI!N;s({v zcQsL;+hA*kWr>M}px-{X4A_?Kt>Z7pA$CZsE>t~=XPT71kxKm71Yfoe)NDRXp$_K|b&Xjjt zLN^5C-rRdt3~vX&5L`0@@B~G_i2&pD9TOqp-swD5aV7l@+cM1XHm#d3~?xw6bS zmi(Tgis8*DZB1)Yzo)1KNk>*HrbLPj97!_T5QrNwYCGW0D0gOoB4;HJf^A!7318_v zgENif>`TW=PwRXUmD3qlim6iJ10n@g7FMqpu#+t)(R#hfNadzd01#?#x zDtm~l!YqOtDt)_M<{3mvPo$DlbWv;+R3r(NkU0XAs3}ob8);+VBx*?Cil6tnl?U|} zWdsXU3YU}7ku`!3^F5vauqFC|ej`tUMy)4KxJ;y)%0SsD%dFtrsm#NfaI=cD%jwe7DjkM)HFi*;)#{C6XOQ5{W zD{<+jlG1J+a4ppWXZ`~-JKI&R?Pj6~%HQqio9jnO1JqFcTo3aYYyA*jlu6g}u}o?3E7cBkyyg;s95&UBrf*-Xc7d49UDIz(FEfFe3$_$$Yvv^H@8PWQf_uVBc< zw#Sm9T1}Ev;=EEY>>~ZiCN_=Qcv|U&Ka&vx^KYmZ(8kn)O4`WjXjclXYUn@8BAule9WB43k5t_ z@$S=FgREtkrbvZCRDW(8gX+U%r@o%9Z&dlfthGwoHD#WPO4{fGc{*wwa9$Yv`#nNa z>`MJC;G1CFHKme2qhwn&nL6^Yo88^V?MW%W2pNFJIMz!q4<(*m0RuRd|iYgN0ZLHz7BJGvNv#9z7;a=+~QT&~3bJP=E{1^X5 zb^CiM$JYAkRa?WKaNYyMn_1ml(dsr_`&f+**yCL&-Pk~;_Jcr&SP(V%_wCct=3ZU- z=k4=*&ZVHWt*l8{OUrFZe3SqFnK;R~!mVXoaYQe~cYxklV`lVvg}%v5&i`n2Pe*R# zO0|wmFbHPZZb`mbx{(Ef77C!!>5I)%HpgCW;|tp9y^_|4fDZu5a#um_BC;u1>2MCB zRwoO4$y1_|)%N+~{&|g(CY_ff9`iWtbsKpHJ`~$RVpbGESX5tQ%mf|kpAmMHGLc|> zHlhY7I2Z-F9DxJDuuTC-uKyu$dGRSpo`BQUM_y;*EDCEbz0Mg(+V5|vPf!Nu=&n9#=y}=a>W~V@5e*R_-M|#!- zHCyUJAQ9q_{ZVFeLhM;Wf<#hDG9wH|U2oTkCp^%C1Uy*cbN!H_Od=Y;trwWO(xv;r zixV!Q!8#B3l0CRz8$u`2?H#JCf#9yj|Bx1fToEDBg8*<(?vA#fhj%Z?+TS5(ND)AM z(f@N^F?Ur1%o>Vc?_w!(zY|9cHB4o6psB*ttfb`+S`I23=xF%QBMbsz;Do$YQtb>6 zCI>9-aLi9t;qi$x$H2(u7GtHE5Gdy+UTJ!EGB?4|l*39&f#)yq=~dACr%e!JV{$W> zV0bCV1IEnNZ@{EzQ&w%P%oswK2eX zHVwP>*59Q3Vu)>mFJ*q}$0TiMicMZ1{=@~Y6V~%_>|t<`eZU_X2Nh>*1kmOcef{H7a|ZOR_Gs_OzY?I0l&{1J zbxOrvI*-HjmENl=6Mh$R=?p8VZMBUf0&E;lMHw@0G(>Hk)~>3`?l$)hOXrJ}i?>XU zcs?58*56IqJ7GVV7P2U$o=jCRJB45(ZLM){a&-ua=Mm~7H4eE2SG~N#?n$~ z1KMb->K>|ofDfo!}AZBck^!){Mzc`-9vW8gMf;Nfwc~1xUgV6TOSRJ-`BZp zGol+o-tm{c{7PHD6J3B9^*d{amx_(1%hGaW+V zXH>?nnj4OlG*U=ZFi(loF70(^zyqKiU9(qM3-Rz^sa*MeL3x;pw&_ zZn)W=_&YnuJiI81770GtRO0gJ*v>1&o)u$*2v-bVSO;k~_>s8$;9}~(bhK1pLSzgO zmiP>4N@NX0<{h}Z#&rj@?BDSb&3@1ALS)8tXOBLuG)*j$nrr?ss|r_!1Ta^TL5 zcHi*uzEfR)fn&;4&qJqKj(kI>Nb&zY-uGYXwcO}8bjrrW%JIL7)b&{MHhACLf6U2C zt9^k3f!a0~{p6X11c;)7`VkCIzXB`@R!}ZeE0-5dxCo-lh7(oE#0YGY8G4XkPElRI z7E`zXK0honD&!VY!3GW1o|Q^$|DEoeqzjdoxAT$L_u&wQ2Ny@yzIoJ%>0rTP$8}pfsMfO0ex!>`rvEdGjv~vj%8y8YowD^-ds$rcQ z$iDIt7%d<=+NSG^;u9B^w(IkpB&z`&OKJ+k?bOZrI0`rxRip*grW<+Nc?P+~4xQ!% zdVYS!fp#d$g2Is~4a|9u*jb_zFLe@%;Qfyu$LC!d8jxMSj&SHe0J1hlLEg{xO-f2A z<~Bw^-)90+Db)VdXG<{D3nS~zdPQ_csM*4&Zw%Yl_qOOE>Rm$|r|ItM-U-F>=t-fC z@yqYe$8kF1K2XDc(4ERL%2%}B{_e5a?47(wN7t!mEy2lz1LM~ub#6%k{jAuE1#a@W zA@B}|vGx0D-U6!%;0F7CY1TADjmsMrPZ|bKnzF$Gh3B1gLFQB0;zwR$Cd}f>y390` zTw&+dlt)w?ONl5FhnY1Btk^1kmaxt0-CzVm_gG!7o3yF;FVF;VY7*8#C)z>hWMmfh z2v-o+8r}ed!v1^RE}k+$3>Fa00q%Gv0myjLt-%Nx0L}}e@y`^xjXFT-0p3D6 zq|?v1==|Iq_Cj{DkXWg)EpnBU5_ua*Cu7EDOnnj3risSc0XFo?8dT?l;*f(*skwCd zz_JftuNsQ}vM7pdj9^f|^OpQVj^M~yg4dw9KD6BzoCo}EsdAGAfjMP2ODrHVcLiy~ z7RTZ(U$2T-01BLGF5@5&4J(%?{{c0~s3{7QsV$0(m|Xc>I1L?MK#-Rtpvvygr|h)qMeBu3G_;m*jJ<@Q zizG(^)_5oXF|m!e=A=Si$n+8A-6V+!5(h zfms_>;FACL;@ zdN~_WfC?uz#v6Fa7;Gs?lWCGTlgT6}SCswPiEKQU*2FNi=n9a^#D%g^x<+tXw2iKI z5e&er5t)@sk}TSJC0V@cSv~rwUgh@oSTqvvb@k%ftIdH z`^0)vw7KyL5x=2Dx}XFz#E9!0kj|>0eJ<)+T2@AHxys{?4pHeEE3OL% zd^!y88QQc<(8B#93zX9Q`%Wg(c!B>c|2pl0h&K?oHlZn%ShZdB^NuBdKOEs~NOf0~WAW9j$fOwYM`*XHanA@9pOdcF2B*7VqOjOrGVy;2~G=;g;hYx|T6Mb0kjt;K(d(nG!@EG#kgaGzTZhOewLcvfztxy=9$15x`rEEXAX07%@} zNaJ>ltwqe7Y!EopApvLiR}pgO^BUz7Y`N|v0cX}*$jpA3+iOBj7lrKOW@rD-i?W#w zt!|=uO`9>-7752fxK>q^ttH>AMIXowMIC>JU~>%w#!vSu2!` z4{sdNeR`1YV7K%f4qc~%pI+pU#xYLAzB|O{@U2F?WmLkQYO!B|AS;CM$-Qq@M9r?3 zN5$X>!jkl^UFJ?2RsPe{Kvj~IpUy*8Xd|HDsZCYlydXa@%B zwj<38$gV80A8WVTs0JpGhg7gMkaDX2j3#*s6(nQbsqY>lWO0{j^c&iB6*T3(OXeBv zPfAhTqZr3tl(HM!Az!T|K2S8mZX(Vt`*X@P>S`ZW3B(tGe-q6nrMy8!VrqvXlLCaK zO1&?K6buW0hZ4fjpLA@MP4v%=5C~DPt$RQiEWi7L%~BZpN?PM4(SqM}j}yh(B6O52 z9*5oM3~1CF=*8A7=`5*?jG=KWjK>d}!`OPA5LR0lCkAkQqtzh!T2x^CctMlsb*nMp z3}X8%?MmSOtSS0P&hCq-iNqa~t@+W7a77f?1fvlf_6z?duj{qT-@Y&>lV^sVj%#vl6<+ug{A&m1VN|f1k!12jnsFVB3Jd=gO^=U839eo zy~1>KOq%~_CQmK@=q3m@S=G?pp(yAmJ|#wYwYI;EOm zh&;n&hoeOu6uFHCzS}*Ri+@F4h<;8kkP`_jQ3_Y!d)QPNfm}mor5N{A2_~_HAdX}$ zz(9mp#!sAAW@V1SOs$STazcZx@AId3xXH5nEb}r>eNPVK?_jnFMa>U|vm`~wD#vmkh&jl86)o^ecJ<72ogRib;X$g&D6T884Wa7p7znrcEwQ$=M698kvE zi(O9j1M9vwgO$C%S*dlr8Z(zCxY%Gmop5%N3yKj3Fh|&kc!p3|tB=nkX<@!l9L@%W zXluv^%8A;`YDzN;qbYuPm8Z~gt5x!#lRt~xu2CRvUuhM!o6C-Vo}hyZ5Uyt)pK7Lj?Vc_=RsY%@5* znYzH6Ix?Oeb&196l-4-9y{Wvd0YM`T*SN*gAGD)6nfnT~;Lh`wyd7L+yuL^=?t1ef zv9c&R86=*^YwpJT{(Yk|EBY)ajHogX&jJSRn$xrIzN6rBX3be2On!sAi1IrokY9_; zXFU&i-2i4!OPjvJXGi~?3l{BIx1Y826{!MqRmj>kxAwYRog~D0ID`fdNSCos8!@aU z(-F7`cgv%13?Q}uwAhuWEJR2&NFYDt7i806Llc7W(gI8s=O)?8WfOhJ?2))g3A^>u znu5kbSQ~*rx!`dI{bwZo2wUKLl74{@{1ua|VB z=3no7K{|O%gu$D+5Ge&De$D%{Ihd=-E$P0{zr|>#D;1;hs?}-`z`^=J7gmLJmV13S zx&R6V*vIN&#!J$+OYqX7+q7u{hV{GbJ-u#wT4!TW_+RoS^Y2|}5_O1pdlVeaI?&l` zU~gY~KC8bJW?j^0DP|cQlMo^qfVK3A1aps*oMQf1^Bc&T6l$S`k~ZGUT|V5)MUl|N zy?Mf91oa2={Wx77!$mNSag#-@J;nELo&;q6xS@+)s>l+?)~V5!n?0v+zut42&yZ@T zGopTX1zED4Yk+nGCiMa(8CmNA(@<)%{E7AXGrbh5ea1bgid^^xI=U~6Nu8osInKBE z`!oiByfEJP?x)`v4<;IUjYZEFirdk=iB0`0Ei5*Lf$_$dmk1YKKM(`?M~&Y&F&&^j zkRy4EtEId16j|1&?%q;n4`P{%5)!jNa!d0a`_{Yp0P@eoYKHi}{v*9L&hNXB=kW$l zmQaS%5eGRvjcm{gD;5-$H4F}hfLI~nup!&2mkV=)`t59848Aa%Xl&QgkOhf@{E&8p zKo*^1>d=5Ju-Q%{%Oc~-9yEOy<-t|gTOAt_*IV){wN zwMsURHZ!JFY&q`Ml5loyR{rO~y5>`92oirf%v({)4ZInrlHCDlVLoW#VhsN zC|hpb3}|MRgM{@&Y_ISqBQZoK`?0Yg?9;Uc6yvrTAh%e|xhb!%hLSk?it!!x1(I6k zg14P0V@AnZdeKbPDtTsIg8)#v!eZ#; z36BhxpJuasHTsHN-1FdH`B@Da+BlpWKpF-@-G5-#W=6I!-&bi)E8sD39N#`$tVFC# z?BBjzNlI}4`f-t`X`h07z_M^L5wWu{6R~i!q&YeQGo*>Eg46!@(}e%&!u1dCt&#?} z22Pze84rRC(A%^k8%OqC)p%?&vU>0XHaS~~eO~|BPiT0{fVHys^cD1=uch}bvsYeT zTsT0+kxEH<8EelDA3LGM=O_jN8@!`+$;%#jp^x3-Eh;&y)W`P@t?@?0P%J zG-_x2?dun50C+!72E2W)rV;uXml=HFW+qHfyE|qm(^M z7F6ulbhCcV+%pz5O}3>G?yN;rjSmB!AFtCe1r#E4dOx2Jrq5+8WZxIt0J(psu#y1W zzVEA(tMV%J_K*IyNX~8#e^aqrPbbPwt&CH{z*TDU*_s&?4G!s?7`>E@`i2;q z?Jkg<-G9i&YFT#urNavA`ou#B%5g?adWyZQhwd8HuyW#XGzva+8_iz6p0`B!3HtLb zR&2Q($(9bM(QfF_$v9Ex+zn2VvU76z6)j=`aE^azGVg=9X?Lyja`{WizCuX;2d-Um zhIPQ-{dUEdY?byvb+2&@by=}=-EE=LLM_9Bj@G#hN3xN-)C^HGoCxMexR6!3?A6K2 zaqJ?E%MwaPFn8H4Mk>_$05TWDZhSoq@nRCf`^+evBf5hhGCwtNor`dMZD3l}&YVsg z0Wy@SmjXmEY)vf>`e?`g0|Z8zPaCm zjQo7Va(Ks?c8!D3em&`&9uS6d>9D%4z!-+DRKGKgQe)B)J$1wN2IvP+ zfxSc22{_1R)mpizLog1rqJpXLXo{~y0X_ENvUjSQMZ^OX6+NumXPu}Gb}BHM#>x?S z)yq8P;?4tR3`~urX{VOt2k>m70%hUyjBubMwaSIuhGNmRIBElI?xbE0fppH(KO4x4Ny-u$P~;@3>>0wItC)@r9m|=CvMZ~ z)Mn!x)L=hf$-33#Z}$eFLZnU5)HV!?&=VXvWXw?*uoCezi)K`>Lwu%?xA7@}IG<2` z$dFa|RL;b;+sLws8>R!Eu;?ThRn1Mk&T7{J*#-Ljbs462QxY+^u+e*_rQCz1aQf@*I>~kh=PLm*}hL zC92lsolg$~^|pL2?5{5F%tj|O^xA?5#C8a=Ldg3INm6A9LFj1;#^R=VQkI)`#jA@e zxEwy4Q7}E_5r9=uYn@^Sz{M4IlAGThB*<)&JZLxPTlYzGP!q(k{i6+8n7e-CJr)f^ zTv6XgAcRtVIy2fdCBB+jxI=U4hR$oBqNL;CK|mvD2khr%&DpRl^Vv`)46^)Xbq!jO z-|1il7`!_zXQOpsoM+XyKl!p*%}kO0v$WNZ3NzHf)NQ`B80sw^0R59*ey2lA{gy7* zW`)0^xFEq*mL&&jL{4?tA;wY7Z+(8{H!%tpr z{BP8{v^=z~=?PDEBi#HqzSoLlKa+ZSIS&E8@`k!rLWcvEvCPZaPflgjhQV|Mj6Vb< zzad;ML z3MS5Z1V4Mz41{0KFWKT|dB28xewLa*NX~Q3EOx=8qn3o`R;`n{^Ype#gIo{TeS7tOTJygAqK#{uy2NZgjkc160+{;O6gps{r&K*< zEM;!We11FlLzG47FRVQE@C4jrv6aP6|=#14m4NwIILtTWK*Qh9LXNr8>cHL1c zTZGjTr{FH8zDt|+I+YV8rnm`Fl>zAMP;?G)S!UXa<{CR)#Z9V$wo>9}LBTYo<<_~{ zuxKFy@z-) z+ryEt4%)n%Oz&)ZGqtqJCxFhy^L^5RXiTF_r~pbQ>Y-v}hU)Kn6jQZ?FMYZ#g!yrj zf)$xUvJA!KdC8HqA?(0~6vqypmq=Cqp|hGlepq^@@AVXi5hUcsKDmwBvuDK8wb=Da zu>dpiUD^tSpGxuZ;GR7yCN2j%5|p*`;~CTAIqZQD!~GFBMv5Pe=vwFlAZYtX9bG!$ z100oF2x|G)bZzF88U1he_~^2mIgv=2aN=h5W+xnR6JmowMGUa~c~+C$j~*oN<=Iei z=>&@YKU5T1e$2}oIX$KG#@P@k_R!Z~Mgbsb7s>XmNE67=>J(|^!7o*{jN;{1%vWz@ zx_Yo!S`2GN5~x%4#*+)i5T~u4EHc}=a~RfA^=Q7g4EUn*l9^rU5+0H>q8R}etnJdN znq<=DEKzmUQ4pClsdVOfqV|AY@<55IfE&8YK}(sMGz zF7nRd`d&lTrRoz^V|i_aG@&XRKzUg$_z`PMKDrU6Y5#s58$pD*5?llYq=WULvPW)n z45OFwmJ%dP$=#7t8J_nO#0Pxpq8TAo{zw9Vt=~THMv}76%ing8#`f@2{> zr}=t3t_L8KA!2sDw$f?dMFe^Dw9m4R1bTcYEZMw7M+3PxlVk30i#?)=N^Yg8x4(lB zH=&`KIE_4o8_T3!+cRFPyaB8;J$&^U*(?$22h9T=&xhtZyRgdlhJn1viePq$lb_p7 zheQ@^Ok*kLZi5QshQb*;OBavItsKX9oV4yMOsIs}ewvKQbO+^^S8+BfmW0ynwM?_< zBUDsB<698>Xr-z3BDk;-%?9g~97}RSUz%Krc|(^Tha+g|oA26WKm(MDhSDD$InZW+ zyegk0dsUG@))ZS2);UbOfgB;>^u>XY$1!dO+L7v^cTT+(H^F0lux2;9i7{Z^iW5=1 z2aX)@Xns>8A|$MH$|kRFo`^XY-`Gy9nW>Np+fdLMB|s59Qw$V6Ej;2j=&f67W7Xue zvuxWcfgi`N2E(-c{Q!h}p!#A3-rnT!Xuu{+&bicO&T6al(nYXnRs3>lCH=iSvhlL? z-158w)!`OHmX&9_t+}+K?)y=*VZpBA13A+rUd#VS0t_#-c|NT9T>xO>?OO8e_=1h7YbDca z5MV_{ee+HtjjVh4fRao^Jdpbx<}|4Aa3@cFAVVu%&-611x=JBv@MZ3&1r>peoBdcrsQtjT{6^bE<9ka0EguS zYPm1Emupq2v|Cn!Ep45q$|7n4?<(26xa($sC&4a6Kd+rIB@p0t>QK;!)0?|vR{ahY znTkIYlg^bkc-`)M{F~Fnrf{+vKN#1&e%`nJsJ}i;M)iX@H&6Bnul))HCgFB$&*D_~ zc=oG4=r!NC;}1OQP2K(_AZy*kBMs&hTrtgX7=k&?q7gz7mW7CggN=xlg_VdU$%vaO z&3*_%J?(rDLJF3MnVF4_%yULaGL*j8Tnsk&TR{4;A@=#7WV(m zq}H)NY)AKdsk?Iyn7{J_js%HFT0f-+X}+~}k1}riW%nhhm{=$|z9R8H*O*hxDm>Ca zo=D<3<6g^m;*H_=Z)Iux)n?${cYQz^8ud7E`?dCYjQ9=+Q-G{m>^Z!|H0pNv?bjP8 z2>5IC{rUYq+f^r6|2g{wzb$#4vB7Ki{2god{)gI?K=8Y=yr2IQv%ti$a|K^jqlIVl zK??W$(fa>dgSOfC*|`{c+b22HvDNqK`!zaO^|AQ(+MsK-Z98uN zv@Per56R2^IRC{++-T=~)?gt|H;e1kptLI%uzRZW#Z8}#i*-u>ePNHC39zTMvd0Nue9$9jJb&a+p@P@5>n0b`|Y()hT@u8DbUT(=%Lv_k=;b|3F7MIPQ!n1zlK_~eM9-CEbYVYe7tl) z`OAg0Czhk^dJ_IXPy{pj=kAfX(^0IMZ6%R##5?KMearIndcWC>D5}ycj)zAQOh{2r4AOqH7?%<5$C|5a&>5C#(=h=-A+&?-%nqaueaCIR zh)Q5b`(+uuNen5qUra}6G9k01k{JH*j$PeOmZ}}I;_}I>4lV}=BDj_oNi2p1_|>c9 za+f8GIA`KQV@*Ydcjr#B!zgVD>jFChS9tIETRZv%PZK~V;a-fZ>ZQSNQ15@dv8yVe z37f1Zcc@oj3%}eJR(D7rVn27LtFrck| zvW2}|Lf=Shu3qY>P za=#kX*hufcquc=6l(Z%I*qA@y z0yaywcUl$w5edXDcI7f9(%DpLUICl|@sZ!CH_oN2cad3>?JcX5pxaF*Fmly4q^hB~ zR`=7VfC!N>eH6c;rXm1Nd2_nBM<;pV%Q^&kd4kYi?#oZ(`;=G^V)4!+Be>(pQ;U=^ z1O1OwKAX<@$Oj(Gf`jctHBQZaQFH|3B_MS?iolrWWR1Xg!(U!A7x4GE=VTV1XnoZ|Mdi+f%y~#1vm6s=+aqCNy#1#%fXe!g&-k zO=IhnPqq2{i2Exh8R7*MkARfsA}_#60n?@7RlD`0nWUV@n|ACzO{_%KFnp#|84ZIm zbkyg0;t+=u@hpIP$Y_w*OFOB1WPnlcX*PuoeTkBGwjt53MbBpp(?d@w)-^)|OB%=e zQx;J;Kbnj&W&aj8h-`Q$ue8TSIg&dwF$h8^R7eg1@*$IsI+w_RyZm~=M^cZjcIWs^iEGE{2@i%b&eHS?4OI$?EE zS^v;0`b9OsBoM+|fVU7@B`M2F>}Wo|?Z9Vv&RM zx~Bd6q@x_p@R%ROM<4%r6z7GCOT3bmKDVK5~FG#>gu+ zg@7Xde*eP2y6mjpPWE)7gPmXf&8HoDy)l534@$(0&?w%Cs8`7q)y6d1L^qdSY&Yr+ zi6K4z(*tDu!RR6c35^V)^9d!wdpOug#X6zH00mj08twKB1+it*d8Uhu!K!)eEI?*-5Zn)71R;-@$Jp z=OWQZ_{I*ci%E90d{!~TMAF_(Mu_@gSP5!$QAlkRT3uGpQxGaiYVqFc5;xB1@eci{ z9u-_}o&hReJ*7FpobyHNl!ruiU(Vzi0*^vxy|U~czSo>U8^O{TOop0|rs>6M z2rj~;^c;%<9d96{F&QJQk5Z;W>n>m_F&4b{aSK<26-fSS5V8C^DUO5#zKIl@^vE#y zsPqK4nUzbC4{iXI+w-^Mvyp)Sxm00ZsoC&=tZ#2vmWVyYW74i=O8ttPzb>55puVhD=H|kU*Spmpl9I^S;-q z?tnWp6Aj)_gXc_uvlRqkdz|$66O)f^F~egA*c!v_ff_NL^Cpt|wZ3czrvf{*bM8Jv zkIU5-1Ot>?DvaUiL;c2^)J)y4TM_-_BPhM~13Yhiy`sE87Fz zmQAr<^P-baxb%@z$Xg3|3zsy6aDY^xNWE_j-bP9gw6&OXS zA}%>a&0?3=wI}*rNS=vOLul2-rKu(tA7?$alFV;iL-N+vF?~laP&q-Z(lck}qbdZG zIoWXnLu-$gZq&07p^M3N~(!FtVb{AgJ3QK5iFsx}g@0>)R77|tBV~um%&#{8B!c`Ix>nG#Pt%U0JHjMEZ;k=vA`I@lZh^IwqOJ=! zGLijVVj&&oa6xTC)Udpp-1e<4B^w9NzmOm*%t`^eGZI@x@91OrUKB04asrzgAC?&=96xucn-#i=5{( zcObBTV+pw28Lp8s5D;LRC4X4W8Dbu(yWvoZ4G%e`l0ay#yC?IElASi4`6dzA zeS{+3Xh!R2_=uCc^GZx#=jgqD$nbp<>0@LVPu3NQ?_?rikkD>t`94wdn=@r2H>V_udHc|HbK=AbbGq9Nhnl`@3m(^q*zE=5g7-h+Vpuk!;u9JNqXSwm{Tf8-n2OpaP%yATzGtp#99Ed-3?G z?w@L(Zom!W_xJf7iFwNgUre)`^29D*YyMVW{^R1ai7QW&rrkW zuV}}E4Y6b?I>7S{CM~91vIYDIhz{&+bBLZ1eTZj zxWd_y_Gg~P%^1_TaqOc-C2ZJWYSnM(;Mn&R0LCvjeXPUl$kW~iqBLv!fe&4O)Cqk; z>f60P*mK|xKlxBRxIC)%+6BU#L68gMWWnSM%_Hzq%)7e7ogecpnjYCQuhNgyJB=9> z3OwmWv4m+w?@2pG77vDV5W8!GBkybV=#I6HowSF+wF6U-40~q%|FV}UQ@WBp`FwKu z0XW!P{o0L4?ddD}ded$4#10mw zZZIG@jpTilw%^D74zk8ED{XP%4(;E^@D%1V0uZp zJc#~yIp@RWJUl!*lZHsDXBtB4NtNjAuMB=kuV!9~&pdr6%9p%SJS=*!qFKpr6)uHh z32q2~oq7Fu3s($IJ#xSm(TJEYtqB^^j5l*dd65|!vm0Q522R)GeTC7&3Rr)e&!_^3 z>^0%%VBGK}WdA8v?!JJi0+*C{3EwxBY?K^9=k)`w{`@o1? zkoyRQM!r?&f}w3zJOektFomWpX1Nz|vxrB3>Y{+kz=*Zrnn0hu9!6NHI)ad&s}7>_ z%9=;=k(ZS|(cA>^RX29HVSjL_?}2=PJHbCLPc)1qAJ zxxD$oY6;)91q)H_bf6Eb!X{gsS9pwlCXl^7c-JkCNFqa| zmtk0KGg8_r+5!#S>Tcao(N&#Ob1%uR`idKY3`bNaWYtT5n60QIDFb99p-^m-rGPai z%@GoFso$n8#~@&@33+mUW=bRf9+ZMIS!p~^N+W95Uc=_K;I@;(S*ho|Ul5*u>4am} z@IpG&?1(e+n(rTx-pqvJuQL%Sco%#MtNjXsfhV@oTPTnA&}vJRrb%Zc^N#N*G5YQPc2G)_};?>M$b=;2W}f}uZy@FH@79h1DzNby;kDJMN7ytuL?L<_61?1II8!yn>p}d8bAz4;G>nDW7BRynv9u?k)~jY7$Zd7H3mzjA(p|CD6Dz` zW!M<_FQK))oy@X;bE8o2(N5u<PdYjpu9)ox$7~Bn`AIwa9<5J+8CDiGrhjMfc(jCsIxjEa9Rwi|nG4 z%v}K|0GVYDVia2)&v&Fd!Ge=xiyJ~JQP5CHZXw&-3{*WcP;DWv7eOysLxqNWw=t^bk^`GZ?Y~aXMAum*qr|{Vv>gaD3YL z<@g|8fS`UN755h%blHkI&MoQ(R>BCMAQIV z8bQF5z*D>%E;dUKx5CBNM!`9oi~TmOF$U3>U{h*ML@LJ1{1F#_*IQm-=Q8-XuawAP zVAF-evIvzUVOO;bhe0_QbT`m?6()nkcop*c3iVE%aaWRnVrEVPZ7%5;SL43bCG{|W zzaYvUC7s>RzRL5p_^uq8o`8y0b?>5ncC&0V2x36{8Ilc@Et}v*X4uf~n`u_EhWAe>u5lOcQuU3@@Fg}BT*{Ca9kMzz6xjf=D-h8`wx|ET%O=K<0XmPSkqbW4J8W%S;R)?0qF|`v zTeaSC5CBL2pzcw;g3jaBk4$C))y-cbvAc57XKL66?lH4$1#2rZ(oF;!gL-2}*C z71AZgBEve>YaV&$5$2OS0bYt>n1|qPI``Z~>vY82YX5lT_&IgaF zNYQ^TZ;9qPOE2bxK%=A7??^TVLetf1>Q$uJ2o};;s%81NL~!ys`^{=1$kCKRzO@)B zi(B4*#nvl3Zp!8saV0MH(3M5o^h*dSAB{HN~5IhiX}>~=(-WVEr)rN2&3=^FNfj&8*h7un`K+>-g@bd& zzhsl94>uV+S5|r!#1a=eunv+LdLVQh8KY2t9KX~}oOI?&7U1!MzQ^}=S)G(vh-jLG z&pD0O%LfH9ItZdjMD(a^k@-PqrEs%V37fa%3fv`vCTTA%g#6Qh4=wsIT__fEAEtW8 z0>uROMZB-#gyi(o`A8W0A+3NJGRm6G&<`Mk%W4l5$M4mr-z18Qgce*#d(IMRr z(YkYWX%C+Z{YhtR`1%vo{`!+%pilAJ6xYq95}sWtT{HvOutNj8U9q$BwIjm&&Iqww ziREiYlouzib^p~c(7WC{GE8X~Q3l{@(1gI zSa>y6xpb?t)DfLBqI_$_PHkOqRR|o8+`a`3#73u|Qrq#!?o?ZP<^D}-sPQy^I>feK z!$Q@d^b8EHglMuws`b@)zvv0dmV%*e%DA=lb6M5`^3aWGjC{4;1S0ai2xVQtF-^@C z(>hz-dE?l;$pF1da>EL%rhZ&>q}$|eU4e+!I%Y!yb+fYZM-BKKj%?VW2z|2`)!#G5iToS9ML(V05+BJ#ChlB&Q6ATK;JrgzbzA4#}EAgceu> zy+FGmyT4OY8)_$O>Ovmv3vO7TQE#1qQ~|la2NlwCB#ew6TDoO1tqm=I*@b3lQ%qxI zYF4U|Gb=-9kgFiB;f=t9yW=y7hbLBE+ZCLYRozfQOeoXC%^>OBe$TsvM4&xX%OcU0 zS{=RerK7%d)I;hhdIJ%1m}KLk_3d7_x>c-n&)27|cAgeWrb$PcF=RNr1Goerk0ChD z#@ApC>5x%>`K+skR|FJ)ZNlTbO;ot{z3JJVUg!H6ifZdEsK~0P&7IrcuzSA&Ob_W2 zL;8pIgt|-XCsKf;KhbxG4)*J9%C~nz#1&R@ck3xkhSJXk!+u zhd_%#c@)mn@M5lQOL%Lu0)VT$frV?SnZ; zd)B`{_S=XbBhEDM)*$aoT8zvJe*qfPaUd8`sHrp}WJ z>ebBiBF?9hpVfb_Z0mfnYyp=$*#;@M&p8KfO_vZj2P?N|hX-&0 z0yjCA+K2}r0X3JQ;Q<$y5{U;te=r~~Nkkx9JYi%pI5c8rVKQYmH8EsiWM()sH#0Uc zIAt<8VrDR5VLm)zWHC52VrF47Wj8f3WMO1xI5RghHZVA4GB{#pFkxXnT_8R_3UhRF zWnpa!c${Nm00AaOM%(QSOhCpN5XmDBA{lRkNPYvbxCn?8xC>_YgV|t}e@tZ{Qjia< z{vuef1A@)V3}#;fk?dd*#y22RAreG#{05QSG6*&NHDLBVAjv4O6G{9Zh-3h>1uBum z*^t=l5Nttl1e@;>61xh)7Px?5^Lith(~rddjHJE`$(&+@d-!f4sn3CnGYW45hfgSw zWU5F5+p-kNg@FhY_@^V8FuVlGMqUuf90eBV2Ac-*BjfIFuxSinSu?P#6-Ye(8d%L# c5a~Mu%%05v05}sgmXkFC<&l6(m%EDx6^tGW^#A|> From 5b2a9d1a01ef8a7810e19d87e26274d6f0bbfb5b Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Wed, 8 Mar 2017 14:49:39 +0300 Subject: [PATCH 14/66] URDF loader: resources path, "package://" removal, error messages, zero material path in .obj loader --- .../ImportURDFDemo/BulletUrdfImporter.cpp | 776 ++++++++---------- .../Importers/ImportURDFDemo/UrdfParser.cpp | 13 +- .../Importers/ImportURDFDemo/UrdfParser.h | 12 +- .../Wavefront/tiny_obj_loader.cpp | 10 + 4 files changed, 389 insertions(+), 422 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index dfe49e8b6..3137af5ae 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -32,6 +32,7 @@ static btScalar gUrdfDefaultCollisionMargin = 0.001; #include #include +#include #include "UrdfParser.h" struct MyTexture @@ -47,14 +48,27 @@ ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData UrdfParser m_urdfParser; struct GUIHelperInterface* m_guiHelper; + std::string m_sourceFile; char m_pathPrefix[1024]; int m_bodyId; btHashMap m_linkColors; btAlignedObjectArray m_allocatedCollisionShapes; LinkVisualShapesConverter* m_customVisualShapesConverter; -}; + void setSourceFile(const std::string& relativeFileName, const std::string& prefix) + { + m_sourceFile = relativeFileName; + m_urdfParser.setSourceFile(relativeFileName); + strncpy(m_pathPrefix, prefix.c_str(), sizeof(m_pathPrefix)); + m_pathPrefix[sizeof(m_pathPrefix)-1] = 0; // required, strncpy doesn't write zero on overflow + } + + BulletURDFInternalData() + { + m_pathPrefix[0] = 0; + } +}; void BulletURDFImporter::printTree() { @@ -76,7 +90,6 @@ BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, LinkVi m_data = new BulletURDFInternalData; m_data->m_guiHelper = helper; - m_data->m_pathPrefix[0]=0; m_data->m_customVisualShapesConverter = customConverter; @@ -111,7 +124,6 @@ struct BulletErrorLogger : public ErrorLogger bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) { - if (strlen(fileName)==0) return false; @@ -124,17 +136,16 @@ bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024))>0; std::string xml_string; - m_data->m_pathPrefix[0] = 0; - - if (!fileFound){ - std::cerr << "URDF file not found" << std::endl; - return false; - } else - { - - int maxPathLen = 1024; - fu.extractPath(relativeFileName,m_data->m_pathPrefix,maxPathLen); + if (!fileFound){ + b3Warning("URDF file '%s' not found\n", fileName); + return false; + } else + { + + char path[1024]; + fu.extractPath(relativeFileName, path, sizeof(path)); + m_data->setSourceFile(relativeFileName, path); std::fstream xml_file(relativeFileName, std::fstream::in); while ( xml_file.good()) @@ -166,7 +177,7 @@ void BulletURDFImporter::activateModel(int modelIndex) bool BulletURDFImporter::loadSDF(const char* fileName, bool forceFixedBase) { - + //int argc=0; char relativeFileName[1024]; @@ -176,17 +187,16 @@ bool BulletURDFImporter::loadSDF(const char* fileName, bool forceFixedBase) bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024))>0; std::string xml_string; - m_data->m_pathPrefix[0] = 0; if (!fileFound){ - std::cerr << "SDF file not found" << std::endl; + b3Warning("SDF file '%s' not found\n", fileName); return false; } else { - int maxPathLen = 1024; - fu.extractPath(relativeFileName,m_data->m_pathPrefix,maxPathLen); - + char path[1024]; + fu.extractPath(relativeFileName, path, sizeof(path)); + m_data->setSourceFile(relativeFileName, path); std::fstream xml_file(relativeFileName, std::fstream::in); while ( xml_file.good() ) @@ -447,6 +457,69 @@ static btCollisionShape* createConvexHullFromShapes(std::vector shorter; + int cnt = path_or_shorter.size(); + for (int i=0; i::iterator x=shorter.begin(); x!=shorter.end(); ++x) + { + std::string attempt = *x + "/" + fn; + FILE* f = fopen(attempt.c_str(), "rb"); + if (!f) { + //b3Printf("%s: tried '%s'", error_message_prefix.c_str(), attempt.c_str()); + continue; + } + fclose(f); + existing_file = attempt; + //b3Printf("%s: found '%s'", error_message_prefix.c_str(), attempt.c_str()); + break; + } + + if (existing_file.empty()) + { + b3Warning("%s: cannot find '%s' in any directory in urdf path\n", error_message_prefix.c_str(), fn.c_str()); + return false; + } else { + *out_found_filename = existing_file; + return true; + } +} + btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, const char* urdfPathPrefix) { BT_PROFILE("convertURDFToCollisionShape"); @@ -507,239 +580,168 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co } case URDF_GEOM_SPHERE: { - btScalar radius = collision->m_geometry.m_sphereRadius; btSphereShape* sphereShape = new btSphereShape(radius); shape = sphereShape; shape ->setMargin(gUrdfDefaultCollisionMargin); break; + } - break; - } - case URDF_GEOM_MESH: - { - if (collision->m_name.length()) + case URDF_GEOM_MESH: + { + std::string existing_file; + int fileType; + bool success = findExistingMeshFile(urdfPathPrefix, collision->m_geometry.m_meshFileName, collision->m_sourceFileLocation, &existing_file, &fileType); + if (!success) break; // error message already printed + + GLInstanceGraphicsShape* glmesh = 0; + switch (fileType) { + case FILE_OBJ: + if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH) { - //b3Printf("collision->name=%s\n",collision->m_name.c_str()); + glmesh = LoadMeshFromObj(existing_file.c_str(), 0); } - if (1) + else { - if (collision->m_geometry.m_meshFileName.length()) + std::vector shapes; + std::string err = tinyobj::LoadObj(shapes, existing_file.c_str()); + //create a convex hull for each shape, and store it in a btCompoundShape + + shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale); + return shape; + } + break; + + case FILE_STL: + glmesh = LoadMeshFromSTL(existing_file.c_str()); + break; + + case FILE_COLLADA: + { + btAlignedObjectArray visualShapes; + btAlignedObjectArray visualShapeInstances; + btTransform upAxisTrans;upAxisTrans.setIdentity(); + float unitMeterScaling = 1; + LoadMeshFromCollada(existing_file.c_str(), visualShapes, visualShapeInstances, upAxisTrans, unitMeterScaling, 2); + + glmesh = new GLInstanceGraphicsShape; + glmesh->m_indices = new b3AlignedObjectArray(); + glmesh->m_vertices = new b3AlignedObjectArray(); + + for (int i=0;im_geometry.m_meshFileName.c_str(); - //b3Printf("mesh->filename=%s\n",filename); - char fullPath[1024]; - int fileType = 0; - sprintf(fullPath,"%s%s",urdfPathPrefix,filename); - b3FileUtils::toLower(fullPath); - char tmpPathPrefix[1024]; - int maxPathLen = 1024; - b3FileUtils::extractPath(filename,tmpPathPrefix,maxPathLen); - - char collisionPathPrefix[1024]; - sprintf(collisionPathPrefix,"%s%s",urdfPathPrefix,tmpPathPrefix); - - - - if (strstr(fullPath,".dae")) + ColladaGraphicsInstance* instance = &visualShapeInstances[i]; + GLInstanceGraphicsShape* gfxShape = &visualShapes[instance->m_shapeIndex]; + + b3AlignedObjectArray verts; + verts.resize(gfxShape->m_vertices->size()); + + int baseIndex = glmesh->m_vertices->size(); + + for (int i=0;im_vertices->size();i++) { - fileType = FILE_COLLADA; + verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; + verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; + verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; + verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; + verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; + verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; + verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; + verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; + verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; + } - if (strstr(fullPath,".stl")) + + int curNumIndices = glmesh->m_indices->size(); + int additionalIndices = gfxShape->m_indices->size(); + glmesh->m_indices->resize(curNumIndices+additionalIndices); + for (int k=0;km_indices->at(curNumIndices+k)=gfxShape->m_indices->at(k)+baseIndex; } - if (strstr(fullPath,".obj")) - { - fileType = FILE_OBJ; - } - sprintf(fullPath,"%s%s",urdfPathPrefix,filename); - FILE* f = fopen(fullPath,"rb"); - if (f) + //compensate upAxisTrans and unitMeterScaling here + btMatrix4x4 upAxisMat; +upAxisMat.setIdentity(); + //upAxisMat.setPureRotation(upAxisTrans.getRotation()); + btMatrix4x4 unitMeterScalingMat; + unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling,unitMeterScaling,unitMeterScaling)); + btMatrix4x4 worldMat = unitMeterScalingMat*instance->m_worldTransform*upAxisMat; + //btMatrix4x4 worldMat = instance->m_worldTransform; + int curNumVertices = glmesh->m_vertices->size(); + int additionalVertices = verts.size(); + glmesh->m_vertices->reserve(curNumVertices+additionalVertices); + + for(int v=0;vm_flags & URDF_FORCE_CONCAVE_TRIMESH) - { - glmesh = LoadMeshFromObj(fullPath, collisionPathPrefix); - } - else - { - std::vector shapes; - std::string err = tinyobj::LoadObj(shapes, fullPath, collisionPathPrefix); - //create a convex hull for each shape, and store it in a btCompoundShape - - shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale); - return shape; - } - break; - } - case FILE_STL: - { - glmesh = LoadMeshFromSTL(fullPath); - break; - } - case FILE_COLLADA: - { - - btAlignedObjectArray visualShapes; - btAlignedObjectArray visualShapeInstances; - btTransform upAxisTrans;upAxisTrans.setIdentity(); - float unitMeterScaling=1; - int upAxis = 2; - LoadMeshFromCollada(fullPath, - visualShapes, - visualShapeInstances, - upAxisTrans, - unitMeterScaling, - upAxis ); - - glmesh = new GLInstanceGraphicsShape; - // int index = 0; - glmesh->m_indices = new b3AlignedObjectArray(); - glmesh->m_vertices = new b3AlignedObjectArray(); - - for (int i=0;im_shapeIndex]; - - b3AlignedObjectArray verts; - verts.resize(gfxShape->m_vertices->size()); - - int baseIndex = glmesh->m_vertices->size(); - - for (int i=0;im_vertices->size();i++) - { - verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; - verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; - verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; - verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; - verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; - verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; - verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; - verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; - verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; - - } - - int curNumIndices = glmesh->m_indices->size(); - int additionalIndices = gfxShape->m_indices->size(); - glmesh->m_indices->resize(curNumIndices+additionalIndices); - for (int k=0;km_indices->at(curNumIndices+k)=gfxShape->m_indices->at(k)+baseIndex; - } - - //compensate upAxisTrans and unitMeterScaling here - btMatrix4x4 upAxisMat; - upAxisMat.setIdentity(); - //upAxisMat.setPureRotation(upAxisTrans.getRotation()); - btMatrix4x4 unitMeterScalingMat; - unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling,unitMeterScaling,unitMeterScaling)); - btMatrix4x4 worldMat = unitMeterScalingMat*instance->m_worldTransform*upAxisMat; - //btMatrix4x4 worldMat = instance->m_worldTransform; - int curNumVertices = glmesh->m_vertices->size(); - int additionalVertices = verts.size(); - glmesh->m_vertices->reserve(curNumVertices+additionalVertices); - - for(int v=0;vm_vertices->push_back(verts[v]); - } - } - glmesh->m_numIndices = glmesh->m_indices->size(); - glmesh->m_numvertices = glmesh->m_vertices->size(); - //glmesh = LoadMeshFromCollada(fullPath); - - break; - } - default: - { - b3Warning("Unsupported file type in Collision: %s\n",fullPath); - btAssert(0); - } - } - - - if (glmesh && (glmesh->m_numvertices>0)) - { - //b3Printf("extracted %d verticed from STL file %s\n", glmesh->m_numvertices,fullPath); - //int shapeId = m_glApp->m_instancingRenderer->registerShape(&gvertices[0].pos[0],gvertices.size(),&indices[0],indices.size()); - //convex->setUserIndex(shapeId); - btAlignedObjectArray convertedVerts; - convertedVerts.reserve(glmesh->m_numvertices); - for (int i=0;im_numvertices;i++) - { - convertedVerts.push_back(btVector3( - glmesh->m_vertices->at(i).xyzw[0]*collision->m_geometry.m_meshScale[0], - glmesh->m_vertices->at(i).xyzw[1]*collision->m_geometry.m_meshScale[1], - glmesh->m_vertices->at(i).xyzw[2]*collision->m_geometry.m_meshScale[2])); - } - - if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH) - { - BT_PROFILE("convert trimesh"); - btTriangleMesh* meshInterface = new btTriangleMesh(); - for (int i=0;im_numIndices/3;i++) - { - float* v0 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3)).xyzw; - float* v1 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+1)).xyzw; - float* v2 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+2)).xyzw; - meshInterface->addTriangle(btVector3(v0[0],v0[1],v0[2]), - btVector3(v1[0],v1[1],v1[2]), - btVector3(v2[0],v2[1],v2[2])); - } - - btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface,true,true); - trimesh->setLocalScaling(collision->m_geometry.m_meshScale); - shape = trimesh; - } else - { - BT_PROFILE("convert btConvexHullShape"); - - btConvexHullShape* convexHull = new btConvexHullShape(&convertedVerts[0].getX(), convertedVerts.size(), sizeof(btVector3)); - convexHull->optimizeConvexHull(); - //convexHull->initializePolyhedralFeatures(); - convexHull->setMargin(gUrdfDefaultCollisionMargin); - convexHull->setLocalScaling(collision->m_geometry.m_meshScale); - shape = convexHull; - } - } else - { - b3Warning("issue extracting mesh from STL file %s\n", fullPath); - } - - delete glmesh; - - } else - { - b3Warning("mesh geometry not found %s\n",fullPath); + btVector3 pos(verts[v].xyzw[0],verts[v].xyzw[1],verts[v].xyzw[2]); + pos = worldMat*pos; + verts[v].xyzw[0] = float(pos[0]); + verts[v].xyzw[1] = float(pos[1]); + verts[v].xyzw[2] = float(pos[2]); + glmesh->m_vertices->push_back(verts[v]); } - } + glmesh->m_numIndices = glmesh->m_indices->size(); + glmesh->m_numvertices = glmesh->m_vertices->size(); + //glmesh = LoadMeshFromCollada(success.c_str()); + break; } + } + + if (!glmesh || glmesh->m_numvertices<=0) + { + b3Warning("%s: cannot extract mesh from '%s'\n", urdfPathPrefix, existing_file.c_str()); + delete glmesh; + break; + } + + btAlignedObjectArray convertedVerts; + convertedVerts.reserve(glmesh->m_numvertices); + for (int i=0; im_numvertices; i++) + { + convertedVerts.push_back(btVector3( + glmesh->m_vertices->at(i).xyzw[0]*collision->m_geometry.m_meshScale[0], + glmesh->m_vertices->at(i).xyzw[1]*collision->m_geometry.m_meshScale[1], + glmesh->m_vertices->at(i).xyzw[2]*collision->m_geometry.m_meshScale[2])); + } + + if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH) + { + BT_PROFILE("convert trimesh"); + btTriangleMesh* meshInterface = new btTriangleMesh(); + for (int i=0; im_numIndices/3; i++) + { + float* v0 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3)).xyzw; + float* v1 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+1)).xyzw; + float* v2 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+2)).xyzw; + meshInterface->addTriangle( + btVector3(v0[0],v0[1],v0[2]), + btVector3(v1[0],v1[1],v1[2]), + btVector3(v2[0],v2[1],v2[2])); + } + btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface,true,true); + trimesh->setLocalScaling(collision->m_geometry.m_meshScale); + shape = trimesh; + + } else + { + BT_PROFILE("convert btConvexHullShape"); + btConvexHullShape* convexHull = new btConvexHullShape(&convertedVerts[0].getX(), convertedVerts.size(), sizeof(btVector3)); + convexHull->optimizeConvexHull(); + //convexHull->initializePolyhedralFeatures(); + convexHull->setMargin(gUrdfDefaultCollisionMargin); + convexHull->setLocalScaling(collision->m_geometry.m_meshScale); + shape = convexHull; + } + + delete glmesh; + break; + } // mesh case - - break; - } default: - { - b3Warning("Error: unknown visual geometry type\n"); - } - } + b3Warning("Error: unknown visual geometry type\n"); + } return shape; } @@ -778,17 +780,17 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha convexColShape = cylZShape; break; } + case URDF_GEOM_BOX: { - btVector3 extents = visual->m_geometry.m_boxSize; - btBoxShape* boxShape = new btBoxShape(extents*0.5f); //btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5); convexColShape = boxShape; convexColShape->setMargin(gUrdfDefaultCollisionMargin); break; } + case URDF_GEOM_SPHERE: { btScalar radius = visual->m_geometry.m_sphereRadius; @@ -796,206 +798,142 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha convexColShape = sphereShape; convexColShape->setMargin(gUrdfDefaultCollisionMargin); break; - - break; } + case URDF_GEOM_MESH: { - if (visual->m_name.length()) + std::string existing_file; + int fileType; + bool success = findExistingMeshFile(urdfPathPrefix, visual->m_geometry.m_meshFileName, visual->m_sourceFileLocation, &existing_file, &fileType); + if (!success) break; // error message already printed + + switch (fileType) { - //b3Printf("visual->name=%s\n", visual->m_name.c_str()); - } - if (1)//visual->m_geometry) - { - if (visual->m_geometry.m_meshFileName.length()) + case FILE_OBJ: { - const char* filename = visual->m_geometry.m_meshFileName.c_str(); - //b3Printf("mesh->filename=%s\n", filename); - char fullPath[1024]; - int fileType = 0; - - char tmpPathPrefix[1024]; - std::string xml_string; - int maxPathLen = 1024; - b3FileUtils::extractPath(filename,tmpPathPrefix,maxPathLen); - - char visualPathPrefix[1024]; - sprintf(visualPathPrefix,"%s%s",urdfPathPrefix,tmpPathPrefix); - - - sprintf(fullPath, "%s%s", urdfPathPrefix, filename); - b3FileUtils::toLower(fullPath); - if (strstr(fullPath, ".dae")) + b3ImportMeshData meshData; + if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(existing_file, meshData)) { - fileType = FILE_COLLADA; + + if (meshData.m_textureImage) + { + MyTexture texData; + texData.m_width = meshData.m_textureWidth; + texData.m_height = meshData.m_textureHeight; + texData.textureData = meshData.m_textureImage; + texturesOut.push_back(texData); + } + glmesh = meshData.m_gfxShape; } - if (strstr(fullPath, ".stl")) - { - fileType = FILE_STL; - } - if (strstr(fullPath,".obj")) - { - fileType = FILE_OBJ; - } - - - sprintf(fullPath, "%s%s", urdfPathPrefix, filename); - FILE* f = fopen(fullPath, "rb"); - if (f) - { - fclose(f); - - switch (fileType) - { - case FILE_OBJ: - { -// glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); - - b3ImportMeshData meshData; - if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fullPath, meshData)) - { - - if (meshData.m_textureImage) - { - MyTexture texData; - texData.m_width = meshData.m_textureWidth; - texData.m_height = meshData.m_textureHeight; - texData.textureData = meshData.m_textureImage; - texturesOut.push_back(texData); - } - glmesh = meshData.m_gfxShape; - } - - break; - } - - case FILE_STL: - { - glmesh = LoadMeshFromSTL(fullPath); - break; - } - case FILE_COLLADA: - { - - btAlignedObjectArray visualShapes; - btAlignedObjectArray visualShapeInstances; - btTransform upAxisTrans; upAxisTrans.setIdentity(); - float unitMeterScaling = 1; - int upAxis = 2; - - LoadMeshFromCollada(fullPath, - visualShapes, - visualShapeInstances, - upAxisTrans, - unitMeterScaling, - upAxis); - - glmesh = new GLInstanceGraphicsShape; - // int index = 0; - glmesh->m_indices = new b3AlignedObjectArray(); - glmesh->m_vertices = new b3AlignedObjectArray(); - - for (int i = 0; im_shapeIndex]; - - b3AlignedObjectArray verts; - verts.resize(gfxShape->m_vertices->size()); - - int baseIndex = glmesh->m_vertices->size(); - - for (int i = 0; im_vertices->size(); i++) - { - verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; - verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; - verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; - verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; - verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; - verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; - verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; - verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; - verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; - - } - - int curNumIndices = glmesh->m_indices->size(); - int additionalIndices = gfxShape->m_indices->size(); - glmesh->m_indices->resize(curNumIndices + additionalIndices); - for (int k = 0; km_indices->at(curNumIndices + k) = gfxShape->m_indices->at(k) + baseIndex; - } - - //compensate upAxisTrans and unitMeterScaling here - btMatrix4x4 upAxisMat; - upAxisMat.setIdentity(); -// upAxisMat.setPureRotation(upAxisTrans.getRotation()); - btMatrix4x4 unitMeterScalingMat; - unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling, unitMeterScaling, unitMeterScaling)); - btMatrix4x4 worldMat = unitMeterScalingMat*upAxisMat*instance->m_worldTransform; - //btMatrix4x4 worldMat = instance->m_worldTransform; - int curNumVertices = glmesh->m_vertices->size(); - int additionalVertices = verts.size(); - glmesh->m_vertices->reserve(curNumVertices + additionalVertices); - - for (int v = 0; vm_vertices->push_back(verts[v]); - } - } - glmesh->m_numIndices = glmesh->m_indices->size(); - glmesh->m_numvertices = glmesh->m_vertices->size(); - //glmesh = LoadMeshFromCollada(fullPath); - - break; - } - default: - { - b3Warning("Error: unsupported file type for Visual mesh: %s\n", fullPath); - btAssert(0); - } - } - - - if (glmesh && glmesh->m_vertices && (glmesh->m_numvertices>0)) - { - //apply the geometry scaling - for (int i=0;im_vertices->size();i++) - { - glmesh->m_vertices->at(i).xyzw[0] *= visual->m_geometry.m_meshScale[0]; - glmesh->m_vertices->at(i).xyzw[1] *= visual->m_geometry.m_meshScale[1]; - glmesh->m_vertices->at(i).xyzw[2] *= visual->m_geometry.m_meshScale[2]; - } - - } - else - { - b3Warning("issue extracting mesh from COLLADA/STL file %s\n", fullPath); - } - - } - else - { - b3Warning("mesh geometry not found %s\n", fullPath); - } - - + break; } + + case FILE_STL: + { + glmesh = LoadMeshFromSTL(existing_file.c_str()); + break; + } + + case FILE_COLLADA: + { + btAlignedObjectArray visualShapes; + btAlignedObjectArray visualShapeInstances; + btTransform upAxisTrans; upAxisTrans.setIdentity(); + float unitMeterScaling = 1; + int upAxis = 2; + + LoadMeshFromCollada(existing_file.c_str(), + visualShapes, + visualShapeInstances, + upAxisTrans, + unitMeterScaling, + upAxis); + + glmesh = new GLInstanceGraphicsShape; + // int index = 0; + glmesh->m_indices = new b3AlignedObjectArray(); + glmesh->m_vertices = new b3AlignedObjectArray(); + + for (int i = 0; im_shapeIndex]; + + b3AlignedObjectArray verts; + verts.resize(gfxShape->m_vertices->size()); + + int baseIndex = glmesh->m_vertices->size(); + + for (int i = 0; im_vertices->size(); i++) + { + verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; + verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; + verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; + verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; + verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; + verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; + verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; + verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; + verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; + + } + + int curNumIndices = glmesh->m_indices->size(); + int additionalIndices = gfxShape->m_indices->size(); + glmesh->m_indices->resize(curNumIndices + additionalIndices); + for (int k = 0; km_indices->at(curNumIndices + k) = gfxShape->m_indices->at(k) + baseIndex; + } + + //compensate upAxisTrans and unitMeterScaling here + btMatrix4x4 upAxisMat; + upAxisMat.setIdentity(); + // upAxisMat.setPureRotation(upAxisTrans.getRotation()); + btMatrix4x4 unitMeterScalingMat; + unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling, unitMeterScaling, unitMeterScaling)); + btMatrix4x4 worldMat = unitMeterScalingMat*upAxisMat*instance->m_worldTransform; + //btMatrix4x4 worldMat = instance->m_worldTransform; + int curNumVertices = glmesh->m_vertices->size(); + int additionalVertices = verts.size(); + glmesh->m_vertices->reserve(curNumVertices + additionalVertices); + + for (int v = 0; vm_vertices->push_back(verts[v]); + } + } + glmesh->m_numIndices = glmesh->m_indices->size(); + glmesh->m_numvertices = glmesh->m_vertices->size(); + //glmesh = LoadMeshFromCollada(existing_file); + + break; + } + } // switch file type + + if (!glmesh || !glmesh->m_vertices || glmesh->m_numvertices<=0) + { + b3Warning("%s: cannot extract anything useful from mesh '%s'\n", urdfPathPrefix, existing_file.c_str()); + break; } - + //apply the geometry scaling + for (int i=0;im_vertices->size();i++) + { + glmesh->m_vertices->at(i).xyzw[0] *= visual->m_geometry.m_meshScale[0]; + glmesh->m_vertices->at(i).xyzw[1] *= visual->m_geometry.m_meshScale[1]; + glmesh->m_vertices->at(i).xyzw[2] *= visual->m_geometry.m_meshScale[2]; + } break; } + default: - { b3Warning("Error: unknown visual geometry type\n"); - } } //if we have a convex, tesselate into localVertices/localIndices diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 37cf5eb70..e27794dde 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -8,9 +8,9 @@ UrdfParser::UrdfParser() :m_parseSDF(false), m_activeSdfModel(-1) { + m_urdf2Model.m_sourceFile = "IN_MEMORY_STRING"; // if loadUrdf() called later, source file name will be replaced with real } - UrdfParser::~UrdfParser() { cleanModel(&m_urdf2Model); @@ -845,7 +845,8 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi for (TiXmlElement* vis_xml = config->FirstChildElement("visual"); vis_xml; vis_xml = vis_xml->NextSiblingElement("visual")) { UrdfVisual visual; - + visual.m_sourceFileLocation = sourceFileLocation(vis_xml); + if (parseVisual(model, visual, vis_xml,logger)) { link.m_visualArray.push_back(visual); @@ -864,6 +865,8 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi for (TiXmlElement* col_xml = config->FirstChildElement("collision"); col_xml; col_xml = col_xml->NextSiblingElement("collision")) { UrdfCollision col; + col.m_sourceFileLocation = sourceFileLocation(col_xml); + if (parseCollision(col, col_xml,logger)) { link.m_collisionArray.push_back(col); @@ -1657,3 +1660,9 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger) return true; } +std::string UrdfParser::sourceFileLocation(TiXmlElement* e) +{ + char buf[1024]; + snprintf(buf, sizeof(buf), "%s:%i", m_urdf2Model.m_sourceFile.c_str(), e->Row()); + return buf; +} diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 64088a1d9..4e7484d23 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -77,6 +77,7 @@ struct UrdfGeometry struct UrdfVisual { + std::string m_sourceFileLocation; btTransform m_linkLocalFrame; UrdfGeometry m_geometry; std::string m_name; @@ -90,6 +91,7 @@ struct UrdfVisual struct UrdfCollision { + std::string m_sourceFileLocation; btTransform m_linkLocalFrame; UrdfGeometry m_geometry; std::string m_name; @@ -159,6 +161,7 @@ struct UrdfJoint struct UrdfModel { std::string m_name; + std::string m_sourceFile; btTransform m_rootTransformInWorld; btHashMap m_materials; btHashMap m_links; @@ -204,7 +207,7 @@ public: UrdfParser(); virtual ~UrdfParser(); - + void setParseSDF(bool useSDF) { m_parseSDF = useSDF; @@ -263,6 +266,13 @@ public: } return m_urdf2Model; } + + std::string sourceFileLocation(TiXmlElement* e); + + void setSourceFile(const std::string& sourceFile) + { + m_urdf2Model.m_sourceFile = sourceFile; + } }; #endif diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp index ca4490aee..f69fa3dda 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp @@ -507,6 +507,16 @@ LoadObj( const char* filename, const char* mtl_basepath) { + std::string tmp = filename; + if (!mtl_basepath) { + int last_slash = 0; + for (int c=0; c<(int)tmp.size(); ++c) + if (tmp[c]=='/' || tmp[c]=='\\') + last_slash = c; + tmp = tmp.substr(0, last_slash); + mtl_basepath = tmp.c_str(); + //fprintf(stderr, "MTL PATH '%s' orig '%s'\n", mtl_basepath, filename); + } shapes.resize(0); std::vector allIndices; From 644e510c83f9108f79d9ae98411e0a0f97be208b Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Wed, 8 Mar 2017 12:38:27 -0800 Subject: [PATCH 15/66] Fix Issue 997 --- src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.h b/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.h index 9a6d16fbe..81c614272 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.h @@ -124,7 +124,6 @@ public: btCollisionShape* getCollisionShapeByIndex(int index); int getNumRigidBodies() const; btCollisionObject* getRigidBodyByIndex(int index) const; - int getNumConstraints() const; int getNumBvhs() const; btOptimizedBvh* getBvhByIndex(int index) const; From f2aa67d2627476103d2fc5efe318f52c0191d747 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 8 Mar 2017 14:10:43 -0800 Subject: [PATCH 16/66] improve vrhand.py --- examples/pybullet/vrhand.py | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/examples/pybullet/vrhand.py b/examples/pybullet/vrhand.py index 44651c65e..2ab6ab732 100644 --- a/examples/pybullet/vrhand.py +++ b/examples/pybullet/vrhand.py @@ -53,15 +53,28 @@ def convertSensor(x): b = (v-minV)/float(maxV-minV) return (1.0-b) +controllerId = -1 + +serialSteps = 0 +serialStepsUntilCheckVREvents = 3 + + ser = serial.Serial(port='COM9',baudrate=115200,parity=serial.PARITY_ODD,stopbits=serial.STOPBITS_TWO,bytesize=serial.SEVENBITS) if (ser.isOpen()): while True: events = p.getVREvents() for e in (events): if (e[BUTTONS][33]&p.VR_BUTTON_IS_DOWN): + controllerId = e[0] + if (e[0] == controllerId): p.changeConstraint(hand_cid,e[POSITION],e[ORIENTATION], maxForce=50) + serialSteps = 0 while ser.inWaiting() > 0: + serialSteps=serialSteps+1 + if (serialSteps>serialStepsUntilCheckVREvents): + ser.flushInput() + break line = str(ser.readline()) words = line.split(",") if (len(words)==6): From 51dc3a1710b443175ebe6b20a17edcfd37798b2a Mon Sep 17 00:00:00 2001 From: Julian Date: Wed, 8 Mar 2017 19:36:41 -0800 Subject: [PATCH 17/66] VR controller the kuka arm --- examples/pybullet/vr_kuka_control.py | 90 ++++++++++++++++++++++++++++ 1 file changed, 90 insertions(+) create mode 100644 examples/pybullet/vr_kuka_control.py diff --git a/examples/pybullet/vr_kuka_control.py b/examples/pybullet/vr_kuka_control.py new file mode 100644 index 000000000..d35e8ef45 --- /dev/null +++ b/examples/pybullet/vr_kuka_control.py @@ -0,0 +1,90 @@ +## Assume you have run vr_kuka_setup and have default scene set up +# Require p.setInternalSimFlags(0) in kuka_setup +import pybullet as p +import math +p.connect(p.SHARED_MEMORY) + +kuka = 3 +kuka_gripper = 7 +POSITION = 1 +BUTTONS = 6 + +THRESHOLD = 1.3 +LOWER_LIMITS = [-.967, -2.0, -2.96, 0.19, -2.96, -2.09, -3.05] +UPPER_LIMITS = [.96, 2.0, 2.96, 2.29, 2.96, 2.09, 3.05] +JOINT_RANGE = [5.8, 4, 5.8, 4, 5.8, 4, 6] +REST_POSE = [0, 0, 0, math.pi / 2, 0, -math.pi * 0.66, 0] +JOINT_DAMP = [.1, .1, .1, .1, .1, .1, .1] +REST_JOINT_POS = [-0., -0., 0., 1.570793, 0., -1.036725, 0.000001] +MAX_FORCE = 500 + +def euc_dist(posA, posB): + dist = 0. + for i in range(len(posA)): + dist += (posA[i] - posB[i]) ** 2 + return dist + +p.setRealTimeSimulation(1) + +controllers = [e[0] for e in p.getVREvents()] + +while True: + + events = p.getVREvents() + for e in (events): + + # Only use one controller + if e[0] == min(controllers): + break + + sq_len = euc_dist(p.getLinkState(kuka, 6)[0], e[POSITION]) + + # A simplistic version of gripper control + if e[BUTTONS][33] & p.VR_BUTTON_WAS_TRIGGERED: + # avg = 0. + for i in range(p.getNumJoints(kuka_gripper)): + p.setJointMotorControl2(kuka_gripper, i, p.VELOCITY_CONTROL, targetVelocity=5, force=50) + # posTarget = 0.1 + (1 - min(0.75, e[3])) * 1.5 * math.pi * 0.29; + # maxPosTarget = 0.55 + # correction = 0. + # jointPosition = p.getJointState(kuka_gripper, i)[0] + # if avg: + # correction = jointPosition - avg + # if jointPosition < 0: + # p.resetJointState(kuka_gripper, i, 0) + # if jointPosition > maxPosTarget: + # p.resetJointState(kuka_gripper, i, maxPosTarget) + # if avg: + + # p.setJointMotorControl2(kuka_gripper, i, p.POSITION_CONTROL, + # targetPosition=avg, targetVelocity=0., + # positionGain=1, velocityGain=0.5, force=50) + # else: + # p.setJointMotorControl2(kuka_gripper, i, p.POSITION_CONTROL, + # targetPosition=posTarget, targetVelocity=0., + # positionGain=1, velocityGain=0.5, force=50) + # avg = p.getJointState(kuka_gripper, i)[0] + + + if e[BUTTONS][33] & p.VR_BUTTON_WAS_RELEASED: + for i in range(p.getNumJoints(kuka_gripper)): + p.setJointMotorControl2(kuka_gripper, i, p.VELOCITY_CONTROL, targetVelocity=-5, force=50) + + if sq_len < THRESHOLD * THRESHOLD: + + joint_pos = p.calculateInverseKinematics(kuka, 6, e[POSITION], (0, 1, 0, 0), + lowerLimits=LOWER_LIMITS, upperLimits=UPPER_LIMITS, + jointRanges=JOINT_RANGE, restPoses=REST_POSE, jointDamping=JOINT_DAMP) + for i in range(len(joint_pos)): + p.setJointMotorControl2(kuka, i, p.POSITION_CONTROL, + targetPosition=joint_pos[i], targetVelocity=0, + positionGain=0.6, velocityGain=1.0, force=MAX_FORCE) + + else: + # Set back to original rest pose + for jointIndex in range(p.getNumJoints(kuka)): + p.setJointMotorControl2(kuka, jointIndex, p.POSITION_CONTROL, + REST_JOINT_POS[jointIndex], 0) + + + From ca31bb2bbd17b245434517d935683bb3216eaf3d Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 9 Mar 2017 17:42:59 -0800 Subject: [PATCH 18/66] pybullet.ER_BULLET_HARDWARE_OPENGL and ER_TINY_RENDERER exposed (for getCameraImage, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) improve performance of getCameraImage when using ER_BULLET_HARDWARE_OPENGL --- examples/ExampleBrowser/OpenGLGuiHelper.cpp | 66 ++++++++++++++------- examples/pybullet/pybullet.c | 4 ++ examples/pybullet/testrender.py | 3 +- examples/pybullet/testrender_np.py | 17 +++--- 4 files changed, 58 insertions(+), 32 deletions(-) diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 1c5893ce6..2107c8bb3 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -427,47 +427,67 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa SimpleCamera tempCam; getRenderInterface()->setActiveCamera(&tempCam); getRenderInterface()->getActiveCamera()->setVRCamera(viewMatrix,projectionMatrix); - getRenderInterface()->renderScene(); + { + BT_PROFILE("renderScene"); + getRenderInterface()->renderScene(); + } getRenderInterface()->setActiveCamera(oldCam); { + BT_PROFILE("copy pixels"); btAlignedObjectArray sourceRgbaPixelBuffer; btAlignedObjectArray sourceDepthBuffer; //copy the image into our local cache sourceRgbaPixelBuffer.resize(sourceWidth*sourceHeight*numBytesPerPixel); sourceDepthBuffer.resize(sourceWidth*sourceHeight); - m_data->m_glApp->getScreenPixels(&(sourceRgbaPixelBuffer[0]),sourceRgbaPixelBuffer.size(), &sourceDepthBuffer[0],sizeof(float)*sourceDepthBuffer.size()); + { + BT_PROFILE("getScreenPixels"); + m_data->m_glApp->getScreenPixels(&(sourceRgbaPixelBuffer[0]),sourceRgbaPixelBuffer.size(), &sourceDepthBuffer[0],sizeof(float)*sourceDepthBuffer.size()); + } m_data->m_rgbaPixelBuffer1.resize(destinationWidth*destinationHeight*numBytesPerPixel); m_data->m_depthBuffer1.resize(destinationWidth*destinationHeight); //rescale and flip - - for (int i=0;im_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0]; + int* src = (int*)&sourceRgbaPixelBuffer[sourcePixelIndex+0]; + *dst = *src; + +#else + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0]; + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1]; + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2]; + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+3] = 255; +#endif + if (depthBuffer) + { + m_data->m_depthBuffer1[i+j*destinationWidth] = sourceDepthBuffer[sourceDepthIndex]; + } - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0]; - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1]; - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2]; - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+3] = 255; - - m_data->m_depthBuffer1[i+j*destinationWidth] = sourceDepthBuffer[sourceDepthIndex]; - - } + } + } } } } if (pixelsRGBA) { + BT_PROFILE("copy rgba pixels"); + for (int i=0;im_rgbaPixelBuffer1[i+startPixelIndex*numBytesPerPixel]; @@ -475,6 +495,8 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa } if (depthBuffer) { + BT_PROFILE("copy depth buffer pixels"); + for (int i=0;im_depthBuffer1[i+startPixelIndex]; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 30d49562b..c0465f7fb 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -5380,6 +5380,10 @@ initpybullet(void) PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI); PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS); PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME); + + PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER); + PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL); + PyModule_AddIntConstant(m,"B3G_F1",B3G_F1); PyModule_AddIntConstant(m,"B3G_F2",B3G_F2); PyModule_AddIntConstant(m,"B3G_F3",B3G_F3); diff --git a/examples/pybullet/testrender.py b/examples/pybullet/testrender.py index 0d3475c84..72fa9e27e 100644 --- a/examples/pybullet/testrender.py +++ b/examples/pybullet/testrender.py @@ -29,7 +29,8 @@ for pitch in range (0,360,10) : viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) aspect = pixelWidth / pixelHeight; projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); - img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection,lightColor) + #getCameraImage can also use renderer=pybullet.ER_BULLET_HARDWARE_OPENGL + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection,lightColor,renderer=pybullet.ER_TINY_RENDERER) w=img_arr[0] h=img_arr[1] rgb=img_arr[2] diff --git a/examples/pybullet/testrender_np.py b/examples/pybullet/testrender_np.py index b8fca10eb..c008da09f 100644 --- a/examples/pybullet/testrender_np.py +++ b/examples/pybullet/testrender_np.py @@ -6,7 +6,7 @@ import matplotlib.pyplot as plt import pybullet import time -pybullet.connect(pybullet.DIRECT) +pybullet.connect(pybullet.GUI) pybullet.loadURDF("r2d2.urdf") camTargetPos = [0,0,0] @@ -18,8 +18,8 @@ pitch = 10.0 roll=0 upAxisIndex = 2 camDistance = 4 -pixelWidth = 1920 -pixelHeight = 1080 +pixelWidth = 1024 +pixelHeight = 768 nearPlane = 0.01 farPlane = 1000 @@ -31,7 +31,7 @@ for pitch in range (0,360,10) : viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) aspect = pixelWidth / pixelHeight; projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); - img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0]) + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) stop = time.time() print ("renderImage %f" % (stop - start)) @@ -40,13 +40,12 @@ for pitch in range (0,360,10) : rgb=img_arr[2] #color data RGB dep=img_arr[3] #depth data - print 'width = %d height = %d' % (w,h) + print ('width = %d height = %d' % (w,h)) #note that sending the data to matplotlib is really slow - #show - plt.imshow(rgb,interpolation='none') - #plt.show() - plt.pause(0.01) + + plt.imshow(rgb,interpolation='none') + plt.pause(0.001) main_stop = time.time() From 82495f3c84983bd2b2d4f1aa1bcd670d7c95b287 Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Fri, 10 Mar 2017 18:17:38 +0300 Subject: [PATCH 19/66] URDF loader: reuse the same resources finder routine for TinyRendererVisualShapeConverter --- .../ImportURDFDemo/BulletUrdfImporter.cpp | 54 ++- .../Importers/ImportURDFDemo/UrdfParser.cpp | 27 +- .../Importers/ImportURDFDemo/UrdfParser.h | 14 +- .../TinyRendererVisualShapeConverter.cpp | 322 +++++++----------- 4 files changed, 170 insertions(+), 247 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 3137af5ae..844b0adef 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -457,9 +457,8 @@ static btCollisionShape* createConvexHullFromShapes(std::vector shorter; - int cnt = path_or_shorter.size(); + shorter.push_back("../.."); + shorter.push_back(".."); + shorter.push_back("."); + int cnt = urdf_path.size(); for (int i=0; im_geometry.m_meshFileName, collision->m_sourceFileLocation, &existing_file, &fileType); - if (!success) break; // error message already printed - GLInstanceGraphicsShape* glmesh = 0; - switch (fileType) { + switch (collision->m_geometry.m_meshFileType) { case FILE_OBJ: if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH) { - glmesh = LoadMeshFromObj(existing_file.c_str(), 0); + glmesh = LoadMeshFromObj(collision->m_geometry.m_meshFileName.c_str(), 0); } else { std::vector shapes; - std::string err = tinyobj::LoadObj(shapes, existing_file.c_str()); + std::string err = tinyobj::LoadObj(shapes, collision->m_geometry.m_meshFileName.c_str()); //create a convex hull for each shape, and store it in a btCompoundShape shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale); @@ -613,7 +608,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co break; case FILE_STL: - glmesh = LoadMeshFromSTL(existing_file.c_str()); + glmesh = LoadMeshFromSTL(collision->m_geometry.m_meshFileName.c_str()); break; case FILE_COLLADA: @@ -622,7 +617,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co btAlignedObjectArray visualShapeInstances; btTransform upAxisTrans;upAxisTrans.setIdentity(); float unitMeterScaling = 1; - LoadMeshFromCollada(existing_file.c_str(), visualShapes, visualShapeInstances, upAxisTrans, unitMeterScaling, 2); + LoadMeshFromCollada(collision->m_geometry.m_meshFileName.c_str(), visualShapes, visualShapeInstances, upAxisTrans, unitMeterScaling, 2); glmesh = new GLInstanceGraphicsShape; glmesh->m_indices = new b3AlignedObjectArray(); @@ -691,7 +686,7 @@ upAxisMat.setIdentity(); if (!glmesh || glmesh->m_numvertices<=0) { - b3Warning("%s: cannot extract mesh from '%s'\n", urdfPathPrefix, existing_file.c_str()); + b3Warning("%s: cannot extract mesh from '%s'\n", urdfPathPrefix, collision->m_geometry.m_meshFileName.c_str()); delete glmesh; break; } @@ -802,17 +797,12 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha case URDF_GEOM_MESH: { - std::string existing_file; - int fileType; - bool success = findExistingMeshFile(urdfPathPrefix, visual->m_geometry.m_meshFileName, visual->m_sourceFileLocation, &existing_file, &fileType); - if (!success) break; // error message already printed - - switch (fileType) + switch (visual->m_geometry.m_meshFileType) { case FILE_OBJ: { b3ImportMeshData meshData; - if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(existing_file, meshData)) + if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData)) { if (meshData.m_textureImage) @@ -830,7 +820,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha case FILE_STL: { - glmesh = LoadMeshFromSTL(existing_file.c_str()); + glmesh = LoadMeshFromSTL(visual->m_geometry.m_meshFileName.c_str()); break; } @@ -842,7 +832,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha float unitMeterScaling = 1; int upAxis = 2; - LoadMeshFromCollada(existing_file.c_str(), + LoadMeshFromCollada(visual->m_geometry.m_meshFileName.c_str(), visualShapes, visualShapeInstances, upAxisTrans, @@ -910,7 +900,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha } glmesh->m_numIndices = glmesh->m_indices->size(); glmesh->m_numvertices = glmesh->m_vertices->size(); - //glmesh = LoadMeshFromCollada(existing_file); + //glmesh = LoadMeshFromCollada(visual->m_geometry.m_meshFileName); break; } @@ -918,7 +908,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha if (!glmesh || !glmesh->m_vertices || glmesh->m_numvertices<=0) { - b3Warning("%s: cannot extract anything useful from mesh '%s'\n", urdfPathPrefix, existing_file.c_str()); + b3Warning("%s: cannot extract anything useful from mesh '%s'\n", urdfPathPrefix, visual->m_geometry.m_meshFileName.c_str()); break; } diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index e27794dde..4ccb9b14a 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -444,21 +444,24 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* return false; } - geom.m_meshFileName = shape->Attribute("filename"); - geom.m_meshScale.setValue(1,1,1); + bool success = findExistingMeshFile( + m_urdf2Model.m_sourceFile, shape->Attribute("filename"), sourceFileLocation(shape), + &geom.m_meshFileName, &geom.m_meshFileType); + if (!success) return false; // warning printed + geom.m_meshScale.setValue(1,1,1); - if (shape->Attribute("scale")) + if (shape->Attribute("scale")) { if (!parseVector3(geom.m_meshScale,shape->Attribute("scale"),logger)) - { - logger->reportWarning("scale should be a vector3, not single scalar. Workaround activated.\n"); - std::string scalar_str = shape->Attribute("scale"); - double scaleFactor = urdfLexicalCast(scalar_str.c_str()); - if (scaleFactor) - { - geom.m_meshScale.setValue(scaleFactor,scaleFactor,scaleFactor); - } - } + { + logger->reportWarning("%s: scale should be a vector3, not single scalar. Workaround activated.\n"); + std::string scalar_str = shape->Attribute("scale"); + double scaleFactor = urdfLexicalCast(scalar_str.c_str()); + if (scaleFactor) + { + geom.m_meshScale.setValue(scaleFactor,scaleFactor,scaleFactor); + } + } } else { } diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 4e7484d23..505e2658f 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -69,12 +69,22 @@ struct UrdfGeometry double m_cylinderRadius; double m_cylinderLength; - btVector3 m_planeNormal; + btVector3 m_planeNormal; + enum { + FILE_STL =1, + FILE_COLLADA =2, + FILE_OBJ =3, + }; + int m_meshFileType; std::string m_meshFileName; - btVector3 m_meshScale; + btVector3 m_meshScale; }; +bool findExistingMeshFile(const std::string& urdf_path, std::string fn, + const std::string& error_message_prefix, + std::string* out_found_filename, int* out_type); // intended to fill UrdfGeometry::m_meshFileName and Type, but can be used elsewhere + struct UrdfVisual { std::string m_sourceFileLocation; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index cfe25c938..1876e9623 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -36,13 +36,6 @@ subject to the following restrictions: #include "../TinyRenderer/model.h" #include "../ThirdPartyLibs/stb_image/stb_image.h" -enum MyFileType -{ - MY_FILE_STL=1, - MY_FILE_COLLADA=2, - MY_FILE_OBJ=3, -}; - struct MyTexture2 { unsigned char* textureData; @@ -241,223 +234,150 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref convexColShape = sphereShape; convexColShape->setMargin(0.001); break; - - break; } case URDF_GEOM_MESH: { - if (visual->m_name.length()) + strncpy(visualShapeOut.m_meshAssetFileName, visual->m_geometry.m_meshFileName.c_str(), VISUAL_SHAPE_MAX_PATH_LEN); + visualShapeOut.m_meshAssetFileName[VISUAL_SHAPE_MAX_PATH_LEN-1] = 0; + + visualShapeOut.m_dimensions[0] = visual->m_geometry.m_meshScale[0]; + visualShapeOut.m_dimensions[1] = visual->m_geometry.m_meshScale[1]; + visualShapeOut.m_dimensions[2] = visual->m_geometry.m_meshScale[2]; + + visualShapeOut.m_localVisualFrame[0] = visual->m_linkLocalFrame.getOrigin()[0]; + visualShapeOut.m_localVisualFrame[1] = visual->m_linkLocalFrame.getOrigin()[1]; + visualShapeOut.m_localVisualFrame[2] = visual->m_linkLocalFrame.getOrigin()[2]; + visualShapeOut.m_localVisualFrame[3] = visual->m_linkLocalFrame.getRotation()[0]; + visualShapeOut.m_localVisualFrame[4] = visual->m_linkLocalFrame.getRotation()[1]; + visualShapeOut.m_localVisualFrame[5] = visual->m_linkLocalFrame.getRotation()[2]; + visualShapeOut.m_localVisualFrame[6] = visual->m_linkLocalFrame.getRotation()[3]; + + switch (visual->m_geometry.m_meshFileType) { - //b3Printf("visual->name=%s\n", visual->m_name.c_str()); - } - if (1)//visual->m_geometry) - { - if (visual->m_geometry.m_meshFileName.length()) + case UrdfGeometry::FILE_OBJ: { - const char* filename = visual->m_geometry.m_meshFileName.c_str(); - //b3Printf("mesh->filename=%s\n", filename); - char fullPath[1024]; - int fileType = 0; - - char tmpPathPrefix[1024]; - std::string xml_string; - int maxPathLen = 1024; - b3FileUtils::extractPath(filename,tmpPathPrefix,maxPathLen); - - char visualPathPrefix[1024]; - sprintf(visualPathPrefix,"%s%s",urdfPathPrefix,tmpPathPrefix); - - - sprintf(fullPath, "%s%s", urdfPathPrefix, filename); - b3FileUtils::toLower(fullPath); - if (strstr(fullPath, ".dae")) + //glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); + b3ImportMeshData meshData; + if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData)) { - fileType = MY_FILE_COLLADA; - } - if (strstr(fullPath, ".stl")) - { - fileType = MY_FILE_STL; - } - if (strstr(fullPath,".obj")) - { - fileType = MY_FILE_OBJ; - } - - sprintf(fullPath, "%s%s", urdfPathPrefix, filename); - - visualShapeOut.m_dimensions[0] = visual->m_geometry.m_meshScale[0]; - visualShapeOut.m_dimensions[1] = visual->m_geometry.m_meshScale[1]; - visualShapeOut.m_dimensions[2] = visual->m_geometry.m_meshScale[2]; - visualShapeOut.m_localVisualFrame[0] = visual->m_linkLocalFrame.getOrigin()[0]; - visualShapeOut.m_localVisualFrame[1] = visual->m_linkLocalFrame.getOrigin()[1]; - visualShapeOut.m_localVisualFrame[2] = visual->m_linkLocalFrame.getOrigin()[2]; - visualShapeOut.m_localVisualFrame[3] = visual->m_linkLocalFrame.getRotation()[0]; - visualShapeOut.m_localVisualFrame[4] = visual->m_linkLocalFrame.getRotation()[1]; - visualShapeOut.m_localVisualFrame[5] = visual->m_linkLocalFrame.getRotation()[2]; - visualShapeOut.m_localVisualFrame[6] = visual->m_linkLocalFrame.getRotation()[3]; - - int sl = strlen(fullPath); - if (sl < (VISUAL_SHAPE_MAX_PATH_LEN-1)) - { - memcpy(visualShapeOut.m_meshAssetFileName, fullPath, sl); - visualShapeOut.m_meshAssetFileName[sl] = 0; - } - - FILE* f = fopen(fullPath, "rb"); - if (f) - { - fclose(f); - - - - switch (fileType) + if (meshData.m_textureImage) { - case MY_FILE_OBJ: - { - //glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); - b3ImportMeshData meshData; - if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fullPath, meshData)) - { - - if (meshData.m_textureImage) - { - MyTexture2 texData; - texData.m_width = meshData.m_textureWidth; - texData.m_height = meshData.m_textureHeight; - texData.textureData = meshData.m_textureImage; - texturesOut.push_back(texData); - } - glmesh = meshData.m_gfxShape; - } - - - break; - } - - case MY_FILE_STL: - { - glmesh = LoadMeshFromSTL(fullPath); - break; + MyTexture2 texData; + texData.m_width = meshData.m_textureWidth; + texData.m_height = meshData.m_textureHeight; + texData.textureData = meshData.m_textureImage; + texturesOut.push_back(texData); } - case MY_FILE_COLLADA: + glmesh = meshData.m_gfxShape; + } + break; + } + case UrdfGeometry::FILE_STL: + glmesh = LoadMeshFromSTL(visual->m_geometry.m_meshFileName.c_str()); + break; + case UrdfGeometry::FILE_COLLADA: + { + btAlignedObjectArray visualShapes; + btAlignedObjectArray visualShapeInstances; + btTransform upAxisTrans; upAxisTrans.setIdentity(); + float unitMeterScaling = 1; + int upAxis = 2; + + LoadMeshFromCollada(visual->m_geometry.m_meshFileName.c_str(), + visualShapes, + visualShapeInstances, + upAxisTrans, + unitMeterScaling, + upAxis); + + glmesh = new GLInstanceGraphicsShape; + // int index = 0; + glmesh->m_indices = new b3AlignedObjectArray(); + glmesh->m_vertices = new b3AlignedObjectArray(); + + for (int i = 0; im_shapeIndex]; + + b3AlignedObjectArray verts; + verts.resize(gfxShape->m_vertices->size()); + + int baseIndex = glmesh->m_vertices->size(); + + for (int i = 0; im_vertices->size(); i++) { + verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; + verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; + verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; + verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; + verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; + verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; + verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; + verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; + verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; - btAlignedObjectArray visualShapes; - btAlignedObjectArray visualShapeInstances; - btTransform upAxisTrans; upAxisTrans.setIdentity(); - float unitMeterScaling = 1; - int upAxis = 2; + } - LoadMeshFromCollada(fullPath, - visualShapes, - visualShapeInstances, - upAxisTrans, - unitMeterScaling, - upAxis); + int curNumIndices = glmesh->m_indices->size(); + int additionalIndices = gfxShape->m_indices->size(); + glmesh->m_indices->resize(curNumIndices + additionalIndices); + for (int k = 0; km_indices->at(curNumIndices + k) = gfxShape->m_indices->at(k) + baseIndex; + } - glmesh = new GLInstanceGraphicsShape; - // int index = 0; - glmesh->m_indices = new b3AlignedObjectArray(); - glmesh->m_vertices = new b3AlignedObjectArray(); - - for (int i = 0; im_shapeIndex]; - - b3AlignedObjectArray verts; - verts.resize(gfxShape->m_vertices->size()); - - int baseIndex = glmesh->m_vertices->size(); - - for (int i = 0; im_vertices->size(); i++) - { - verts[i].normal[0] = gfxShape->m_vertices->at(i).normal[0]; - verts[i].normal[1] = gfxShape->m_vertices->at(i).normal[1]; - verts[i].normal[2] = gfxShape->m_vertices->at(i).normal[2]; - verts[i].uv[0] = gfxShape->m_vertices->at(i).uv[0]; - verts[i].uv[1] = gfxShape->m_vertices->at(i).uv[1]; - verts[i].xyzw[0] = gfxShape->m_vertices->at(i).xyzw[0]; - verts[i].xyzw[1] = gfxShape->m_vertices->at(i).xyzw[1]; - verts[i].xyzw[2] = gfxShape->m_vertices->at(i).xyzw[2]; - verts[i].xyzw[3] = gfxShape->m_vertices->at(i).xyzw[3]; - - } - - int curNumIndices = glmesh->m_indices->size(); - int additionalIndices = gfxShape->m_indices->size(); - glmesh->m_indices->resize(curNumIndices + additionalIndices); - for (int k = 0; km_indices->at(curNumIndices + k) = gfxShape->m_indices->at(k) + baseIndex; - } - - //compensate upAxisTrans and unitMeterScaling here - btMatrix4x4 upAxisMat; - upAxisMat.setIdentity(); + //compensate upAxisTrans and unitMeterScaling here + btMatrix4x4 upAxisMat; + upAxisMat.setIdentity(); // upAxisMat.setPureRotation(upAxisTrans.getRotation()); - btMatrix4x4 unitMeterScalingMat; - unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling, unitMeterScaling, unitMeterScaling)); - btMatrix4x4 worldMat = unitMeterScalingMat*upAxisMat*instance->m_worldTransform; - //btMatrix4x4 worldMat = instance->m_worldTransform; - int curNumVertices = glmesh->m_vertices->size(); - int additionalVertices = verts.size(); - glmesh->m_vertices->reserve(curNumVertices + additionalVertices); + btMatrix4x4 unitMeterScalingMat; + unitMeterScalingMat.setPureScaling(btVector3(unitMeterScaling, unitMeterScaling, unitMeterScaling)); + btMatrix4x4 worldMat = unitMeterScalingMat*upAxisMat*instance->m_worldTransform; + //btMatrix4x4 worldMat = instance->m_worldTransform; + int curNumVertices = glmesh->m_vertices->size(); + int additionalVertices = verts.size(); + glmesh->m_vertices->reserve(curNumVertices + additionalVertices); - for (int v = 0; vm_vertices->push_back(verts[v]); - } - } - glmesh->m_numIndices = glmesh->m_indices->size(); - glmesh->m_numvertices = glmesh->m_vertices->size(); - //glmesh = LoadMeshFromCollada(fullPath); - - break; - } - default: + for (int v = 0; vm_vertices->push_back(verts[v]); } - } - - - if (glmesh && glmesh->m_vertices && (glmesh->m_numvertices>0)) - { - //apply the geometry scaling - for (int i=0;im_vertices->size();i++) - { - glmesh->m_vertices->at(i).xyzw[0] *= visual->m_geometry.m_meshScale[0]; - glmesh->m_vertices->at(i).xyzw[1] *= visual->m_geometry.m_meshScale[1]; - glmesh->m_vertices->at(i).xyzw[2] *= visual->m_geometry.m_meshScale[2]; - } - - } - else - { - b3Warning("issue extracting mesh from COLLADA/STL file %s\n", fullPath); - } - - } - else - { - b3Warning("mesh geometry not found %s\n", fullPath); } + glmesh->m_numIndices = glmesh->m_indices->size(); + glmesh->m_numvertices = glmesh->m_vertices->size(); + //glmesh = LoadMeshFromCollada(visual->m_geometry.m_meshFileName.c_str()); + break; + } + default: + // should never get here (findExistingMeshFile returns false if it doesn't recognize extension) + btAssert(0); + } + if (glmesh && glmesh->m_vertices && (glmesh->m_numvertices>0)) + { + //apply the geometry scaling + for (int i=0;im_vertices->size();i++) + { + glmesh->m_vertices->at(i).xyzw[0] *= visual->m_geometry.m_meshScale[0]; + glmesh->m_vertices->at(i).xyzw[1] *= visual->m_geometry.m_meshScale[1]; + glmesh->m_vertices->at(i).xyzw[2] *= visual->m_geometry.m_meshScale[2]; } } - - + else + { + b3Warning("issue extracting mesh from COLLADA/STL file %s\n", visual->m_geometry.m_meshFileName.c_str()); + } break; - } + } // case mesh + default: { b3Warning("Error: unknown visual geometry type\n"); From 3a8199ec2867c8c38751a323641ce972c8fee572 Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Fri, 10 Mar 2017 19:46:46 +0300 Subject: [PATCH 20/66] Fix formatting --- .../ImportURDFDemo/BulletUrdfImporter.cpp | 34 +++++++++++++++---- .../Importers/ImportURDFDemo/UrdfParser.cpp | 9 +++-- 2 files changed, 34 insertions(+), 9 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 844b0adef..553c34b12 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -467,13 +467,26 @@ bool findExistingMeshFile( b3Warning("%s: invalid mesh filename '%s'\n", error_message_prefix.c_str(), fn.c_str()); return false; } + std::string ext; std::string ext_ = fn.substr(fn.size()-4); for (std::string::iterator i=ext_.begin(); i!=ext_.end(); ++i) + { ext += char(tolower(*i)); - if (ext==".dae") *out_type = UrdfGeometry::FILE_COLLADA; - else if (ext==".stl") *out_type = UrdfGeometry::FILE_STL; - else if (ext==".obj") *out_type = UrdfGeometry::FILE_OBJ; + } + + if (ext==".dae") + { + *out_type = UrdfGeometry::FILE_COLLADA; + } + else if (ext==".stl") + { + *out_type = UrdfGeometry::FILE_STL; + } + else if (ext==".obj") + { + *out_type = UrdfGeometry::FILE_OBJ; + } else { b3Warning("%s: invalid mesh filename extension '%s'\n", error_message_prefix.c_str(), ext.c_str()); @@ -489,9 +502,12 @@ bool findExistingMeshFile( shorter.push_back(".."); shorter.push_back("."); int cnt = urdf_path.size(); - for (int i=0; im_geometry.m_meshFileType) { + switch (collision->m_geometry.m_meshFileType) + { case FILE_OBJ: if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH) { diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 4ccb9b14a..cd0a19acc 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -439,7 +439,8 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* } else { - if (!shape->Attribute("filename")) { + if (!shape->Attribute("filename")) + { logger->reportError("Mesh must contain a filename attribute"); return false; } @@ -447,7 +448,11 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* bool success = findExistingMeshFile( m_urdf2Model.m_sourceFile, shape->Attribute("filename"), sourceFileLocation(shape), &geom.m_meshFileName, &geom.m_meshFileType); - if (!success) return false; // warning printed + if (!success) + { + // warning printed + return false; + } geom.m_meshScale.setValue(1,1,1); if (shape->Attribute("scale")) From 923fbe858851be28e5c523283b5ba2bdeb0333d8 Mon Sep 17 00:00:00 2001 From: Jie Tan Date: Fri, 10 Mar 2017 11:22:38 -0800 Subject: [PATCH 21/66] add gym examples --- .../gym/cartpole_bullet_gym_example.py | 31 ++++ examples/pybullet/gym/envs/__init__.py | 17 +++ examples/pybullet/gym/envs/bullet/__init__.py | 2 + .../gym/envs/bullet/cartpole_bullet.py | 94 ++++++++++++ examples/pybullet/gym/envs/bullet/minitaur.py | 142 ++++++++++++++++++ .../gym/envs/bullet/minitaur_bullet.py | 90 +++++++++++ .../gym/minitaurWalk_bullet_gym_example.py | 27 ++++ .../gym/minitaur_bullet_gym_example.py | 27 ++++ 8 files changed, 430 insertions(+) create mode 100644 examples/pybullet/gym/cartpole_bullet_gym_example.py create mode 100644 examples/pybullet/gym/envs/__init__.py create mode 100644 examples/pybullet/gym/envs/bullet/__init__.py create mode 100644 examples/pybullet/gym/envs/bullet/cartpole_bullet.py create mode 100644 examples/pybullet/gym/envs/bullet/minitaur.py create mode 100644 examples/pybullet/gym/envs/bullet/minitaur_bullet.py create mode 100644 examples/pybullet/gym/minitaurWalk_bullet_gym_example.py create mode 100644 examples/pybullet/gym/minitaur_bullet_gym_example.py diff --git a/examples/pybullet/gym/cartpole_bullet_gym_example.py b/examples/pybullet/gym/cartpole_bullet_gym_example.py new file mode 100644 index 000000000..52cdab258 --- /dev/null +++ b/examples/pybullet/gym/cartpole_bullet_gym_example.py @@ -0,0 +1,31 @@ +"""One-line documentation for gym_example module. + +A detailed description of gym_example. +""" + +import gym +from envs.bullet.cartpole_bullet import CartPoleBulletEnv +import setuptools +import time +import numpy as np + + +w = [0.3, 0.02, 0.02, 0.012] + +def main(): + env = gym.make('CartPoleBulletEnv-v0') + for i_episode in range(1): + observation = env.reset() + done = False + t = 0 + while not done: + print(observation) + action = np.array([np.inner(observation, w)]) + print(action) + observation, reward, done, info = env.step(action) + t = t + 1 + if done: + print("Episode finished after {} timesteps".format(t+1)) + break + +main() diff --git a/examples/pybullet/gym/envs/__init__.py b/examples/pybullet/gym/envs/__init__.py new file mode 100644 index 000000000..605d5e531 --- /dev/null +++ b/examples/pybullet/gym/envs/__init__.py @@ -0,0 +1,17 @@ +from gym.envs.registration import registry, register, make, spec + +# ------------bullet------------- + +register( + id='CartPoleBulletEnv-v0', + entry_point='envs.bullet:CartPoleBulletEnv', + timestep_limit=1000, + reward_threshold=950.0, +) + +register( + id='MinitaurBulletEnv-v0', + entry_point='envs.bullet:MinitaurBulletEnv', + timestep_limit=1000, + reward_threshold=5.0, +) diff --git a/examples/pybullet/gym/envs/bullet/__init__.py b/examples/pybullet/gym/envs/bullet/__init__.py new file mode 100644 index 000000000..25da62f87 --- /dev/null +++ b/examples/pybullet/gym/envs/bullet/__init__.py @@ -0,0 +1,2 @@ +from envs.bullet.cartpole_bullet import CartPoleBulletEnv +from envs.bullet.minitaur_bullet import MinitaurBulletEnv diff --git a/examples/pybullet/gym/envs/bullet/cartpole_bullet.py b/examples/pybullet/gym/envs/bullet/cartpole_bullet.py new file mode 100644 index 000000000..bf0d85ab9 --- /dev/null +++ b/examples/pybullet/gym/envs/bullet/cartpole_bullet.py @@ -0,0 +1,94 @@ +""" +Classic cart-pole system implemented by Rich Sutton et al. +Copied from https://webdocs.cs.ualberta.ca/~sutton/book/code/pole.c +""" +import os +import logging +import math +import gym +from gym import spaces +from gym.utils import seeding +import numpy as np +import time +import subprocess +import pybullet as p + + +logger = logging.getLogger(__name__) + +class CartPoleBulletEnv(gym.Env): + metadata = { + 'render.modes': ['human', 'rgb_array'], + 'video.frames_per_second' : 50 + } + + def __init__(self): + # start the bullet physics server +# cmdStartBulletServer=['/Users/jietan/Projects/bullet3/build_cmake_python3/examples/SharedMemory/App_SharedMemoryPhysics_GUI'] +# subprocess.Popen(cmdStartBulletServer) + # wait to make sure that the physics server is ready +# time.sleep(1) + # connect to the physics server +# p.connect(p.SHARED_MEMORY) + p.connect(p.GUI) + observation_high = np.array([ + np.finfo(np.float32).max, + np.finfo(np.float32).max, + np.finfo(np.float32).max, + np.finfo(np.float32).max]) + action_high = np.array([0.1]) + + self.action_space = spaces.Box(-action_high, action_high) + self.observation_space = spaces.Box(-observation_high, observation_high) + + self.theta_threshold_radians = 1 + self.x_threshold = 2.4 + self._seed() +# self.reset() + self.viewer = None + self._configure() + + def _configure(self, display=None): + self.display = display + + def _seed(self, seed=None): + self.np_random, seed = seeding.np_random(seed) + return [seed] + + def _step(self, action): + p.stepSimulation() +# time.sleep(self.timeStep) + self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2] + theta, theta_dot, x, x_dot = self.state + force = action + p.setJointMotorControl2(self.cartpole, 0, p.VELOCITY_CONTROL, targetVelocity=(action + self.state[3])) + + done = x < -self.x_threshold \ + or x > self.x_threshold \ + or theta < -self.theta_threshold_radians \ + or theta > self.theta_threshold_radians + reward = 1.0 + + return np.array(self.state), reward, done, {} + + def _reset(self): +# print("-----------reset simulation---------------") + p.resetSimulation() + self.cartpole = p.loadURDF("cartpole.urdf",[0,0,0]) + self.timeStep = 0.01 + p.setJointMotorControl2(self.cartpole, 1, p.VELOCITY_CONTROL, force=0) + p.setGravity(0,0, -10) + p.setTimeStep(self.timeStep) + p.setRealTimeSimulation(0) + + initialCartPos = self.np_random.uniform(low=-0.5, high=0.5, size=(1,)) + initialAngle = self.np_random.uniform(low=-0.5, high=0.5, size=(1,)) + p.resetJointState(self.cartpole, 1, initialAngle) + p.resetJointState(self.cartpole, 0, initialCartPos) + + self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2] + + return np.array(self.state) + + def _render(self, mode='human', close=False): + return diff --git a/examples/pybullet/gym/envs/bullet/minitaur.py b/examples/pybullet/gym/envs/bullet/minitaur.py new file mode 100644 index 000000000..74ddedf84 --- /dev/null +++ b/examples/pybullet/gym/envs/bullet/minitaur.py @@ -0,0 +1,142 @@ +import pybullet as p +import numpy as np + +class Minitaur: + def __init__(self, urdfRootPath=''): + self.urdfRootPath = urdfRootPath + self.reset() + + def applyAction(self, motorCommands): + motorCommandsWithDir = np.multiply(motorCommands, self.motorDir) + for i in range(self.nMotors): + self.setMotorAngleById(self.motorIdList[i], motorCommandsWithDir[i]) + + def getObservation(self): + observation = [] + observation.extend(self.getMotorAngles().tolist()) + observation.extend(self.getMotorVelocities().tolist()) + observation.extend(self.getMotorTorques().tolist()) + observation.extend(list(self.getBaseOrientation())) + observation.extend(list(self.getBasePosition())) + return observation + + def getActionDimension(self): + return self.nMotors + + def getObservationDimension(self): + return len(self.getObservation()) + + def buildJointNameToIdDict(self): + nJoints = p.getNumJoints(self.quadruped) + self.jointNameToId = {} + for i in range(nJoints): + jointInfo = p.getJointInfo(self.quadruped, i) + self.jointNameToId[jointInfo[1].decode('UTF-8')] = jointInfo[0] + self.resetPose() + for i in range(100): + p.stepSimulation() + + def buildMotorIdList(self): + self.motorIdList.append(self.jointNameToId['motor_front_leftR_joint']) + self.motorIdList.append(self.jointNameToId['motor_front_leftL_joint']) + self.motorIdList.append(self.jointNameToId['motor_back_leftR_joint']) + self.motorIdList.append(self.jointNameToId['motor_back_leftL_joint']) + self.motorIdList.append(self.jointNameToId['motor_front_rightL_joint']) + self.motorIdList.append(self.jointNameToId['motor_front_rightR_joint']) + self.motorIdList.append(self.jointNameToId['motor_back_rightL_joint']) + self.motorIdList.append(self.jointNameToId['motor_back_rightR_joint']) + + + def reset(self): + self.quadruped = p.loadURDF("%s/quadruped/quadruped.urdf" % self.urdfRootPath,0,0,.3) + self.kp = 1 + self.kd = 0.1 + self.maxForce = 3.5 + self.nMotors = 8 + self.motorIdList = [] + self.motorDir = [1, -1, 1, -1, -1, 1, -1, 1] + self.buildJointNameToIdDict() + self.buildMotorIdList() + + + def disableAllMotors(self): + nJoints = p.getNumJoints(self.quadruped) + for i in range(nJoints): + p.setJointMotorControl2(bodyIndex=self.quadruped, jointIndex=i, controlMode=p.VELOCITY_CONTROL, force=0) + + def setMotorAngleById(self, motorId, desiredAngle): + p.setJointMotorControl2(bodyIndex=self.quadruped, jointIndex=motorId, controlMode=p.POSITION_CONTROL, targetPosition=desiredAngle, positionGain=self.kp, velocityGain=self.kd, force=self.maxForce) + + def setMotorAngleByName(self, motorName, desiredAngle): + self.setMotorAngleById(self.jointNameToId[motorName], desiredAngle) + + + def resetPose(self): + #right front leg + self.disableAllMotors() + p.resetJointState(self.quadruped,self.jointNameToId['motor_front_rightR_joint'],1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_front_rightR_link'],-2.2) + p.resetJointState(self.quadruped,self.jointNameToId['motor_front_rightL_joint'],-1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_front_rightL_link'],2.2) + p.createConstraint(self.quadruped,self.jointNameToId['knee_front_rightR_link'],self.quadruped,self.jointNameToId['knee_front_rightL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2]) + self.setMotorAngleByName('motor_front_rightR_joint', 1.57) + self.setMotorAngleByName('motor_front_rightL_joint',-1.57) + + #left front leg + p.resetJointState(self.quadruped,self.jointNameToId['motor_front_leftR_joint'],1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_front_leftR_link'],-2.2) + p.resetJointState(self.quadruped,self.jointNameToId['motor_front_leftL_joint'],-1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_front_leftL_link'],2.2) + p.createConstraint(self.quadruped,self.jointNameToId['knee_front_leftR_link'],self.quadruped,self.jointNameToId['knee_front_leftL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2]) + self.setMotorAngleByName('motor_front_leftR_joint', 1.57) + self.setMotorAngleByName('motor_front_leftL_joint',-1.57) + + #right back leg + p.resetJointState(self.quadruped,self.jointNameToId['motor_back_rightR_joint'],1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_back_rightR_link'],-2.2) + p.resetJointState(self.quadruped,self.jointNameToId['motor_back_rightL_joint'],-1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_back_rightL_link'],2.2) + p.createConstraint(self.quadruped,self.jointNameToId['knee_back_rightR_link'],self.quadruped,self.jointNameToId['knee_back_rightL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2]) + self.setMotorAngleByName('motor_back_rightR_joint', 1.57) + self.setMotorAngleByName('motor_back_rightL_joint',-1.57) + + #left back leg + p.resetJointState(self.quadruped,self.jointNameToId['motor_back_leftR_joint'],1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_back_leftR_link'],-2.2) + p.resetJointState(self.quadruped,self.jointNameToId['motor_back_leftL_joint'],-1.57) + p.resetJointState(self.quadruped,self.jointNameToId['knee_back_leftL_link'],2.2) + p.createConstraint(self.quadruped,self.jointNameToId['knee_back_leftR_link'],self.quadruped,self.jointNameToId['knee_back_leftL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2]) + self.setMotorAngleByName('motor_back_leftR_joint', 1.57) + self.setMotorAngleByName('motor_back_leftL_joint',-1.57) + + def getBasePosition(self): + position, orientation = p.getBasePositionAndOrientation(self.quadruped) + return position + + def getBaseOrientation(self): + position, orientation = p.getBasePositionAndOrientation(self.quadruped) + return orientation + + def getMotorAngles(self): + motorAngles = [] + for i in range(self.nMotors): + jointState = p.getJointState(self.quadruped, self.motorIdList[i]) + motorAngles.append(jointState[0]) + motorAngles = np.multiply(motorAngles, self.motorDir) + return motorAngles + + def getMotorVelocities(self): + motorVelocities = [] + for i in range(self.nMotors): + jointState = p.getJointState(self.quadruped, self.motorIdList[i]) + motorVelocities.append(jointState[1]) + motorVelocities = np.multiply(motorVelocities, self.motorDir) + return motorVelocities + + def getMotorTorques(self): + motorTorques = [] + for i in range(self.nMotors): + jointState = p.getJointState(self.quadruped, self.motorIdList[i]) + motorTorques.append(jointState[3]) + motorTorques = np.multiply(motorTorques, self.motorDir) + return motorTorques diff --git a/examples/pybullet/gym/envs/bullet/minitaur_bullet.py b/examples/pybullet/gym/envs/bullet/minitaur_bullet.py new file mode 100644 index 000000000..cd4d5f658 --- /dev/null +++ b/examples/pybullet/gym/envs/bullet/minitaur_bullet.py @@ -0,0 +1,90 @@ +import math +import gym +from gym import spaces +from gym.utils import seeding +import numpy as np +import time + +import pybullet as p +from envs.bullet.minitaur import Minitaur + +class MinitaurBulletEnv(gym.Env): + metadata = { + 'render.modes': ['human', 'rgb_array'], + 'video.frames_per_second' : 50 + } + + def __init__(self): + self._timeStep = 0.01 + self._observation = [] + self._envStepCounter = 0 + self._lastBasePosition = [0, 0, 0] + + p.connect(p.GUI) + + p.resetSimulation() + p.setTimeStep(self._timeStep) + p.loadURDF("plane.urdf") + p.setGravity(0,0,-10) + self._minitaur = Minitaur() + + observationDim = self._minitaur.getObservationDimension() + observation_high = np.array([np.finfo(np.float32).max] * observationDim) + actionDim = 8 + action_high = np.array([math.pi / 2.0] * actionDim) + self.action_space = spaces.Box(-action_high, action_high) + self.observation_space = spaces.Box(-observation_high, observation_high) + + self._seed() + self.reset() + self.viewer = None + + def __del__(self): + p.disconnect() + + def _seed(self, seed=None): + self.np_random, seed = seeding.np_random(seed) + return [seed] + + def _step(self, action): + if len(action) != self._minitaur.getActionDimension(): + raise ValueError("We expect {} continuous action not {}.".format(self._minitaur.getActionDimension(), len(actions.continuous_actions))) + + for i in range(len(action)): + if not -math.pi/2 <= action[i] <= math.pi/2: + raise ValueError("{}th action should be between -1 and 1 not {}.".format(i, action[i])) + action[i] += math.pi / 2 + + self._minitaur.applyAction(action) + p.stepSimulation() + self._observation = self._minitaur.getObservation() + self._envStepCounter += 1 + reward = self._reward() + done = self._termination() + return np.array(self._observation), reward, done, {} + + def _reset(self): + p.resetSimulation() + p.setTimeStep(self._timeStep) + p.loadURDF("plane.urdf") + p.setGravity(0,0,-10) + self._minitaur = Minitaur() + self._observation = self._minitaur.getObservation() + + def _render(self, mode='human', close=False): + return + + def is_fallen(self): + orientation = self._minitaur.getBaseOrientation() + rotMat = p.getMatrixFromQuaternion(orientation) + localUp = rotMat[6:] + return np.dot(np.asarray([0, 0, 1]), np.asarray(localUp)) < 0 + + def _termination(self): + return self.is_fallen() + + def _reward(self): + currentBasePosition = self._minitaur.getBasePosition() + reward = np.dot(np.asarray([-1, 0, 0]), np.asarray(currentBasePosition) - np.asarray(self._lastBasePosition)) + self._lastBasePosition = currentBasePosition + return reward diff --git a/examples/pybullet/gym/minitaurWalk_bullet_gym_example.py b/examples/pybullet/gym/minitaurWalk_bullet_gym_example.py new file mode 100644 index 000000000..4da575341 --- /dev/null +++ b/examples/pybullet/gym/minitaurWalk_bullet_gym_example.py @@ -0,0 +1,27 @@ +"""One-line documentation for gym_example module. + +A detailed description of gym_example. +""" + +import gym +from envs.bullet.minitaur import MinitaurWalkEnv +import setuptools +import time +import numpy as np + + +def main(): + env = gym.make('MinitaurWalkEnv-v0') + for i_episode in range(1): + observation = env.reset() + done = False + while not done: + print(observation) + action = np.array([1.3, 0, 0, 0, 1.3, 0, 0, 0, 1.3, 3.14, 0, 0, 1.3, 3.14, 0, 0]) + print(action) + observation, reward, done, info = env.step(action) + if done: + print("Episode finished after {} timesteps".format(t+1)) + break + +main() diff --git a/examples/pybullet/gym/minitaur_bullet_gym_example.py b/examples/pybullet/gym/minitaur_bullet_gym_example.py new file mode 100644 index 000000000..18c70d43e --- /dev/null +++ b/examples/pybullet/gym/minitaur_bullet_gym_example.py @@ -0,0 +1,27 @@ +import gym +import numpy as np +import math + +from envs.bullet.minitaur_bullet import MinitaurBulletEnv + +def main(): + environment = gym.make('MinitaurBulletEnv-v0') + sum_reward = 0 + steps = 1000 + amplitude = 0.5 + speed = 0.3 + + for stepCounter in range(steps): + a1 = math.sin(stepCounter*speed)*amplitude + a2 = math.sin(stepCounter*speed+3.14)*amplitude + action = [a1, 0, a2, 0, 0, a1, 0, a2] + state, reward, done, info = environment.step(action) + sum_reward += reward + print(state) + if done: + environment.reset() + average_reward = sum_reward / steps + print("avg reward: ", average_reward) + + +main() From 37a809f5d14f56314ea86b394b9d301b7c880d29 Mon Sep 17 00:00:00 2001 From: Jie Tan Date: Fri, 10 Mar 2017 12:29:47 -0800 Subject: [PATCH 22/66] added the learning algorithm from RL-lab --- .../gym/envs/bullet/cartpole_bullet.py | 7 +-- .../gym/minitaur_bullet_gym_example.py | 27 ---------- .../pybullet/gym/trpo_cartpole_bullet_gym.py | 51 +++++++++++++++++++ .../gym/trpo_tf_cartpole_bullet_gym.py | 48 +++++++++++++++++ 4 files changed, 100 insertions(+), 33 deletions(-) delete mode 100644 examples/pybullet/gym/minitaur_bullet_gym_example.py create mode 100644 examples/pybullet/gym/trpo_cartpole_bullet_gym.py create mode 100644 examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py diff --git a/examples/pybullet/gym/envs/bullet/cartpole_bullet.py b/examples/pybullet/gym/envs/bullet/cartpole_bullet.py index bf0d85ab9..b1f1a1e35 100644 --- a/examples/pybullet/gym/envs/bullet/cartpole_bullet.py +++ b/examples/pybullet/gym/envs/bullet/cartpole_bullet.py @@ -24,13 +24,8 @@ class CartPoleBulletEnv(gym.Env): def __init__(self): # start the bullet physics server -# cmdStartBulletServer=['/Users/jietan/Projects/bullet3/build_cmake_python3/examples/SharedMemory/App_SharedMemoryPhysics_GUI'] -# subprocess.Popen(cmdStartBulletServer) - # wait to make sure that the physics server is ready -# time.sleep(1) - # connect to the physics server -# p.connect(p.SHARED_MEMORY) p.connect(p.GUI) +# p.connect(p.DIRECT) observation_high = np.array([ np.finfo(np.float32).max, np.finfo(np.float32).max, diff --git a/examples/pybullet/gym/minitaur_bullet_gym_example.py b/examples/pybullet/gym/minitaur_bullet_gym_example.py deleted file mode 100644 index 18c70d43e..000000000 --- a/examples/pybullet/gym/minitaur_bullet_gym_example.py +++ /dev/null @@ -1,27 +0,0 @@ -import gym -import numpy as np -import math - -from envs.bullet.minitaur_bullet import MinitaurBulletEnv - -def main(): - environment = gym.make('MinitaurBulletEnv-v0') - sum_reward = 0 - steps = 1000 - amplitude = 0.5 - speed = 0.3 - - for stepCounter in range(steps): - a1 = math.sin(stepCounter*speed)*amplitude - a2 = math.sin(stepCounter*speed+3.14)*amplitude - action = [a1, 0, a2, 0, 0, a1, 0, a2] - state, reward, done, info = environment.step(action) - sum_reward += reward - print(state) - if done: - environment.reset() - average_reward = sum_reward / steps - print("avg reward: ", average_reward) - - -main() diff --git a/examples/pybullet/gym/trpo_cartpole_bullet_gym.py b/examples/pybullet/gym/trpo_cartpole_bullet_gym.py new file mode 100644 index 000000000..4c257cf6b --- /dev/null +++ b/examples/pybullet/gym/trpo_cartpole_bullet_gym.py @@ -0,0 +1,51 @@ +from envs.bullet.cartpole_bullet import CartPoleBulletEnv +from rllab.algos.trpo import TRPO +from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline +from rllab.envs.gym_env import GymEnv +from rllab.envs.normalized_env import normalize +from rllab.misc.instrument import stub, run_experiment_lite +from rllab.policies.gaussian_mlp_policy import GaussianMLPPolicy +import subprocess +import time + +stub(globals()) + +env = normalize(GymEnv("CartPoleBulletEnv-v0")) + +policy = GaussianMLPPolicy( + env_spec=env.spec, + # The neural network policy should have two hidden layers, each with 32 hidden units. + hidden_sizes=(8,) +) + +baseline = LinearFeatureBaseline(env_spec=env.spec) + +algo = TRPO( + env=env, + policy=policy, + baseline=baseline, + batch_size=5000, + max_path_length=env.horizon, + n_itr=50, + discount=0.999, + step_size=0.01, + # Uncomment both lines (this and the plot parameter below) to enable plotting +# plot=True, +) + +#cmdStartBulletServer=['~/Projects/rllab/bullet_examples/run_physics_server.sh'] +#subprocess.Popen(cmdStartBulletServer, shell=True) +#time.sleep(1) + + +run_experiment_lite( + algo.train(), + # Number of parallel workers for sampling + n_parallel=1, + # Only keep the snapshot parameters for the last iteration + snapshot_mode="last", + # Specifies the seed for the experiment. If this is not provided, a random seed + # will be used + seed=1, + # plot=True, +) diff --git a/examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py b/examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py new file mode 100644 index 000000000..0e6c1353b --- /dev/null +++ b/examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py @@ -0,0 +1,48 @@ +from envs.bullet.cartpole_bullet import CartPoleBulletEnv +from sandbox.rocky.tf.algos.trpo import TRPO +from sandbox.rocky.tf.policies.gaussian_mlp_policy import GaussianMLPPolicy +from sandbox.rocky.tf.envs.base import TfEnv + +from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline +from rllab.envs.gym_env import GymEnv +from rllab.envs.normalized_env import normalize +from rllab.misc.instrument import stub, run_experiment_lite + +stub(globals()) + +env = TfEnv(normalize(GymEnv("CartPoleBulletEnv-v0"))) + +policy = GaussianMLPPolicy( + name = "tf_gaussian_mlp", + env_spec=env.spec, + # The neural network policy should have two hidden layers, each with 32 hidden units. + hidden_sizes=(8,) +) + +baseline = LinearFeatureBaseline(env_spec=env.spec) + +algo = TRPO( + env=env, + policy=policy, + baseline=baseline, + batch_size=5000, + max_path_length=env.horizon, + n_itr=50, + discount=0.999, + step_size=0.01, + force_batch_sampler=True, + # Uncomment both lines (this and the plot parameter below) to enable plotting + #plot=True, +) + +run_experiment_lite( + algo.train(), + # Number of parallel workers for sampling + n_parallel=1, + # Only keep the snapshot parameters for the last iteration + snapshot_mode="last", + # Specifies the seed for the experiment. If this is not provided, a random seed + # will be used + seed=1, + #plot=True, +) From 8c27a62e042cbf444c829f4ae97d9d3bdabaff51 Mon Sep 17 00:00:00 2001 From: Jie Tan Date: Fri, 10 Mar 2017 13:41:05 -0800 Subject: [PATCH 23/66] remove the stub calls from rllab --- .../gym/minitaurWalk_bullet_gym_example.py | 27 ------------------- .../pybullet/gym/trpo_cartpole_bullet_gym.py | 22 +-------------- .../gym/trpo_tf_cartpole_bullet_gym.py | 15 +---------- 3 files changed, 2 insertions(+), 62 deletions(-) delete mode 100644 examples/pybullet/gym/minitaurWalk_bullet_gym_example.py diff --git a/examples/pybullet/gym/minitaurWalk_bullet_gym_example.py b/examples/pybullet/gym/minitaurWalk_bullet_gym_example.py deleted file mode 100644 index 4da575341..000000000 --- a/examples/pybullet/gym/minitaurWalk_bullet_gym_example.py +++ /dev/null @@ -1,27 +0,0 @@ -"""One-line documentation for gym_example module. - -A detailed description of gym_example. -""" - -import gym -from envs.bullet.minitaur import MinitaurWalkEnv -import setuptools -import time -import numpy as np - - -def main(): - env = gym.make('MinitaurWalkEnv-v0') - for i_episode in range(1): - observation = env.reset() - done = False - while not done: - print(observation) - action = np.array([1.3, 0, 0, 0, 1.3, 0, 0, 0, 1.3, 3.14, 0, 0, 1.3, 3.14, 0, 0]) - print(action) - observation, reward, done, info = env.step(action) - if done: - print("Episode finished after {} timesteps".format(t+1)) - break - -main() diff --git a/examples/pybullet/gym/trpo_cartpole_bullet_gym.py b/examples/pybullet/gym/trpo_cartpole_bullet_gym.py index 4c257cf6b..bac943217 100644 --- a/examples/pybullet/gym/trpo_cartpole_bullet_gym.py +++ b/examples/pybullet/gym/trpo_cartpole_bullet_gym.py @@ -3,12 +3,7 @@ from rllab.algos.trpo import TRPO from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline from rllab.envs.gym_env import GymEnv from rllab.envs.normalized_env import normalize -from rllab.misc.instrument import stub, run_experiment_lite from rllab.policies.gaussian_mlp_policy import GaussianMLPPolicy -import subprocess -import time - -stub(globals()) env = normalize(GymEnv("CartPoleBulletEnv-v0")) @@ -33,19 +28,4 @@ algo = TRPO( # plot=True, ) -#cmdStartBulletServer=['~/Projects/rllab/bullet_examples/run_physics_server.sh'] -#subprocess.Popen(cmdStartBulletServer, shell=True) -#time.sleep(1) - - -run_experiment_lite( - algo.train(), - # Number of parallel workers for sampling - n_parallel=1, - # Only keep the snapshot parameters for the last iteration - snapshot_mode="last", - # Specifies the seed for the experiment. If this is not provided, a random seed - # will be used - seed=1, - # plot=True, -) +algo.train() diff --git a/examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py b/examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py index 0e6c1353b..6e055be15 100644 --- a/examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py +++ b/examples/pybullet/gym/trpo_tf_cartpole_bullet_gym.py @@ -6,9 +6,6 @@ from sandbox.rocky.tf.envs.base import TfEnv from rllab.baselines.linear_feature_baseline import LinearFeatureBaseline from rllab.envs.gym_env import GymEnv from rllab.envs.normalized_env import normalize -from rllab.misc.instrument import stub, run_experiment_lite - -stub(globals()) env = TfEnv(normalize(GymEnv("CartPoleBulletEnv-v0"))) @@ -35,14 +32,4 @@ algo = TRPO( #plot=True, ) -run_experiment_lite( - algo.train(), - # Number of parallel workers for sampling - n_parallel=1, - # Only keep the snapshot parameters for the last iteration - snapshot_mode="last", - # Specifies the seed for the experiment. If this is not provided, a random seed - # will be used - seed=1, - #plot=True, -) +algo.train() From 953bc0d3e7a61fe7ed021907c41fede1ffc2e8a6 Mon Sep 17 00:00:00 2001 From: Szabolcs Dombi Date: Mon, 13 Mar 2017 18:00:35 +0100 Subject: [PATCH 24/66] float to btScalar --- src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp | 4 ++-- src/BulletDynamics/Featherstone/btMultiBody.cpp | 2 +- src/BulletDynamics/Featherstone/btMultiBody.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp b/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp index 09b7388b6..0572256f7 100644 --- a/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp @@ -642,7 +642,7 @@ void btConeTwistConstraint::calcAngleInfo2(const btTransform& transA, const btTr btTransform trDeltaAB = trB * trPose * trA.inverse(); btQuaternion qDeltaAB = trDeltaAB.getRotation(); btVector3 swingAxis = btVector3(qDeltaAB.x(), qDeltaAB.y(), qDeltaAB.z()); - float swingAxisLen2 = swingAxis.length2(); + btScalar swingAxisLen2 = swingAxis.length2(); if(btFuzzyZero(swingAxisLen2)) { return; @@ -903,7 +903,7 @@ btVector3 btConeTwistConstraint::GetPointForAngle(btScalar fAngleInRadians, btSc // a^2 b^2 // Do the math and it should be clear. - float swingLimit = m_swingSpan1; // if xEllipse == 0, just use axis b (1) + btScalar swingLimit = m_swingSpan1; // if xEllipse == 0, just use axis b (1) if (fabs(xEllipse) > SIMD_EPSILON) { btScalar surfaceSlope2 = (yEllipse*yEllipse)/(xEllipse*xEllipse); diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index dd5f253b6..c14aa2aea 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -1238,7 +1238,7 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar -void btMultiBody::solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, float result[6]) const +void btMultiBody::solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, btScalar result[6]) const { int num_links = getNumLinks(); ///solve I * x = rhs, so the result = invI * rhs diff --git a/src/BulletDynamics/Featherstone/btMultiBody.h b/src/BulletDynamics/Featherstone/btMultiBody.h index c3a4bb8c1..b36d0e4e8 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.h +++ b/src/BulletDynamics/Featherstone/btMultiBody.h @@ -616,7 +616,7 @@ private: void operator=(const btMultiBody &); // not implemented - void solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, float result[6]) const; + void solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, btScalar result[6]) const; void solveImatrix(const btSpatialForceVector &rhs, btSpatialMotionVector &result) const; void updateLinksDofOffsets() From 41c5a2e9723565c125b55adc324ce5370e31be21 Mon Sep 17 00:00:00 2001 From: Szabolcs Dombi Date: Mon, 13 Mar 2017 18:23:25 +0100 Subject: [PATCH 25/66] sinf -> btSin and acosf -> btAcos --- src/BulletDynamics/Character/btKinematicCharacterController.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/BulletDynamics/Character/btKinematicCharacterController.cpp b/src/BulletDynamics/Character/btKinematicCharacterController.cpp index 339bb6fc1..06429f349 100644 --- a/src/BulletDynamics/Character/btKinematicCharacterController.cpp +++ b/src/BulletDynamics/Character/btKinematicCharacterController.cpp @@ -657,7 +657,7 @@ void btKinematicCharacterController::setLinearVelocity(const btVector3& velocity if (c != 0) { //there is a component in walkdirection for vertical velocity - btVector3 upComponent = m_up * (sinf(SIMD_HALF_PI - acosf(c)) * m_walkDirection.length()); + btVector3 upComponent = m_up * (btSin(SIMD_HALF_PI - btAcos(c)) * m_walkDirection.length()); m_walkDirection -= upComponent; m_verticalVelocity = (c < 0.0f ? -1 : 1) * upComponent.length(); From 3052477c6784906443d2f84d4f155dffa8f89d6d Mon Sep 17 00:00:00 2001 From: Szabolcs Dombi Date: Mon, 13 Mar 2017 18:27:57 +0100 Subject: [PATCH 26/66] cast vertex data (btScalar) to float --- src/BulletSoftBody/btDefaultSoftBodySolver.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp index e90d24e6e..9c2040307 100644 --- a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp +++ b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp @@ -100,9 +100,9 @@ void btDefaultSoftBodySolver::copySoftBodyToVertexBuffer( const btSoftBody *cons for( int vertexIndex = 0; vertexIndex < numVertices; ++vertexIndex ) { btVector3 position = clothVertices[vertexIndex].m_x; - *(vertexPointer + 0) = position.getX(); - *(vertexPointer + 1) = position.getY(); - *(vertexPointer + 2) = position.getZ(); + *(vertexPointer + 0) = (float)position.getX(); + *(vertexPointer + 1) = (float)position.getY(); + *(vertexPointer + 2) = (float)position.getZ(); vertexPointer += vertexStride; } } @@ -115,9 +115,9 @@ void btDefaultSoftBodySolver::copySoftBodyToVertexBuffer( const btSoftBody *cons for( int vertexIndex = 0; vertexIndex < numVertices; ++vertexIndex ) { btVector3 normal = clothVertices[vertexIndex].m_n; - *(normalPointer + 0) = normal.getX(); - *(normalPointer + 1) = normal.getY(); - *(normalPointer + 2) = normal.getZ(); + *(normalPointer + 0) = (float)normal.getX(); + *(normalPointer + 1) = (float)normal.getY(); + *(normalPointer + 2) = (float)normal.getZ(); normalPointer += normalStride; } } From 839086ac84e852e30af2250f49e1970d09322fa5 Mon Sep 17 00:00:00 2001 From: Szabolcs Dombi Date: Mon, 13 Mar 2017 18:30:44 +0100 Subject: [PATCH 27/66] fix type conversion warnings --- src/LinearMath/btQuickprof.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/LinearMath/btQuickprof.cpp b/src/LinearMath/btQuickprof.cpp index 16ca88cdc..4ca51cc23 100644 --- a/src/LinearMath/btQuickprof.cpp +++ b/src/LinearMath/btQuickprof.cpp @@ -218,7 +218,7 @@ unsigned long long int btClock::getTimeNanoseconds() QueryPerformanceCounter(¤tTime); elapsedTime.QuadPart = currentTime.QuadPart - m_data->mStartTime.QuadPart; - elapsedTime.QuadPart *= 1e9; + elapsedTime.QuadPart *= 1000000000; elapsedTime.QuadPart /= m_data->mClockFrequency.QuadPart; return (unsigned long long) elapsedTime.QuadPart; @@ -287,7 +287,7 @@ static btClock gProfileClock; inline void Profile_Get_Ticks(unsigned long int * ticks) { - *ticks = gProfileClock.getTimeMicroseconds(); + *ticks = (unsigned long int)gProfileClock.getTimeMicroseconds(); } inline float Profile_Get_Tick_Rate(void) From 43b0a8b6fb3017fa14b2e9e8af8f095fc314683c Mon Sep 17 00:00:00 2001 From: Mohi Date: Mon, 13 Mar 2017 10:38:02 -0700 Subject: [PATCH 28/66] Fixing a bug on Visualizer Camera and a few more - resetDebugVisualizerCamera now accepts negative values for pitch and yaw angles - Defining kitchen model to be concave, so as to be able to put floating objects inside - Fixed an indention error in testrender_np.py --- data/kitchens/1.sdf | 346 ++++++++++++++--------------- examples/pybullet/pybullet.c | 6 +- examples/pybullet/testrender_np.py | 4 +- 3 files changed, 178 insertions(+), 178 deletions(-) diff --git a/data/kitchens/1.sdf b/data/kitchens/1.sdf index 5f1046837..0bf6112e9 100644 --- a/data/kitchens/1.sdf +++ b/data/kitchens/1.sdf @@ -16,7 +16,7 @@ 0.166667 - + .1 .1 .1 @@ -55,7 +55,7 @@ 0.166667 - + .1 .1 .1 @@ -94,7 +94,7 @@ 0.166667 - + .1 .1 .1 @@ -133,7 +133,7 @@ 0.166667 - + .1 .1 .1 @@ -172,7 +172,7 @@ 0.166667 - + .1 .1 .1 @@ -211,7 +211,7 @@ 0.166667 - + .1 .1 .1 @@ -250,7 +250,7 @@ 0.166667 - + .1 .1 .1 @@ -289,7 +289,7 @@ 0.166667 - + .1 .1 .1 @@ -328,7 +328,7 @@ 0.166667 - + .1 .1 .1 @@ -367,7 +367,7 @@ 0.166667 - + .1 .1 .1 @@ -406,7 +406,7 @@ 0.166667 - + .1 .1 .1 @@ -445,7 +445,7 @@ 0.166667 - + .1 .1 .1 @@ -484,7 +484,7 @@ 0.166667 - + .1 .1 .1 @@ -523,7 +523,7 @@ 0.166667 - + .1 .1 .1 @@ -562,7 +562,7 @@ 0.166667 - + .1 .1 .1 @@ -601,7 +601,7 @@ 0.166667 - + .1 .1 .1 @@ -640,7 +640,7 @@ 0.166667 - + .1 .1 .1 @@ -679,7 +679,7 @@ 0.166667 - + .1 .1 .1 @@ -718,7 +718,7 @@ 0.166667 - + .1 .1 .1 @@ -757,7 +757,7 @@ 0.166667 - + .1 .1 .1 @@ -796,7 +796,7 @@ 0.166667 - + .1 .1 .1 @@ -835,7 +835,7 @@ 0.166667 - + .1 .1 .1 @@ -874,7 +874,7 @@ 0.166667 - + .1 .1 .1 @@ -913,7 +913,7 @@ 0.166667 - + .1 .1 .1 @@ -952,7 +952,7 @@ 0.166667 - + .1 .1 .1 @@ -991,7 +991,7 @@ 0.166667 - + .1 .1 .1 @@ -1030,7 +1030,7 @@ 0.166667 - + .1 .1 .1 @@ -1069,7 +1069,7 @@ 0.166667 - + .1 .1 .1 @@ -1108,7 +1108,7 @@ 0.166667 - + .1 .1 .1 @@ -1147,7 +1147,7 @@ 0.166667 - + .1 .1 .1 @@ -1186,7 +1186,7 @@ 0.166667 - + .1 .1 .1 @@ -1225,7 +1225,7 @@ 0.166667 - + .1 .1 .1 @@ -1264,7 +1264,7 @@ 0.166667 - + .1 .1 .1 @@ -1303,7 +1303,7 @@ 0.166667 - + .1 .1 .1 @@ -1342,7 +1342,7 @@ 0.166667 - + .1 .1 .1 @@ -1381,7 +1381,7 @@ 0.166667 - + .1 .1 .1 @@ -1420,7 +1420,7 @@ 0.166667 - + .1 .1 .1 @@ -1459,7 +1459,7 @@ 0.166667 - + .1 .1 .1 @@ -1498,7 +1498,7 @@ 0.166667 - + .1 .1 .1 @@ -1537,7 +1537,7 @@ 0.166667 - + .1 .1 .1 @@ -1576,7 +1576,7 @@ 0.166667 - + .1 .1 .1 @@ -1615,7 +1615,7 @@ 0.166667 - + .1 .1 .1 @@ -1654,7 +1654,7 @@ 0.166667 - + .1 .1 .1 @@ -1693,7 +1693,7 @@ 0.166667 - + .1 .1 .1 @@ -1732,7 +1732,7 @@ 0.166667 - + .1 .1 .1 @@ -1771,7 +1771,7 @@ 0.166667 - + .1 .1 .1 @@ -1810,7 +1810,7 @@ 0.166667 - + .1 .1 .1 @@ -1849,7 +1849,7 @@ 0.166667 - + .1 .1 .1 @@ -1888,7 +1888,7 @@ 0.166667 - + .1 .1 .1 @@ -1927,7 +1927,7 @@ 0.166667 - + .1 .1 .1 @@ -1966,7 +1966,7 @@ 0.166667 - + .1 .1 .1 @@ -2005,7 +2005,7 @@ 0.166667 - + .1 .1 .1 @@ -2044,7 +2044,7 @@ 0.166667 - + .1 .1 .1 @@ -2083,7 +2083,7 @@ 0.166667 - + .1 .1 .1 @@ -2122,7 +2122,7 @@ 0.166667 - + .1 .1 .1 @@ -2161,7 +2161,7 @@ 0.166667 - + .1 .1 .1 @@ -2200,7 +2200,7 @@ 0.166667 - + .1 .1 .1 @@ -2239,7 +2239,7 @@ 0.166667 - + .1 .1 .1 @@ -2278,7 +2278,7 @@ 0.166667 - + .1 .1 .1 @@ -2317,7 +2317,7 @@ 0.166667 - + .1 .1 .1 @@ -2356,7 +2356,7 @@ 0.166667 - + .1 .1 .1 @@ -2395,7 +2395,7 @@ 0.166667 - + .1 .1 .1 @@ -2434,7 +2434,7 @@ 0.166667 - + .1 .1 .1 @@ -2473,7 +2473,7 @@ 0.166667 - + .1 .1 .1 @@ -2512,7 +2512,7 @@ 0.166667 - + .1 .1 .1 @@ -2551,7 +2551,7 @@ 0.166667 - + .1 .1 .1 @@ -2590,7 +2590,7 @@ 0.166667 - + .1 .1 .1 @@ -2629,7 +2629,7 @@ 0.166667 - + .1 .1 .1 @@ -2668,7 +2668,7 @@ 0.166667 - + .1 .1 .1 @@ -2707,7 +2707,7 @@ 0.166667 - + .1 .1 .1 @@ -2746,7 +2746,7 @@ 0.166667 - + .1 .1 .1 @@ -2785,7 +2785,7 @@ 0.166667 - + .1 .1 .1 @@ -2824,7 +2824,7 @@ 0.166667 - + .1 .1 .1 @@ -2863,7 +2863,7 @@ 0.166667 - + .1 .1 .1 @@ -2902,7 +2902,7 @@ 0.166667 - + .1 .1 .1 @@ -2941,7 +2941,7 @@ 0.166667 - + .1 .1 .1 @@ -2980,7 +2980,7 @@ 0.166667 - + .1 .1 .1 @@ -3019,7 +3019,7 @@ 0.166667 - + .1 .1 .1 @@ -3058,7 +3058,7 @@ 0.166667 - + .1 .1 .1 @@ -3097,7 +3097,7 @@ 0.166667 - + .1 .1 .1 @@ -3136,7 +3136,7 @@ 0.166667 - + .1 .1 .1 @@ -3175,7 +3175,7 @@ 0.166667 - + .1 .1 .1 @@ -3214,7 +3214,7 @@ 0.166667 - + .1 .1 .1 @@ -3253,7 +3253,7 @@ 0.166667 - + .1 .1 .1 @@ -3292,7 +3292,7 @@ 0.166667 - + .1 .1 .1 @@ -3331,7 +3331,7 @@ 0.166667 - + .1 .1 .1 @@ -3370,7 +3370,7 @@ 0.166667 - + .1 .1 .1 @@ -3409,7 +3409,7 @@ 0.166667 - + .1 .1 .1 @@ -3448,7 +3448,7 @@ 0.166667 - + .1 .1 .1 @@ -3487,7 +3487,7 @@ 0.166667 - + .1 .1 .1 @@ -3526,7 +3526,7 @@ 0.166667 - + .1 .1 .1 @@ -3565,7 +3565,7 @@ 0.166667 - + .1 .1 .1 @@ -3604,7 +3604,7 @@ 0.166667 - + .1 .1 .1 @@ -3643,7 +3643,7 @@ 0.166667 - + .1 .1 .1 @@ -3682,7 +3682,7 @@ 0.166667 - + .1 .1 .1 @@ -3721,7 +3721,7 @@ 0.166667 - + .1 .1 .1 @@ -3760,7 +3760,7 @@ 0.166667 - + .1 .1 .1 @@ -3799,7 +3799,7 @@ 0.166667 - + .1 .1 .1 @@ -3838,7 +3838,7 @@ 0.166667 - + .1 .1 .1 @@ -3877,7 +3877,7 @@ 0.166667 - + .1 .1 .1 @@ -3916,7 +3916,7 @@ 0.166667 - + .1 .1 .1 @@ -3955,7 +3955,7 @@ 0.166667 - + .1 .1 .1 @@ -3994,7 +3994,7 @@ 0.166667 - + .1 .1 .1 @@ -4033,7 +4033,7 @@ 0.166667 - + .1 .1 .1 @@ -4072,7 +4072,7 @@ 0.166667 - + .1 .1 .1 @@ -4111,7 +4111,7 @@ 0.166667 - + .1 .1 .1 @@ -4150,7 +4150,7 @@ 0.166667 - + .1 .1 .1 @@ -4189,7 +4189,7 @@ 0.166667 - + .1 .1 .1 @@ -4228,7 +4228,7 @@ 0.166667 - + .1 .1 .1 @@ -4267,7 +4267,7 @@ 0.166667 - + .1 .1 .1 @@ -4306,7 +4306,7 @@ 0.166667 - + .1 .1 .1 @@ -4345,7 +4345,7 @@ 0.166667 - + .1 .1 .1 @@ -4384,7 +4384,7 @@ 0.166667 - + .1 .1 .1 @@ -4423,7 +4423,7 @@ 0.166667 - + .1 .1 .1 @@ -4462,7 +4462,7 @@ 0.166667 - + .1 .1 .1 @@ -4501,7 +4501,7 @@ 0.166667 - + .1 .1 .1 @@ -4540,7 +4540,7 @@ 0.166667 - + .1 .1 .1 @@ -4579,7 +4579,7 @@ 0.166667 - + .1 .1 .1 @@ -4618,7 +4618,7 @@ 0.166667 - + .1 .1 .1 @@ -4657,7 +4657,7 @@ 0.166667 - + .1 .1 .1 @@ -4696,7 +4696,7 @@ 0.166667 - + .1 .1 .1 @@ -4735,7 +4735,7 @@ 0.166667 - + .1 .1 .1 @@ -4774,7 +4774,7 @@ 0.166667 - + .1 .1 .1 @@ -4813,7 +4813,7 @@ 0.166667 - + .1 .1 .1 @@ -4852,7 +4852,7 @@ 0.166667 - + .1 .1 .1 @@ -4891,7 +4891,7 @@ 0.166667 - + .1 .1 .1 @@ -4930,7 +4930,7 @@ 0.166667 - + .1 .1 .1 @@ -4969,7 +4969,7 @@ 0.166667 - + .1 .1 .1 @@ -5008,7 +5008,7 @@ 0.166667 - + .1 .1 .1 @@ -5047,7 +5047,7 @@ 0.166667 - + .1 .1 .1 @@ -5086,7 +5086,7 @@ 0.166667 - + .1 .1 .1 @@ -5125,7 +5125,7 @@ 0.166667 - + .1 .1 .1 @@ -5164,7 +5164,7 @@ 0.166667 - + .1 .1 .1 @@ -5203,7 +5203,7 @@ 0.166667 - + .1 .1 .1 @@ -5242,7 +5242,7 @@ 0.166667 - + .1 .1 .1 @@ -5281,7 +5281,7 @@ 0.166667 - + .1 .1 .1 @@ -5320,7 +5320,7 @@ 0.166667 - + .1 .1 .1 @@ -5359,7 +5359,7 @@ 0.166667 - + .1 .1 .1 @@ -5398,7 +5398,7 @@ 0.166667 - + .1 .1 .1 @@ -5437,7 +5437,7 @@ 0.166667 - + .1 .1 .1 @@ -5476,7 +5476,7 @@ 0.166667 - + .1 .1 .1 @@ -5515,7 +5515,7 @@ 0.166667 - + .1 .1 .1 @@ -5554,7 +5554,7 @@ 0.166667 - + .1 .1 .1 @@ -5593,7 +5593,7 @@ 0.166667 - + .1 .1 .1 @@ -5632,7 +5632,7 @@ 0.166667 - + .1 .1 .1 @@ -5671,7 +5671,7 @@ 0.166667 - + .1 .1 .1 @@ -5741,7 +5741,7 @@ 0.166667 - + .1 .1 .1 @@ -5780,7 +5780,7 @@ 0.166667 - + .1 .1 .1 @@ -5819,7 +5819,7 @@ 0.166667 - + .1 .1 .1 @@ -5858,7 +5858,7 @@ 0.166667 - + .1 .1 .1 @@ -5897,7 +5897,7 @@ 0.166667 - + .1 .1 .1 @@ -5936,7 +5936,7 @@ 0.166667 - + .1 .1 .1 @@ -5975,7 +5975,7 @@ 0.166667 - + .1 .1 .1 @@ -6014,7 +6014,7 @@ 0.166667 - + .1 .1 .1 @@ -6053,7 +6053,7 @@ 0.166667 - + .1 .1 .1 @@ -6092,7 +6092,7 @@ 0.166667 - + .1 .1 .1 @@ -6131,7 +6131,7 @@ 0.166667 - + .1 .1 .1 @@ -6170,7 +6170,7 @@ 0.166667 - + .1 .1 .1 @@ -6209,7 +6209,7 @@ 0.166667 - + .1 .1 .1 @@ -6248,7 +6248,7 @@ 0.166667 - + .1 .1 .1 @@ -6287,7 +6287,7 @@ 0.166667 - + .1 .1 .1 @@ -6326,7 +6326,7 @@ 0.166667 - + .1 .1 .1 @@ -6365,7 +6365,7 @@ 0.166667 - + .1 .1 .1 @@ -6404,7 +6404,7 @@ 0.166667 - + .1 .1 .1 @@ -6443,7 +6443,7 @@ 0.166667 - + .1 .1 .1 @@ -6482,7 +6482,7 @@ 0.166667 - + .1 .1 .1 @@ -6521,7 +6521,7 @@ 0.166667 - + .1 .1 .1 @@ -6560,7 +6560,7 @@ 0.166667 - + .1 .1 .1 @@ -6599,7 +6599,7 @@ 0.166667 - + .1 .1 .1 @@ -6638,7 +6638,7 @@ 0.166667 - + .1 .1 .1 @@ -6677,7 +6677,7 @@ 0.166667 - + .1 .1 .1 @@ -6716,7 +6716,7 @@ 0.166667 - + .1 .1 .1 @@ -6755,7 +6755,7 @@ 0.166667 - + .1 .1 .1 diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index c0465f7fb..1566dfc9f 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -3055,8 +3055,8 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg static PyObject* pybullet_resetDebugVisualizerCamera(PyObject* self, PyObject* args, PyObject *keywds) { float cameraDistance = -1; - float cameraYaw = -1; - float cameraPitch = -1; + float cameraYaw = 35; + float cameraPitch = 50; PyObject* cameraTargetPosObj=0; int physicsClientId = 0; @@ -3076,7 +3076,7 @@ static PyObject* pybullet_resetDebugVisualizerCamera(PyObject* self, PyObject* a { b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(sm); - if ((cameraDistance>=0) && (cameraYaw>=0) && (cameraPitch>=0)) + if ((cameraDistance>=0)) { float cameraTargetPosition[3]; if (pybullet_internalSetVector(cameraTargetPosObj,cameraTargetPosition)) diff --git a/examples/pybullet/testrender_np.py b/examples/pybullet/testrender_np.py index c008da09f..9f84fbed9 100644 --- a/examples/pybullet/testrender_np.py +++ b/examples/pybullet/testrender_np.py @@ -43,8 +43,8 @@ for pitch in range (0,360,10) : print ('width = %d height = %d' % (w,h)) #note that sending the data to matplotlib is really slow - - plt.imshow(rgb,interpolation='none') + + plt.imshow(rgb,interpolation='none') plt.pause(0.001) main_stop = time.time() From e36b7e02aacd3d2bf0485d5ebb4570aab7938bc8 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 13 Mar 2017 11:00:56 -0700 Subject: [PATCH 29/66] Fix for issue 1007 _clang-format file and applied to HelloWorld.cpp usage: clang-format -style=file -i examples/HelloWorld/HelloWorld.cpp THere are still some issues with clang-format and its style --- _clang-format | 90 ++++++++++++++++++++++++++++++ examples/HelloWorld/HelloWorld.cpp | 66 ++++++++++------------ 2 files changed, 120 insertions(+), 36 deletions(-) create mode 100644 _clang-format diff --git a/_clang-format b/_clang-format new file mode 100644 index 000000000..d1841d577 --- /dev/null +++ b/_clang-format @@ -0,0 +1,90 @@ +--- +Language: Cpp +# BasedOnStyle: Google +AccessModifierOffset: -1 +AlignAfterOpenBracket: Align +AlignConsecutiveAssignments: false +AlignConsecutiveDeclarations: false +AlignEscapedNewlinesLeft: true +AlignOperands: true +AlignTrailingComments: true +AllowAllParametersOfDeclarationOnNextLine: true +AllowShortBlocksOnASingleLine: false +AllowShortCaseLabelsOnASingleLine: false +AllowShortFunctionsOnASingleLine: All +AllowShortIfStatementsOnASingleLine: true +AllowShortLoopsOnASingleLine: true +AlwaysBreakAfterDefinitionReturnType: None +AlwaysBreakAfterReturnType: None +AlwaysBreakBeforeMultilineStrings: true +AlwaysBreakTemplateDeclarations: true +BinPackArguments: true +BinPackParameters: true +BraceWrapping: + AfterClass: false + AfterControlStatement: false + AfterEnum: false + AfterFunction: false + AfterNamespace: false + AfterObjCDeclaration: false + AfterStruct: false + AfterUnion: false + BeforeCatch: false + BeforeElse: false + IndentBraces: false +BreakBeforeBinaryOperators: None +BreakBeforeBraces: Allman +BreakBeforeTernaryOperators: true +BreakConstructorInitializersBeforeComma: false +ColumnLimit: 0 +CommentPragmas: '^ IWYU pragma:' +ConstructorInitializerAllOnOneLineOrOnePerLine: true +ConstructorInitializerIndentWidth: 4 +ContinuationIndentWidth: 4 +Cpp11BracedListStyle: true +DerivePointerAlignment: true +DisableFormat: false +ExperimentalAutoDetectBinPacking: false +ForEachMacros: [ foreach, Q_FOREACH, BOOST_FOREACH ] +IncludeCategories: + - Regex: '^<.*\.h>' + Priority: 1 + - Regex: '^<.*' + Priority: 2 + - Regex: '.*' + Priority: 3 +IndentCaseLabels: true +IndentWidth: 4 +IndentWrappedFunctionNames: false +KeepEmptyLinesAtTheStartOfBlocks: false +MacroBlockBegin: '' +MacroBlockEnd: '' +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCBlockIndentWidth: 2 +ObjCSpaceAfterProperty: false +ObjCSpaceBeforeProtocolList: false +PenaltyBreakBeforeFirstCallParameter: 1 +PenaltyBreakComment: 300 +PenaltyBreakFirstLessLess: 120 +PenaltyBreakString: 1000 +PenaltyExcessCharacter: 1000000 +PenaltyReturnTypeOnItsOwnLine: 200 +PointerAlignment: Left +ReflowComments: false +SortIncludes: false +SpaceAfterCStyleCast: false +SpaceBeforeAssignmentOperators: true +SpaceBeforeParens: ControlStatements +SpaceInEmptyParentheses: false +SpacesBeforeTrailingComments: 2 +SpacesInAngles: false +SpacesInContainerLiterals: true +SpacesInCStyleCastParentheses: false +SpacesInParentheses: false +SpacesInSquareBrackets: false +Standard: Auto +TabWidth: 4 +UseTab: Always +... + diff --git a/examples/HelloWorld/HelloWorld.cpp b/examples/HelloWorld/HelloWorld.cpp index e51e6d541..e897bcdd3 100644 --- a/examples/HelloWorld/HelloWorld.cpp +++ b/examples/HelloWorld/HelloWorld.cpp @@ -30,7 +30,7 @@ int main(int argc, char** argv) btDefaultCollisionConfiguration* collisionConfiguration = new btDefaultCollisionConfiguration(); ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) - btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collisionConfiguration); + btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collisionConfiguration); ///btDbvtBroadphase is a good general purpose broadphase. You can also try out btAxis3Sweep. btBroadphaseInterface* overlappingPairCache = new btDbvtBroadphase(); @@ -38,9 +38,9 @@ int main(int argc, char** argv) ///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded) btSequentialImpulseConstraintSolver* solver = new btSequentialImpulseConstraintSolver; - btDiscreteDynamicsWorld* dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,overlappingPairCache,solver,collisionConfiguration); + btDiscreteDynamicsWorld* dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher, overlappingPairCache, solver, collisionConfiguration); - dynamicsWorld->setGravity(btVector3(0,-10,0)); + dynamicsWorld->setGravity(btVector3(0, -10, 0)); ///-----initialization_end----- @@ -48,39 +48,37 @@ int main(int argc, char** argv) //make sure to re-use collision shapes among rigid bodies whenever possible! btAlignedObjectArray collisionShapes; - ///create a few basic rigid bodies //the ground is a cube of side 100 at position y = -56. //the sphere will hit it at y = -6, with center at -5 { - btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.))); + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.), btScalar(50.), btScalar(50.))); collisionShapes.push_back(groundShape); btTransform groundTransform; groundTransform.setIdentity(); - groundTransform.setOrigin(btVector3(0,-56,0)); + groundTransform.setOrigin(btVector3(0, -56, 0)); btScalar mass(0.); //rigidbody is dynamic if and only if mass is non zero, otherwise static bool isDynamic = (mass != 0.f); - btVector3 localInertia(0,0,0); + btVector3 localInertia(0, 0, 0); if (isDynamic) - groundShape->calculateLocalInertia(mass,localInertia); + groundShape->calculateLocalInertia(mass, localInertia); //using motionstate is optional, it provides interpolation capabilities, and only synchronizes 'active' objects btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); - btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,groundShape,localInertia); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); btRigidBody* body = new btRigidBody(rbInfo); //add the body to the dynamics world dynamicsWorld->addRigidBody(body); } - { //create a dynamic rigidbody @@ -92,37 +90,34 @@ int main(int argc, char** argv) btTransform startTransform; startTransform.setIdentity(); - btScalar mass(1.f); + btScalar mass(1.f); //rigidbody is dynamic if and only if mass is non zero, otherwise static bool isDynamic = (mass != 0.f); - btVector3 localInertia(0,0,0); + btVector3 localInertia(0, 0, 0); if (isDynamic) - colShape->calculateLocalInertia(mass,localInertia); + colShape->calculateLocalInertia(mass, localInertia); - startTransform.setOrigin(btVector3(2,10,0)); - - //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects - btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform); - btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia); - btRigidBody* body = new btRigidBody(rbInfo); + startTransform.setOrigin(btVector3(2, 10, 0)); - dynamicsWorld->addRigidBody(body); + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, colShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + + dynamicsWorld->addRigidBody(body); } - - -/// Do some simulation - + /// Do some simulation ///-----stepsimulation_start----- - for (i=0;i<150;i++) + for (i = 0; i < 150; i++) { - dynamicsWorld->stepSimulation(1.f/60.f,10); - + dynamicsWorld->stepSimulation(1.f / 60.f, 10); + //print positions of all objects - for (int j=dynamicsWorld->getNumCollisionObjects()-1; j>=0 ;j--) + for (int j = dynamicsWorld->getNumCollisionObjects() - 1; j >= 0; j--) { btCollisionObject* obj = dynamicsWorld->getCollisionObjectArray()[j]; btRigidBody* body = btRigidBody::upcast(obj); @@ -130,23 +125,23 @@ int main(int argc, char** argv) if (body && body->getMotionState()) { body->getMotionState()->getWorldTransform(trans); - - } else + } + else { trans = obj->getWorldTransform(); } - printf("world pos object %d = %f,%f,%f\n",j,float(trans.getOrigin().getX()),float(trans.getOrigin().getY()),float(trans.getOrigin().getZ())); + printf("world pos object %d = %f,%f,%f\n", j, float(trans.getOrigin().getX()), float(trans.getOrigin().getY()), float(trans.getOrigin().getZ())); } } ///-----stepsimulation_end----- //cleanup in the reverse order of creation/initialization - + ///-----cleanup_start----- //remove the rigidbodies from the dynamics world and delete them - for (i=dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--) + for (i = dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) { btCollisionObject* obj = dynamicsWorld->getCollisionObjectArray()[i]; btRigidBody* body = btRigidBody::upcast(obj); @@ -154,12 +149,12 @@ int main(int argc, char** argv) { delete body->getMotionState(); } - dynamicsWorld->removeCollisionObject( obj ); + dynamicsWorld->removeCollisionObject(obj); delete obj; } //delete collision shapes - for (int j=0;j Date: Mon, 13 Mar 2017 11:17:42 -0700 Subject: [PATCH 30/66] apply _clang-format to Bullet/src/LinearMath/btScalar.h, disable around preprocessor defines (issue with clang-format lacking preprocessor indentation support, see https://bugs.llvm.org//show_bug.cgi?id=17362 and possibly apply this patch: https://github.com/mkurdej/clang/tree/indent-pp-directives ) --- src/LinearMath/btScalar.h | 1003 +++++++++++++++++++------------------ 1 file changed, 504 insertions(+), 499 deletions(-) diff --git a/src/LinearMath/btScalar.h b/src/LinearMath/btScalar.h index b101d7416..054652255 100644 --- a/src/LinearMath/btScalar.h +++ b/src/LinearMath/btScalar.h @@ -12,59 +12,54 @@ subject to the following restrictions: 3. This notice may not be removed or altered from any source distribution. */ - - #ifndef BT_SCALAR_H #define BT_SCALAR_H - #ifdef BT_MANAGED_CODE //Aligned data types not supported in managed code #pragma unmanaged #endif - #include -#include //size_t for MSVC 6.0 +#include //size_t for MSVC 6.0 #include /* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/ #define BT_BULLET_VERSION 286 -inline int btGetVersion() +inline int btGetVersion() { return BT_BULLET_VERSION; } +// clang and most formatting tools don't support indentation of preprocessor guards, so turn it off +// clang-format off #if defined(DEBUG) || defined (_DEBUG) -#define BT_DEBUG + #define BT_DEBUG #endif - #ifdef _WIN32 - - #if defined(__MINGW32__) || defined(__CYGWIN__) || (defined (_MSC_VER) && _MSC_VER < 1300) - - #define SIMD_FORCE_INLINE inline - #define ATTRIBUTE_ALIGNED16(a) a - #define ATTRIBUTE_ALIGNED64(a) a - #define ATTRIBUTE_ALIGNED128(a) a - #elif defined(_M_ARM) - #define SIMD_FORCE_INLINE __forceinline - #define ATTRIBUTE_ALIGNED16(a) __declspec() a - #define ATTRIBUTE_ALIGNED64(a) __declspec() a - #define ATTRIBUTE_ALIGNED128(a) __declspec () a - #else - //#define BT_HAS_ALIGNED_ALLOCATOR - #pragma warning(disable : 4324) // disable padding warning + #if defined(__MINGW32__) || defined(__CYGWIN__) || (defined (_MSC_VER) && _MSC_VER < 1300) + #define SIMD_FORCE_INLINE inline + #define ATTRIBUTE_ALIGNED16(a) a + #define ATTRIBUTE_ALIGNED64(a) a + #define ATTRIBUTE_ALIGNED128(a) a + #elif defined(_M_ARM) + #define SIMD_FORCE_INLINE __forceinline + #define ATTRIBUTE_ALIGNED16(a) __declspec() a + #define ATTRIBUTE_ALIGNED64(a) __declspec() a + #define ATTRIBUTE_ALIGNED128(a) __declspec () a + #else//__MINGW32__ + //#define BT_HAS_ALIGNED_ALLOCATOR + #pragma warning(disable : 4324) // disable padding warning // #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning. - #pragma warning(disable:4996) //Turn off warnings about deprecated C routines + #pragma warning(disable:4996) //Turn off warnings about deprecated C routines // #pragma warning(disable:4786) // Disable the "debug name too long" warning - #define SIMD_FORCE_INLINE __forceinline - #define ATTRIBUTE_ALIGNED16(a) __declspec(align(16)) a - #define ATTRIBUTE_ALIGNED64(a) __declspec(align(64)) a - #define ATTRIBUTE_ALIGNED128(a) __declspec (align(128)) a + #define SIMD_FORCE_INLINE __forceinline + #define ATTRIBUTE_ALIGNED16(a) __declspec(align(16)) a + #define ATTRIBUTE_ALIGNED64(a) __declspec(align(64)) a + #define ATTRIBUTE_ALIGNED128(a) __declspec (align(128)) a #ifdef _XBOX #define BT_USE_VMX128 @@ -100,28 +95,28 @@ inline int btGetVersion() #endif//_XBOX - #endif //__MINGW32__ + #endif //__MINGW32__ -#ifdef BT_DEBUG - #ifdef _MSC_VER - #include - #define btAssert(x) { if(!(x)){printf("Assert "__FILE__ ":%u (%s)\n", __LINE__, #x);__debugbreak(); }} - #else//_MSC_VER - #include - #define btAssert assert - #endif//_MSC_VER -#else + #ifdef BT_DEBUG + #ifdef _MSC_VER + #include + #define btAssert(x) { if(!(x)){printf("Assert "__FILE__ ":%u (%s)\n", __LINE__, #x);__debugbreak(); }} + #else//_MSC_VER + #include + #define btAssert assert + #endif//_MSC_VER + #else #define btAssert(x) -#endif + #endif //btFullAssert is optional, slows down a lot #define btFullAssert(x) #define btLikely(_c) _c #define btUnlikely(_c) _c -#else +#else//_WIN32 -#if defined (__CELLOS_LV2__) + #if defined (__CELLOS_LV2__) #define SIMD_FORCE_INLINE inline __attribute__((always_inline)) #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) @@ -129,217 +124,249 @@ inline int btGetVersion() #ifndef assert #include #endif -#ifdef BT_DEBUG -#ifdef __SPU__ -#include -#define printf spu_printf - #define btAssert(x) {if(!(x)){printf("Assert "__FILE__ ":%u ("#x")\n", __LINE__);spu_hcmpeq(0,0);}} -#else - #define btAssert assert -#endif + #ifdef BT_DEBUG + #ifdef __SPU__ + #include + #define printf spu_printf + #define btAssert(x) {if(!(x)){printf("Assert "__FILE__ ":%u ("#x")\n", __LINE__);spu_hcmpeq(0,0);}} + #else + #define btAssert assert + #endif -#else - #define btAssert(x) -#endif + #else//BT_DEBUG + #define btAssert(x) + #endif//BT_DEBUG //btFullAssert is optional, slows down a lot #define btFullAssert(x) #define btLikely(_c) _c #define btUnlikely(_c) _c -#else + #else//defined (__CELLOS_LV2__) -#ifdef USE_LIBSPE2 + #ifdef USE_LIBSPE2 - #define SIMD_FORCE_INLINE __inline - #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) - #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) - #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128))) - #ifndef assert - #include - #endif -#ifdef BT_DEBUG - #define btAssert assert -#else - #define btAssert(x) -#endif - //btFullAssert is optional, slows down a lot - #define btFullAssert(x) + #define SIMD_FORCE_INLINE __inline + #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) + #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) + #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128))) + #ifndef assert + #include + #endif + #ifdef BT_DEBUG + #define btAssert assert + #else + #define btAssert(x) + #endif + //btFullAssert is optional, slows down a lot + #define btFullAssert(x) - #define btLikely(_c) __builtin_expect((_c), 1) - #define btUnlikely(_c) __builtin_expect((_c), 0) + #define btLikely(_c) __builtin_expect((_c), 1) + #define btUnlikely(_c) __builtin_expect((_c), 0) -#else + #else//USE_LIBSPE2 //non-windows systems -#if (defined (__APPLE__) && (!defined (BT_USE_DOUBLE_PRECISION))) - #if defined (__i386__) || defined (__x86_64__) - #define BT_USE_SIMD_VECTOR3 - #define BT_USE_SSE - //BT_USE_SSE_IN_API is enabled on Mac OSX by default, because memory is automatically aligned on 16-byte boundaries - //if apps run into issues, we will disable the next line - #define BT_USE_SSE_IN_API - #ifdef BT_USE_SSE - // include appropriate SSE level - #if defined (__SSE4_1__) - #include - #elif defined (__SSSE3__) - #include - #elif defined (__SSE3__) - #include - #else - #include - #endif - #endif //BT_USE_SSE - #elif defined( __ARM_NEON__ ) - #ifdef __clang__ - #define BT_USE_NEON 1 - #define BT_USE_SIMD_VECTOR3 + #if (defined (__APPLE__) && (!defined (BT_USE_DOUBLE_PRECISION))) + #if defined (__i386__) || defined (__x86_64__) + #define BT_USE_SIMD_VECTOR3 + #define BT_USE_SSE + //BT_USE_SSE_IN_API is enabled on Mac OSX by default, because memory is automatically aligned on 16-byte boundaries + //if apps run into issues, we will disable the next line + #define BT_USE_SSE_IN_API + #ifdef BT_USE_SSE + // include appropriate SSE level + #if defined (__SSE4_1__) + #include + #elif defined (__SSSE3__) + #include + #elif defined (__SSE3__) + #include + #else + #include + #endif + #endif //BT_USE_SSE + #elif defined( __ARM_NEON__ ) + #ifdef __clang__ + #define BT_USE_NEON 1 + #define BT_USE_SIMD_VECTOR3 - #if defined BT_USE_NEON && defined (__clang__) - #include - #endif//BT_USE_NEON - #endif //__clang__ - #endif//__arm__ + #if defined BT_USE_NEON && defined (__clang__) + #include + #endif//BT_USE_NEON + #endif //__clang__ + #endif//__arm__ - #define SIMD_FORCE_INLINE inline __attribute__ ((always_inline)) -///@todo: check out alignment methods for other platforms/compilers - #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) - #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) - #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128))) - #ifndef assert - #include - #endif + #define SIMD_FORCE_INLINE inline __attribute__ ((always_inline)) + ///@todo: check out alignment methods for other platforms/compilers + #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) + #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) + #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128))) + #ifndef assert + #include + #endif - #if defined(DEBUG) || defined (_DEBUG) - #if defined (__i386__) || defined (__x86_64__) - #include - #define btAssert(x)\ - {\ - if(!(x))\ - {\ - printf("Assert %s in line %d, file %s\n",#x, __LINE__, __FILE__);\ - asm volatile ("int3");\ - }\ - } - #else//defined (__i386__) || defined (__x86_64__) - #define btAssert assert - #endif//defined (__i386__) || defined (__x86_64__) - #else//defined(DEBUG) || defined (_DEBUG) - #define btAssert(x) - #endif//defined(DEBUG) || defined (_DEBUG) + #if defined(DEBUG) || defined (_DEBUG) + #if defined (__i386__) || defined (__x86_64__) + #include + #define btAssert(x)\ + {\ + if(!(x))\ + {\ + printf("Assert %s in line %d, file %s\n",#x, __LINE__, __FILE__);\ + asm volatile ("int3");\ + }\ + } + #else//defined (__i386__) || defined (__x86_64__) + #define btAssert assert + #endif//defined (__i386__) || defined (__x86_64__) + #else//defined(DEBUG) || defined (_DEBUG) + #define btAssert(x) + #endif//defined(DEBUG) || defined (_DEBUG) - //btFullAssert is optional, slows down a lot - #define btFullAssert(x) - #define btLikely(_c) _c - #define btUnlikely(_c) _c + //btFullAssert is optional, slows down a lot + #define btFullAssert(x) + #define btLikely(_c) _c + #define btUnlikely(_c) _c -#else + #else//__APPLE__ - #define SIMD_FORCE_INLINE inline - ///@todo: check out alignment methods for other platforms/compilers - ///#define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) - ///#define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) - ///#define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128))) - #define ATTRIBUTE_ALIGNED16(a) a - #define ATTRIBUTE_ALIGNED64(a) a - #define ATTRIBUTE_ALIGNED128(a) a - #ifndef assert - #include - #endif + #define SIMD_FORCE_INLINE inline + ///@todo: check out alignment methods for other platforms/compilers + ///#define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) + ///#define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) + ///#define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128))) + #define ATTRIBUTE_ALIGNED16(a) a + #define ATTRIBUTE_ALIGNED64(a) a + #define ATTRIBUTE_ALIGNED128(a) a + #ifndef assert + #include + #endif -#if defined(DEBUG) || defined (_DEBUG) - #define btAssert assert -#else - #define btAssert(x) -#endif + #if defined(DEBUG) || defined (_DEBUG) + #define btAssert assert + #else + #define btAssert(x) + #endif - //btFullAssert is optional, slows down a lot - #define btFullAssert(x) - #define btLikely(_c) _c - #define btUnlikely(_c) _c -#endif //__APPLE__ - -#endif // LIBSPE2 - -#endif //__CELLOS_LV2__ -#endif + //btFullAssert is optional, slows down a lot + #define btFullAssert(x) + #define btLikely(_c) _c + #define btUnlikely(_c) _c + #endif //__APPLE__ + #endif // LIBSPE2 + #endif //__CELLOS_LV2__ +#endif//_WIN32 ///The btScalar type abstracts floating point numbers, to easily switch between double and single floating point precision. #if defined(BT_USE_DOUBLE_PRECISION) - -typedef double btScalar; -//this number could be bigger in double precision -#define BT_LARGE_FLOAT 1e30 + typedef double btScalar; + //this number could be bigger in double precision + #define BT_LARGE_FLOAT 1e30 #else - -typedef float btScalar; -//keep BT_LARGE_FLOAT*BT_LARGE_FLOAT < FLT_MAX -#define BT_LARGE_FLOAT 1e18f + typedef float btScalar; + //keep BT_LARGE_FLOAT*BT_LARGE_FLOAT < FLT_MAX + #define BT_LARGE_FLOAT 1e18f #endif #ifdef BT_USE_SSE -typedef __m128 btSimdFloat4; -#endif//BT_USE_SSE + typedef __m128 btSimdFloat4; +#endif //BT_USE_SSE -#if defined (BT_USE_SSE) -//#if defined BT_USE_SSE_IN_API && defined (BT_USE_SSE) -#ifdef _WIN32 +#if defined(BT_USE_SSE) + //#if defined BT_USE_SSE_IN_API && defined (BT_USE_SSE) + #ifdef _WIN32 -#ifndef BT_NAN -static int btNanMask = 0x7F800001; -#define BT_NAN (*(float*)&btNanMask) -#endif + #ifndef BT_NAN + static int btNanMask = 0x7F800001; + #define BT_NAN (*(float *)&btNanMask) + #endif -#ifndef BT_INFINITY -static int btInfinityMask = 0x7F800000; -#define BT_INFINITY (*(float*)&btInfinityMask) -inline int btGetInfinityMask()//suppress stupid compiler warning -{ - return btInfinityMask; -} -#endif + #ifndef BT_INFINITY + static int btInfinityMask = 0x7F800000; + #define BT_INFINITY (*(float *)&btInfinityMask) + inline int btGetInfinityMask() //suppress stupid compiler warning + { + return btInfinityMask; + } + #endif -//use this, in case there are clashes (such as xnamath.h) -#ifndef BT_NO_SIMD_OPERATOR_OVERLOADS -inline __m128 operator + (const __m128 A, const __m128 B) -{ - return _mm_add_ps(A, B); -} -inline __m128 operator - (const __m128 A, const __m128 B) -{ - return _mm_sub_ps(A, B); -} -inline __m128 operator * (const __m128 A, const __m128 B) -{ - return _mm_mul_ps(A, B); -} -#endif //BT_NO_SIMD_OPERATOR_OVERLOADS + //use this, in case there are clashes (such as xnamath.h) + #ifndef BT_NO_SIMD_OPERATOR_OVERLOADS + inline __m128 operator+(const __m128 A, const __m128 B) + { + return _mm_add_ps(A, B); + } -#define btCastfTo128i(a) (_mm_castps_si128(a)) -#define btCastfTo128d(a) (_mm_castps_pd(a)) -#define btCastiTo128f(a) (_mm_castsi128_ps(a)) -#define btCastdTo128f(a) (_mm_castpd_ps(a)) -#define btCastdTo128i(a) (_mm_castpd_si128(a)) -#define btAssign128(r0,r1,r2,r3) _mm_setr_ps(r0,r1,r2,r3) + inline __m128 operator-(const __m128 A, const __m128 B) + { + return _mm_sub_ps(A, B); + } -#else//_WIN32 + inline __m128 operator*(const __m128 A, const __m128 B) + { + return _mm_mul_ps(A, B); + } + #endif //BT_NO_SIMD_OPERATOR_OVERLOADS -#define btCastfTo128i(a) ((__m128i)(a)) -#define btCastfTo128d(a) ((__m128d)(a)) -#define btCastiTo128f(a) ((__m128) (a)) -#define btCastdTo128f(a) ((__m128) (a)) -#define btCastdTo128i(a) ((__m128i)(a)) -#define btAssign128(r0,r1,r2,r3) (__m128){r0,r1,r2,r3} -#define BT_INFINITY INFINITY -#define BT_NAN NAN -#endif//_WIN32 -#else + #define btCastfTo128i(a) (_mm_castps_si128(a)) + #define btCastfTo128d(a) (_mm_castps_pd(a)) + #define btCastiTo128f(a) (_mm_castsi128_ps(a)) + #define btCastdTo128f(a) (_mm_castpd_ps(a)) + #define btCastdTo128i(a) (_mm_castpd_si128(a)) + #define btAssign128(r0, r1, r2, r3) _mm_setr_ps(r0, r1, r2, r3) + + #else //_WIN32 + + #define btCastfTo128i(a) ((__m128i)(a)) + #define btCastfTo128d(a) ((__m128d)(a)) + #define btCastiTo128f(a) ((__m128)(a)) + #define btCastdTo128f(a) ((__m128)(a)) + #define btCastdTo128i(a) ((__m128i)(a)) + #define btAssign128(r0, r1, r2, r3) \ + (__m128) { r0, r1, r2, r3 } + #define BT_INFINITY INFINITY + #define BT_NAN NAN + #endif //_WIN32 +#else//BT_USE_SSE + + #ifdef BT_USE_NEON + #include + + typedef float32x4_t btSimdFloat4; + #define BT_INFINITY INFINITY + #define BT_NAN NAN + #define btAssign128(r0, r1, r2, r3) \ + (float32x4_t) { r0, r1, r2, r3 } + #else //BT_USE_NEON + + #ifndef BT_INFINITY + struct btInfMaskConverter + { + union { + float mask; + int intmask; + }; + btInfMaskConverter(int mask = 0x7F800000) + : intmask(mask) + { + } + }; + static btInfMaskConverter btInfinityMask = 0x7F800000; + #define BT_INFINITY (btInfinityMask.mask) + inline int btGetInfinityMask() //suppress stupid compiler warning + { + return btInfinityMask.intmask; + } + #endif + #endif //BT_USE_NEON + +#endif //BT_USE_SSE #ifdef BT_USE_NEON #include @@ -347,193 +374,181 @@ inline __m128 operator * (const __m128 A, const __m128 B) typedef float32x4_t btSimdFloat4; #define BT_INFINITY INFINITY #define BT_NAN NAN - #define btAssign128(r0,r1,r2,r3) (float32x4_t){r0,r1,r2,r3} -#else//BT_USE_NEON - - #ifndef BT_INFINITY - struct btInfMaskConverter - { - union { - float mask; - int intmask; - }; - btInfMaskConverter(int mask=0x7F800000) - :intmask(mask) - { - } - }; - static btInfMaskConverter btInfinityMask = 0x7F800000; - #define BT_INFINITY (btInfinityMask.mask) - inline int btGetInfinityMask()//suppress stupid compiler warning - { - return btInfinityMask.intmask; - } - #endif + #define btAssign128(r0, r1, r2, r3) \ + (float32x4_t) { r0, r1, r2, r3 } #endif//BT_USE_NEON -#endif //BT_USE_SSE - -#ifdef BT_USE_NEON -#include - -typedef float32x4_t btSimdFloat4; -#define BT_INFINITY INFINITY -#define BT_NAN NAN -#define btAssign128(r0,r1,r2,r3) (float32x4_t){r0,r1,r2,r3} -#endif - - - - - -#define BT_DECLARE_ALIGNED_ALLOCATOR() \ - SIMD_FORCE_INLINE void* operator new(size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes,16); } \ - SIMD_FORCE_INLINE void operator delete(void* ptr) { btAlignedFree(ptr); } \ - SIMD_FORCE_INLINE void* operator new(size_t, void* ptr) { return ptr; } \ - SIMD_FORCE_INLINE void operator delete(void*, void*) { } \ - SIMD_FORCE_INLINE void* operator new[](size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes,16); } \ - SIMD_FORCE_INLINE void operator delete[](void* ptr) { btAlignedFree(ptr); } \ - SIMD_FORCE_INLINE void* operator new[](size_t, void* ptr) { return ptr; } \ - SIMD_FORCE_INLINE void operator delete[](void*, void*) { } \ - - +#define BT_DECLARE_ALIGNED_ALLOCATOR() \ + SIMD_FORCE_INLINE void *operator new(size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes, 16); } \ + SIMD_FORCE_INLINE void operator delete(void *ptr) { btAlignedFree(ptr); } \ + SIMD_FORCE_INLINE void *operator new(size_t, void *ptr) { return ptr; } \ + SIMD_FORCE_INLINE void operator delete(void *, void *) {} \ + SIMD_FORCE_INLINE void *operator new[](size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes, 16); } \ + SIMD_FORCE_INLINE void operator delete[](void *ptr) { btAlignedFree(ptr); } \ + SIMD_FORCE_INLINE void *operator new[](size_t, void *ptr) { return ptr; } \ + SIMD_FORCE_INLINE void operator delete[](void *, void *) {} #if defined(BT_USE_DOUBLE_PRECISION) || defined(BT_FORCE_DOUBLE_FUNCTIONS) - -SIMD_FORCE_INLINE btScalar btSqrt(btScalar x) { return sqrt(x); } -SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabs(x); } -SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cos(x); } -SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sin(x); } -SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tan(x); } -SIMD_FORCE_INLINE btScalar btAcos(btScalar x) { if (xbtScalar(1)) x=btScalar(1); return acos(x); } -SIMD_FORCE_INLINE btScalar btAsin(btScalar x) { if (xbtScalar(1)) x=btScalar(1); return asin(x); } -SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atan(x); } -SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2(x, y); } -SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return exp(x); } -SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return log(x); } -SIMD_FORCE_INLINE btScalar btPow(btScalar x,btScalar y) { return pow(x,y); } -SIMD_FORCE_INLINE btScalar btFmod(btScalar x,btScalar y) { return fmod(x,y); } -#else - -SIMD_FORCE_INLINE btScalar btSqrt(btScalar y) -{ -#ifdef USE_APPROXIMATION -#ifdef __LP64__ - float xhalf = 0.5f*y; - int i = *(int*)&y; - i = 0x5f375a86 - (i>>1); - y = *(float*)&i; - y = y*(1.5f - xhalf*y*y); - y = y*(1.5f - xhalf*y*y); - y = y*(1.5f - xhalf*y*y); - y=1/y; - return y; -#else - double x, z, tempf; - unsigned long *tfptr = ((unsigned long *)&tempf) + 1; - tempf = y; - *tfptr = (0xbfcdd90a - *tfptr)>>1; /* estimate of 1/sqrt(y) */ - x = tempf; - z = y*btScalar(0.5); - x = (btScalar(1.5)*x)-(x*x)*(x*z); /* iteration formula */ - x = (btScalar(1.5)*x)-(x*x)*(x*z); - x = (btScalar(1.5)*x)-(x*x)*(x*z); - x = (btScalar(1.5)*x)-(x*x)*(x*z); - x = (btScalar(1.5)*x)-(x*x)*(x*z); - return x*y; -#endif -#else - return sqrtf(y); -#endif -} -SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabsf(x); } -SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cosf(x); } -SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sinf(x); } -SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tanf(x); } -SIMD_FORCE_INLINE btScalar btAcos(btScalar x) { - if (xbtScalar(1)) - x=btScalar(1); - return acosf(x); -} -SIMD_FORCE_INLINE btScalar btAsin(btScalar x) { - if (xbtScalar(1)) - x=btScalar(1); - return asinf(x); -} -SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atanf(x); } -SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2f(x, y); } -SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return expf(x); } -SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return logf(x); } -SIMD_FORCE_INLINE btScalar btPow(btScalar x,btScalar y) { return powf(x,y); } -SIMD_FORCE_INLINE btScalar btFmod(btScalar x,btScalar y) { return fmodf(x,y); } - -#endif + SIMD_FORCE_INLINE btScalar btSqrt(btScalar x) + { + return sqrt(x); + } + SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabs(x); } + SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cos(x); } + SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sin(x); } + SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tan(x); } + SIMD_FORCE_INLINE btScalar btAcos(btScalar x) + { + if (x < btScalar(-1)) x = btScalar(-1); + if (x > btScalar(1)) x = btScalar(1); + return acos(x); + } + SIMD_FORCE_INLINE btScalar btAsin(btScalar x) + { + if (x < btScalar(-1)) x = btScalar(-1); + if (x > btScalar(1)) x = btScalar(1); + return asin(x); + } + SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atan(x); } + SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2(x, y); } + SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return exp(x); } + SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return log(x); } + SIMD_FORCE_INLINE btScalar btPow(btScalar x, btScalar y) { return pow(x, y); } + SIMD_FORCE_INLINE btScalar btFmod(btScalar x, btScalar y) { return fmod(x, y); } -#define SIMD_PI btScalar(3.1415926535897932384626433832795029) -#define SIMD_2_PI (btScalar(2.0) * SIMD_PI) -#define SIMD_HALF_PI (SIMD_PI * btScalar(0.5)) +#else//BT_USE_DOUBLE_PRECISION + + SIMD_FORCE_INLINE btScalar btSqrt(btScalar y) + { + #ifdef USE_APPROXIMATION + #ifdef __LP64__ + float xhalf = 0.5f * y; + int i = *(int *)&y; + i = 0x5f375a86 - (i >> 1); + y = *(float *)&i; + y = y * (1.5f - xhalf * y * y); + y = y * (1.5f - xhalf * y * y); + y = y * (1.5f - xhalf * y * y); + y = 1 / y; + return y; + #else + double x, z, tempf; + unsigned long *tfptr = ((unsigned long *)&tempf) + 1; + tempf = y; + *tfptr = (0xbfcdd90a - *tfptr) >> 1; /* estimate of 1/sqrt(y) */ + x = tempf; + z = y * btScalar(0.5); + x = (btScalar(1.5) * x) - (x * x) * (x * z); /* iteration formula */ + x = (btScalar(1.5) * x) - (x * x) * (x * z); + x = (btScalar(1.5) * x) - (x * x) * (x * z); + x = (btScalar(1.5) * x) - (x * x) * (x * z); + x = (btScalar(1.5) * x) - (x * x) * (x * z); + return x * y; + #endif + #else + return sqrtf(y); + #endif + } + SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabsf(x); } + SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cosf(x); } + SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sinf(x); } + SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tanf(x); } + SIMD_FORCE_INLINE btScalar btAcos(btScalar x) + { + if (x < btScalar(-1)) + x = btScalar(-1); + if (x > btScalar(1)) + x = btScalar(1); + return acosf(x); + } + SIMD_FORCE_INLINE btScalar btAsin(btScalar x) + { + if (x < btScalar(-1)) + x = btScalar(-1); + if (x > btScalar(1)) + x = btScalar(1); + return asinf(x); + } + SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atanf(x); } + SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2f(x, y); } + SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return expf(x); } + SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return logf(x); } + SIMD_FORCE_INLINE btScalar btPow(btScalar x, btScalar y) { return powf(x, y); } + SIMD_FORCE_INLINE btScalar btFmod(btScalar x, btScalar y) { return fmodf(x, y); } + +#endif//BT_USE_DOUBLE_PRECISION + +#define SIMD_PI btScalar(3.1415926535897932384626433832795029) +#define SIMD_2_PI (btScalar(2.0) * SIMD_PI) +#define SIMD_HALF_PI (SIMD_PI * btScalar(0.5)) #define SIMD_RADS_PER_DEG (SIMD_2_PI / btScalar(360.0)) -#define SIMD_DEGS_PER_RAD (btScalar(360.0) / SIMD_2_PI) +#define SIMD_DEGS_PER_RAD (btScalar(360.0) / SIMD_2_PI) #define SIMDSQRT12 btScalar(0.7071067811865475244008443621048490) - -#define btRecipSqrt(x) ((btScalar)(btScalar(1.0)/btSqrt(btScalar(x)))) /* reciprocal square root */ -#define btRecip(x) (btScalar(1.0)/btScalar(x)) +#define btRecipSqrt(x) ((btScalar)(btScalar(1.0) / btSqrt(btScalar(x)))) /* reciprocal square root */ +#define btRecip(x) (btScalar(1.0) / btScalar(x)) #ifdef BT_USE_DOUBLE_PRECISION -#define SIMD_EPSILON DBL_EPSILON -#define SIMD_INFINITY DBL_MAX -#define BT_ONE 1.0 -#define BT_ZERO 0.0 -#define BT_TWO 2.0 -#define BT_HALF 0.5 + #define SIMD_EPSILON DBL_EPSILON + #define SIMD_INFINITY DBL_MAX + #define BT_ONE 1.0 + #define BT_ZERO 0.0 + #define BT_TWO 2.0 + #define BT_HALF 0.5 #else -#define SIMD_EPSILON FLT_EPSILON -#define SIMD_INFINITY FLT_MAX -#define BT_ONE 1.0f -#define BT_ZERO 0.0f -#define BT_TWO 2.0f -#define BT_HALF 0.5f + #define SIMD_EPSILON FLT_EPSILON + #define SIMD_INFINITY FLT_MAX + #define BT_ONE 1.0f + #define BT_ZERO 0.0f + #define BT_TWO 2.0f + #define BT_HALF 0.5f #endif -SIMD_FORCE_INLINE btScalar btAtan2Fast(btScalar y, btScalar x) +// clang-format on + +SIMD_FORCE_INLINE btScalar btAtan2Fast(btScalar y, btScalar x) { btScalar coeff_1 = SIMD_PI / 4.0f; btScalar coeff_2 = 3.0f * coeff_1; btScalar abs_y = btFabs(y); btScalar angle; - if (x >= 0.0f) { + if (x >= 0.0f) + { btScalar r = (x - abs_y) / (x + abs_y); angle = coeff_1 - coeff_1 * r; - } else { + } + else + { btScalar r = (x + abs_y) / (abs_y - x); angle = coeff_2 - coeff_1 * r; } return (y < 0.0f) ? -angle : angle; } -SIMD_FORCE_INLINE bool btFuzzyZero(btScalar x) { return btFabs(x) < SIMD_EPSILON; } +SIMD_FORCE_INLINE bool btFuzzyZero(btScalar x) { return btFabs(x) < SIMD_EPSILON; } -SIMD_FORCE_INLINE bool btEqual(btScalar a, btScalar eps) { +SIMD_FORCE_INLINE bool btEqual(btScalar a, btScalar eps) +{ return (((a) <= eps) && !((a) < -eps)); } -SIMD_FORCE_INLINE bool btGreaterEqual (btScalar a, btScalar eps) { +SIMD_FORCE_INLINE bool btGreaterEqual(btScalar a, btScalar eps) +{ return (!((a) <= eps)); } - -SIMD_FORCE_INLINE int btIsNegative(btScalar x) { - return x < btScalar(0.0) ? 1 : 0; +SIMD_FORCE_INLINE int btIsNegative(btScalar x) +{ + return x < btScalar(0.0) ? 1 : 0; } SIMD_FORCE_INLINE btScalar btRadians(btScalar x) { return x * SIMD_RADS_PER_DEG; } SIMD_FORCE_INLINE btScalar btDegrees(btScalar x) { return x * SIMD_DEGS_PER_RAD; } -#define BT_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name +#define BT_DECLARE_HANDLE(name) \ + typedef struct name##__ \ + { \ + int unused; \ + } * name #ifndef btFsel SIMD_FORCE_INLINE btScalar btFsel(btScalar a, btScalar b, btScalar c) @@ -541,60 +556,57 @@ SIMD_FORCE_INLINE btScalar btFsel(btScalar a, btScalar b, btScalar c) return a >= 0 ? b : c; } #endif -#define btFsels(a,b,c) (btScalar)btFsel(a,b,c) - +#define btFsels(a, b, c) (btScalar) btFsel(a, b, c) SIMD_FORCE_INLINE bool btMachineIsLittleEndian() { - long int i = 1; - const char *p = (const char *) &i; - if (p[0] == 1) // Lowest address contains the least significant byte - return true; - else - return false; + long int i = 1; + const char *p = (const char *)&i; + if (p[0] == 1) // Lowest address contains the least significant byte + return true; + else + return false; } - - ///btSelect avoids branches, which makes performance much better for consoles like Playstation 3 and XBox 360 ///Thanks Phil Knight. See also http://www.cellperformance.com/articles/2006/04/more_techniques_for_eliminatin_1.html -SIMD_FORCE_INLINE unsigned btSelect(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) +SIMD_FORCE_INLINE unsigned btSelect(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) { - // Set testNz to 0xFFFFFFFF if condition is nonzero, 0x00000000 if condition is zero - // Rely on positive value or'ed with its negative having sign bit on - // and zero value or'ed with its negative (which is still zero) having sign bit off - // Use arithmetic shift right, shifting the sign bit through all 32 bits - unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); - unsigned testEqz = ~testNz; - return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); + // Set testNz to 0xFFFFFFFF if condition is nonzero, 0x00000000 if condition is zero + // Rely on positive value or'ed with its negative having sign bit on + // and zero value or'ed with its negative (which is still zero) having sign bit off + // Use arithmetic shift right, shifting the sign bit through all 32 bits + unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); + unsigned testEqz = ~testNz; + return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); } SIMD_FORCE_INLINE int btSelect(unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero) { - unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); - unsigned testEqz = ~testNz; - return static_cast((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); + unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); + unsigned testEqz = ~testNz; + return static_cast((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); } SIMD_FORCE_INLINE float btSelect(unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero) { #ifdef BT_HAVE_NATIVE_FSEL - return (float)btFsel((btScalar)condition - btScalar(1.0f), valueIfConditionNonZero, valueIfConditionZero); + return (float)btFsel((btScalar)condition - btScalar(1.0f), valueIfConditionNonZero, valueIfConditionZero); #else - return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; + return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; #endif } -template SIMD_FORCE_INLINE void btSwap(T& a, T& b) +template +SIMD_FORCE_INLINE void btSwap(T &a, T &b) { T tmp = a; a = b; b = tmp; } - //PCK: endian swapping functions SIMD_FORCE_INLINE unsigned btSwapEndian(unsigned val) { - return (((val & 0xff000000) >> 24) | ((val & 0x00ff0000) >> 8) | ((val & 0x0000ff00) << 8) | ((val & 0x000000ff) << 24)); + return (((val & 0xff000000) >> 24) | ((val & 0x00ff0000) >> 8) | ((val & 0x0000ff00) << 8) | ((val & 0x000000ff) << 24)); } SIMD_FORCE_INLINE unsigned short btSwapEndian(unsigned short val) @@ -609,127 +621,127 @@ SIMD_FORCE_INLINE unsigned btSwapEndian(int val) SIMD_FORCE_INLINE unsigned short btSwapEndian(short val) { - return btSwapEndian((unsigned short) val); + return btSwapEndian((unsigned short)val); } ///btSwapFloat uses using char pointers to swap the endianness ////btSwapFloat/btSwapDouble will NOT return a float, because the machine might 'correct' invalid floating point values -///Not all values of sign/exponent/mantissa are valid floating point numbers according to IEEE 754. -///When a floating point unit is faced with an invalid value, it may actually change the value, or worse, throw an exception. -///In most systems, running user mode code, you wouldn't get an exception, but instead the hardware/os/runtime will 'fix' the number for you. +///Not all values of sign/exponent/mantissa are valid floating point numbers according to IEEE 754. +///When a floating point unit is faced with an invalid value, it may actually change the value, or worse, throw an exception. +///In most systems, running user mode code, you wouldn't get an exception, but instead the hardware/os/runtime will 'fix' the number for you. ///so instead of returning a float/double, we return integer/long long integer -SIMD_FORCE_INLINE unsigned int btSwapEndianFloat(float d) +SIMD_FORCE_INLINE unsigned int btSwapEndianFloat(float d) { - unsigned int a = 0; - unsigned char *dst = (unsigned char *)&a; - unsigned char *src = (unsigned char *)&d; + unsigned int a = 0; + unsigned char *dst = (unsigned char *)&a; + unsigned char *src = (unsigned char *)&d; - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; - return a; + dst[0] = src[3]; + dst[1] = src[2]; + dst[2] = src[1]; + dst[3] = src[0]; + return a; } // unswap using char pointers -SIMD_FORCE_INLINE float btUnswapEndianFloat(unsigned int a) +SIMD_FORCE_INLINE float btUnswapEndianFloat(unsigned int a) { - float d = 0.0f; - unsigned char *src = (unsigned char *)&a; - unsigned char *dst = (unsigned char *)&d; + float d = 0.0f; + unsigned char *src = (unsigned char *)&a; + unsigned char *dst = (unsigned char *)&d; - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; - - return d; -} - - -// swap using char pointers -SIMD_FORCE_INLINE void btSwapEndianDouble(double d, unsigned char* dst) -{ - unsigned char *src = (unsigned char *)&d; - - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; - -} - -// unswap using char pointers -SIMD_FORCE_INLINE double btUnswapEndianDouble(const unsigned char *src) -{ - double d = 0.0; - unsigned char *dst = (unsigned char *)&d; - - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; + dst[0] = src[3]; + dst[1] = src[2]; + dst[2] = src[1]; + dst[3] = src[0]; return d; } -template -SIMD_FORCE_INLINE void btSetZero(T* a, int n) +// swap using char pointers +SIMD_FORCE_INLINE void btSwapEndianDouble(double d, unsigned char *dst) { - T* acurr = a; - size_t ncurr = n; - while (ncurr > 0) - { - *(acurr++) = 0; - --ncurr; - } + unsigned char *src = (unsigned char *)&d; + + dst[0] = src[7]; + dst[1] = src[6]; + dst[2] = src[5]; + dst[3] = src[4]; + dst[4] = src[3]; + dst[5] = src[2]; + dst[6] = src[1]; + dst[7] = src[0]; } +// unswap using char pointers +SIMD_FORCE_INLINE double btUnswapEndianDouble(const unsigned char *src) +{ + double d = 0.0; + unsigned char *dst = (unsigned char *)&d; + + dst[0] = src[7]; + dst[1] = src[6]; + dst[2] = src[5]; + dst[3] = src[4]; + dst[4] = src[3]; + dst[5] = src[2]; + dst[6] = src[1]; + dst[7] = src[0]; + + return d; +} + +template +SIMD_FORCE_INLINE void btSetZero(T *a, int n) +{ + T *acurr = a; + size_t ncurr = n; + while (ncurr > 0) + { + *(acurr++) = 0; + --ncurr; + } +} SIMD_FORCE_INLINE btScalar btLargeDot(const btScalar *a, const btScalar *b, int n) -{ - btScalar p0,q0,m0,p1,q1,m1,sum; - sum = 0; - n -= 2; - while (n >= 0) { - p0 = a[0]; q0 = b[0]; - m0 = p0 * q0; - p1 = a[1]; q1 = b[1]; - m1 = p1 * q1; - sum += m0; - sum += m1; - a += 2; - b += 2; - n -= 2; - } - n += 2; - while (n > 0) { - sum += (*a) * (*b); - a++; - b++; - n--; - } - return sum; +{ + btScalar p0, q0, m0, p1, q1, m1, sum; + sum = 0; + n -= 2; + while (n >= 0) + { + p0 = a[0]; + q0 = b[0]; + m0 = p0 * q0; + p1 = a[1]; + q1 = b[1]; + m1 = p1 * q1; + sum += m0; + sum += m1; + a += 2; + b += 2; + n -= 2; + } + n += 2; + while (n > 0) + { + sum += (*a) * (*b); + a++; + b++; + n--; + } + return sum; } - // returns normalized value in range [-SIMD_PI, SIMD_PI] -SIMD_FORCE_INLINE btScalar btNormalizeAngle(btScalar angleInRadians) +SIMD_FORCE_INLINE btScalar btNormalizeAngle(btScalar angleInRadians) { angleInRadians = btFmod(angleInRadians, SIMD_2_PI); - if(angleInRadians < -SIMD_PI) + if (angleInRadians < -SIMD_PI) { return angleInRadians + SIMD_2_PI; } - else if(angleInRadians > SIMD_PI) + else if (angleInRadians > SIMD_PI) { return angleInRadians - SIMD_2_PI; } @@ -739,45 +751,38 @@ SIMD_FORCE_INLINE btScalar btNormalizeAngle(btScalar angleInRadians) } } - - ///rudimentary class to provide type info struct btTypedObject { btTypedObject(int objectType) - :m_objectType(objectType) + : m_objectType(objectType) { } - int m_objectType; + int m_objectType; inline int getObjectType() const { return m_objectType; } }; - - ///align a pointer to the provided alignment, upwards -template T* btAlignPointer(T* unalignedPtr, size_t alignment) +template +T *btAlignPointer(T *unalignedPtr, size_t alignment) { - struct btConvertPointerSizeT { - union - { - T* ptr; - size_t integer; + union { + T *ptr; + size_t integer; }; }; - btConvertPointerSizeT converter; - - + btConvertPointerSizeT converter; + const size_t bit_mask = ~(alignment - 1); - converter.ptr = unalignedPtr; - converter.integer += alignment-1; + converter.ptr = unalignedPtr; + converter.integer += alignment - 1; converter.integer &= bit_mask; return converter.ptr; } - -#endif //BT_SCALAR_H +#endif //BT_SCALAR_H From 6e35a9ee64502f0e0d464b54b0e3615c40122c0e Mon Sep 17 00:00:00 2001 From: David Morgan Date: Mon, 13 Mar 2017 19:14:10 +0000 Subject: [PATCH 31/66] fix using SSE on non x86 targets --- src/Bullet3Common/b3Scalar.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/Bullet3Common/b3Scalar.h b/src/Bullet3Common/b3Scalar.h index 16a9ac7a7..dbc7fea39 100644 --- a/src/Bullet3Common/b3Scalar.h +++ b/src/Bullet3Common/b3Scalar.h @@ -71,6 +71,7 @@ inline int b3GetVersion() #else #if (defined (_WIN32) && (_MSC_VER) && _MSC_VER >= 1400) && (!defined (B3_USE_DOUBLE_PRECISION)) + #if (defined (_M_IX86) || defined (_M_X64)) #define B3_USE_SSE #ifdef B3_USE_SSE //B3_USE_SSE_IN_API is disabled under Windows by default, because @@ -82,6 +83,7 @@ inline int b3GetVersion() //#define B3_USE_SSE_IN_API #endif //B3_USE_SSE #include + #endif #endif #endif//_XBOX From e524b22fd62f537f018b5776b430ea861af8e813 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 13 Mar 2017 15:52:52 -0700 Subject: [PATCH 32/66] relax the UseTab in _clang-format, see https://github.com/bulletphysics/bullet3/issues/1007#issuecomment-286264717 --- _clang-format | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/_clang-format b/_clang-format index d1841d577..69810190f 100644 --- a/_clang-format +++ b/_clang-format @@ -85,6 +85,6 @@ SpacesInParentheses: false SpacesInSquareBrackets: false Standard: Auto TabWidth: 4 -UseTab: Always +UseTab: ForContinuationAndIndentation ... From 901b314a1ea96a6398fed6066d9ac0333cdf8450 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 13 Mar 2017 16:06:52 -0700 Subject: [PATCH 33/66] clang-format pybullet.c move AccessModifierOffset to -4 (public:, private:, protected: are aligned to the left in Bullet) --- _clang-format | 1 + examples/pybullet/pybullet.c | 6224 +++++++++++++++++----------------- 2 files changed, 3115 insertions(+), 3110 deletions(-) diff --git a/_clang-format b/_clang-format index 69810190f..43a8b1d04 100644 --- a/_clang-format +++ b/_clang-format @@ -83,6 +83,7 @@ SpacesInContainerLiterals: true SpacesInCStyleCastParentheses: false SpacesInParentheses: false SpacesInSquareBrackets: false +AccessModifierOffset: -4 Standard: Auto TabWidth: 4 UseTab: ForContinuationAndIndentation diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index c0465f7fb..b5c70f5bd 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -3,11 +3,11 @@ #include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h" #ifdef BT_ENABLE_ENET #include "../SharedMemory/PhysicsClientUDP_C_API.h" -#endif //BT_ENABLE_ENET +#endif //BT_ENABLE_ENET #ifdef BT_ENABLE_CLSOCKET #include "../SharedMemory/PhysicsClientTCP_C_API.h" -#endif //BT_ENABLE_CLSOCKET +#endif //BT_ENABLE_CLSOCKET #ifdef __APPLE__ #include @@ -24,19 +24,17 @@ #define PyString_FromString PyBytes_FromString #endif - - static PyObject* SpamError; #define MAX_PHYSICS_CLIENTS 1024 static b3PhysicsClientHandle sPhysicsClients1[MAX_PHYSICS_CLIENTS] = {0}; static int sPhysicsClientsGUI[MAX_PHYSICS_CLIENTS] = {0}; -static int sNumPhysicsClients=0; +static int sNumPhysicsClients = 0; b3PhysicsClientHandle getPhysicsClient(int physicsClientId) { b3PhysicsClientHandle sm; - if ((physicsClientId <0) || (physicsClientId>=MAX_PHYSICS_CLIENTS) || (0 == sPhysicsClients1[physicsClientId])) + if ((physicsClientId < 0) || (physicsClientId >= MAX_PHYSICS_CLIENTS) || (0 == sPhysicsClients1[physicsClientId])) { return 0; } @@ -55,32 +53,34 @@ b3PhysicsClientHandle getPhysicsClient(int physicsClientId) sNumPhysicsClients--; } return 0; - } -static double pybullet_internalGetFloatFromSequence(PyObject* seq, int index) { +static double pybullet_internalGetFloatFromSequence(PyObject* seq, int index) +{ double v = 0.0; PyObject* item; - if (PyList_Check(seq)) { + if (PyList_Check(seq)) + { item = PyList_GET_ITEM(seq, index); v = PyFloat_AsDouble(item); } - else { + else + { item = PyTuple_GET_ITEM(seq, index); v = PyFloat_AsDouble(item); } return v; } - // internal function to set a float matrix[16] // used to initialize camera position with // a view and projection matrix in renderImage() // // // Args: // matrix - float[16] which will be set by values from objMat -static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) { +static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) +{ int i, len; PyObject* seq; @@ -88,8 +88,10 @@ static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) { if (seq) { len = PySequence_Size(objMat); - if (len == 16) { - for (i = 0; i < len; i++) { + if (len == 16) + { + for (i = 0; i < len; i++) + { matrix[i] = pybullet_internalGetFloatFromSequence(seq, i); } Py_DECREF(seq); @@ -106,7 +108,8 @@ static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) { // // // Args: // vector - float[3] which will be set by values from objMat -static int pybullet_internalSetVector(PyObject* objVec, float vector[3]) { +static int pybullet_internalSetVector(PyObject* objVec, float vector[3]) +{ int i, len; PyObject* seq = 0; if (objVec == NULL) @@ -115,10 +118,11 @@ static int pybullet_internalSetVector(PyObject* objVec, float vector[3]) { seq = PySequence_Fast(objVec, "expected a sequence"); if (seq) { - len = PySequence_Size(objVec); - if (len == 3) { - for (i = 0; i < len; i++) { + if (len == 3) + { + for (i = 0; i < len; i++) + { vector[i] = pybullet_internalGetFloatFromSequence(seq, i); } Py_DECREF(seq); @@ -130,7 +134,8 @@ static int pybullet_internalSetVector(PyObject* objVec, float vector[3]) { } // vector - double[3] which will be set by values from obVec -static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) { +static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) +{ int i, len; PyObject* seq; if (obVec == NULL) @@ -140,8 +145,10 @@ static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) { if (seq) { len = PySequence_Size(obVec); - if (len == 3) { - for (i = 0; i < len; i++) { + if (len == 3) + { + for (i = 0; i < len; i++) + { vector[i] = pybullet_internalGetFloatFromSequence(seq, i); } Py_DECREF(seq); @@ -153,7 +160,8 @@ static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) { } // vector - double[3] which will be set by values from obVec -static int pybullet_internalSetVector4d(PyObject* obVec, double vector[4]) { +static int pybullet_internalSetVector4d(PyObject* obVec, double vector[4]) +{ int i, len; PyObject* seq; if (obVec == NULL) @@ -161,8 +169,10 @@ static int pybullet_internalSetVector4d(PyObject* obVec, double vector[4]) { seq = PySequence_Fast(obVec, "expected a sequence"); len = PySequence_Size(obVec); - if (len == 4) { - for (i = 0; i < len; i++) { + if (len == 4) + { + for (i = 0; i < len; i++) + { vector[i] = pybullet_internalGetFloatFromSequence(seq, i); } Py_DECREF(seq); @@ -172,203 +182,201 @@ static int pybullet_internalSetVector4d(PyObject* obVec, double vector[4]) { return 0; } - - // Step through one timestep of the simulation -static PyObject* pybullet_stepSimulation(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_stepSimulation(PyObject* self, PyObject* args, PyObject* keywds) { int physicsClientId = 0; - static char *kwlist[] = { "physicsClientId", NULL }; - b3PhysicsClientHandle sm=0; + static char* kwlist[] = {"physicsClientId", NULL}; + b3PhysicsClientHandle sm = 0; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist,&physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - b3SharedMemoryStatusHandle statusHandle; - int statusType; - if (b3CanSubmitCommand(sm)) { - statusHandle = b3SubmitClientCommandAndWaitStatus( - sm, b3InitStepSimulationCommand(sm)); - statusType = b3GetStatusType(statusHandle); - } - } + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; - Py_INCREF(Py_None); - return Py_None; + if (b3CanSubmitCommand(sm)) + { + statusHandle = b3SubmitClientCommandAndWaitStatus( + sm, b3InitStepSimulationCommand(sm)); + statusType = b3GetStatusType(statusHandle); + } + } + + Py_INCREF(Py_None); + return Py_None; } -static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, PyObject* keywds) { +static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, PyObject* keywds) +{ + int freeIndex = -1; + int method = eCONNECT_GUI; + int i; + b3PhysicsClientHandle sm = 0; - - int freeIndex = -1; - int method = eCONNECT_GUI; - int i; - b3PhysicsClientHandle sm=0; - - if (sNumPhysicsClients>=MAX_PHYSICS_CLIENTS) + if (sNumPhysicsClients >= MAX_PHYSICS_CLIENTS) { - PyErr_SetString(SpamError, - "Exceeding maximum number of physics connections."); - return NULL; + PyErr_SetString(SpamError, + "Exceeding maximum number of physics connections."); + return NULL; } - - { - - int key = SHARED_MEMORY_KEY; - int udpPort = 1234; - int tcpPort = 6667; - - const char* hostName = "localhost"; - - int size = PySequence_Size(args); - if (size == 1) { - if (!PyArg_ParseTuple(args, "i", &method)) { - PyErr_SetString(SpamError, - "connectPhysicsServer expected argument GUI, " - "DIRECT, SHARED_MEMORY, UDP or TCP"); - return NULL; - } - } + int key = SHARED_MEMORY_KEY; + int udpPort = 1234; + int tcpPort = 6667; - //Only one local in-process GUI connection allowed. - if (method == eCONNECT_GUI) - { - int i; - for (i=0;i=0) - { - udpPort = port; - tcpPort = port; - } - } + if (size == 3) + { + int port = -1; + if (!PyArg_ParseTuple(args, "isi", &method, &hostName, &port)) + { + PyErr_SetString(SpamError, + "connectPhysicsServer 3 arguments: method, hostname, port"); + return NULL; + } + if (port >= 0) + { + udpPort = port; + tcpPort = port; + } + } - switch (method) { - case eCONNECT_GUI: { - int argc = 0; - char* argv[1] = {0}; + switch (method) + { + case eCONNECT_GUI: + { + int argc = 0; + char* argv[1] = {0}; #ifdef __APPLE__ - sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); + sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); #else - sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv); + sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv); #endif - break; - } - case eCONNECT_DIRECT: { - sm = b3ConnectPhysicsDirect(); - break; - } - case eCONNECT_SHARED_MEMORY: { - sm = b3ConnectSharedMemory(key); - break; - } - case eCONNECT_UDP: - { + break; + } + case eCONNECT_DIRECT: + { + sm = b3ConnectPhysicsDirect(); + break; + } + case eCONNECT_SHARED_MEMORY: + { + sm = b3ConnectSharedMemory(key); + break; + } + case eCONNECT_UDP: + { #ifdef BT_ENABLE_ENET - sm = b3ConnectPhysicsUDP(hostName, udpPort); + sm = b3ConnectPhysicsUDP(hostName, udpPort); #else - PyErr_SetString(SpamError, "UDP is not enabled in this pybullet build"); - return NULL; -#endif //BT_ENABLE_ENET + PyErr_SetString(SpamError, "UDP is not enabled in this pybullet build"); + return NULL; +#endif //BT_ENABLE_ENET - break; - } - case eCONNECT_TCP: - { + break; + } + case eCONNECT_TCP: + { #ifdef BT_ENABLE_CLSOCKET - - sm = b3ConnectPhysicsTCP(hostName, tcpPort); + + sm = b3ConnectPhysicsTCP(hostName, tcpPort); #else - PyErr_SetString(SpamError, "TCP is not enabled in this pybullet build"); - return NULL; -#endif //BT_ENABLE_CLSOCKET - - break; - } - - + PyErr_SetString(SpamError, "TCP is not enabled in this pybullet build"); + return NULL; +#endif //BT_ENABLE_CLSOCKET - default: { - PyErr_SetString(SpamError, "connectPhysicsServer unexpected argument"); - return NULL; - } - }; - } + break; + } - if (sm && b3CanSubmitCommand(sm)) - { - for (i=0;i=0) - { - b3SharedMemoryCommandHandle command; + if (sm && b3CanSubmitCommand(sm)) + { + for (i = 0; i < MAX_PHYSICS_CLIENTS; i++) + { + if (sPhysicsClients1[i] == 0) + { + freeIndex = i; + break; + } + } + + if (freeIndex >= 0) + { + b3SharedMemoryCommandHandle command; b3SharedMemoryStatusHandle statusHandle; int statusType; + sPhysicsClients1[freeIndex] = sm; + sPhysicsClientsGUI[freeIndex] = method; + sNumPhysicsClients++; - sPhysicsClients1[freeIndex] = sm; - sPhysicsClientsGUI[freeIndex] = method; - sNumPhysicsClients++; - - command = b3InitSyncBodyInfoCommand(sm); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + command = b3InitSyncBodyInfoCommand(sm); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); #if 0 if (statusType != CMD_BODY_INFO_COMPLETED) @@ -377,110 +385,105 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P return NULL; } #endif - } - - } - return PyInt_FromLong(freeIndex); + } + } + return PyInt_FromLong(freeIndex); } static PyObject* pybullet_disconnectPhysicsServer(PyObject* self, - PyObject* args, - PyObject *keywds) { - + PyObject* args, + PyObject* keywds) +{ int physicsClientId = 0; - b3PhysicsClientHandle sm=0; - static char *kwlist[] = { "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist,&physicsClientId)) + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - b3DisconnectSharedMemory(sm); - sm = 0; - } + { + b3DisconnectSharedMemory(sm); + sm = 0; + } - sPhysicsClients1[physicsClientId] = 0; - sPhysicsClientsGUI[physicsClientId] = 0; - sNumPhysicsClients--; + sPhysicsClients1[physicsClientId] = 0; + sPhysicsClientsGUI[physicsClientId] = 0; + sNumPhysicsClients--; - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } -static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args,PyObject *keywds) { +static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args, PyObject* keywds) +{ const char* worldFileName = ""; b3PhysicsClientHandle sm = 0; int physicsClientId = 0; - static char *kwlist[] = { "worldFileName","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &worldFileName,&physicsClientId)) + static char* kwlist[] = {"worldFileName", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &worldFileName, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - { - b3SharedMemoryCommandHandle command; + b3SharedMemoryCommandHandle command; b3SharedMemoryStatusHandle statusHandle; int statusType; command = b3SaveWorldCommandInit(sm, worldFileName); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); - if (statusType != CMD_SAVE_WORLD_COMPLETED) { + if (statusType != CMD_SAVE_WORLD_COMPLETED) + { PyErr_SetString(SpamError, "saveWorld command execution failed."); return NULL; } Py_INCREF(Py_None); return Py_None; - - } + } - PyErr_SetString(SpamError, "Cannot execute saveWorld command."); return NULL; - } #define MAX_SDF_BODIES 512 -static PyObject* pybullet_loadBullet(PyObject* self, PyObject* args,PyObject *keywds) +static PyObject* pybullet_loadBullet(PyObject* self, PyObject* args, PyObject* keywds) { const char* bulletFileName = ""; b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command; - int i,numBodies; + int i, numBodies; int bodyIndicesOut[MAX_SDF_BODIES]; PyObject* pylist = 0; b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "bulletFileName","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &bulletFileName,&physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"bulletFileName", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &bulletFileName, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - command = b3LoadBulletCommandInit(sm, bulletFileName); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); @@ -492,22 +495,23 @@ static PyObject* pybullet_loadBullet(PyObject* self, PyObject* args,PyObject *ke } numBodies = - b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); - if (numBodies > MAX_SDF_BODIES) { - PyErr_SetString(SpamError, "loadBullet exceeds body capacity"); - return NULL; - } + b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); + if (numBodies > MAX_SDF_BODIES) + { + PyErr_SetString(SpamError, "loadBullet exceeds body capacity"); + return NULL; + } - pylist = PyTuple_New(numBodies); + pylist = PyTuple_New(numBodies); - if (numBodies > 0 && numBodies <= MAX_SDF_BODIES) { - for (i = 0; i < numBodies; i++) { - PyTuple_SetItem(pylist, i, PyInt_FromLong(bodyIndicesOut[i])); - } - } - return pylist; - - + if (numBodies > 0 && numBodies <= MAX_SDF_BODIES) + { + for (i = 0; i < numBodies; i++) + { + PyTuple_SetItem(pylist, i, PyInt_FromLong(bodyIndicesOut[i])); + } + } + return pylist; } static PyObject* pybullet_saveBullet(PyObject* self, PyObject* args, PyObject* keywds) @@ -518,20 +522,19 @@ static PyObject* pybullet_saveBullet(PyObject* self, PyObject* args, PyObject* k b3SharedMemoryCommandHandle command; b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "bulletFileName","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &bulletFileName,&physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"bulletFileName", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &bulletFileName, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - command = b3SaveBulletCommandInit(sm, bulletFileName); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); @@ -544,8 +547,6 @@ static PyObject* pybullet_saveBullet(PyObject* self, PyObject* args, PyObject* k return Py_None; } - - static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* keywds) { const char* mjcfFileName = ""; @@ -558,19 +559,18 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key int bodyIndicesOut[MAX_SDF_BODIES]; PyObject* pylist = 0; int physicsClientId = 0; - static char *kwlist[] = { "mjcfFileName","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &mjcfFileName,&physicsClientId)) + static char* kwlist[] = {"mjcfFileName", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &mjcfFileName, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - command = b3LoadMJCFCommandInit(sm, mjcfFileName); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); @@ -580,24 +580,27 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key return NULL; } - numBodies = - b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); - if (numBodies > MAX_SDF_BODIES) { - PyErr_SetString(SpamError, "SDF exceeds body capacity"); - return NULL; - } + numBodies = + b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); + if (numBodies > MAX_SDF_BODIES) + { + PyErr_SetString(SpamError, "SDF exceeds body capacity"); + return NULL; + } - pylist = PyTuple_New(numBodies); + pylist = PyTuple_New(numBodies); - if (numBodies > 0 && numBodies <= MAX_SDF_BODIES) { - for (i = 0; i < numBodies; i++) { - PyTuple_SetItem(pylist, i, PyInt_FromLong(bodyIndicesOut[i])); - } - } - return pylist; + if (numBodies > 0 && numBodies <= MAX_SDF_BODIES) + { + for (i = 0; i < numBodies; i++) + { + PyTuple_SetItem(pylist, i, PyInt_FromLong(bodyIndicesOut[i])); + } + } + return pylist; } -static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* args, PyObject* keywds) { double fixedTimeStep = -1; int numSolverIterations = -1; @@ -610,16 +613,16 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar b3PhysicsClientHandle sm = 0; int physicsClientId = 0; - static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "physicsClientId", NULL }; + static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidii", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps, + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps, &collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; @@ -634,7 +637,7 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar b3PhysicsParamSetNumSolverIterations(command, numSolverIterations); } - if (collisionFilterMode>=0) + if (collisionFilterMode >= 0) { b3PhysicsParamSetCollisionFilterMode(command, collisionFilterMode); } @@ -648,20 +651,20 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar } if (useSplitImpulse >= 0) { - b3PhysicsParamSetUseSplitImpulse(command,useSplitImpulse); + b3PhysicsParamSetUseSplitImpulse(command, useSplitImpulse); } if (splitImpulsePenetrationThreshold >= 0) { b3PhysicsParamSetSplitImpulsePenetrationThreshold(command, splitImpulsePenetrationThreshold); } - if (contactBreakingThreshold>=0) + if (contactBreakingThreshold >= 0) { - b3PhysicsParamSetContactBreakingThreshold(command,contactBreakingThreshold); + b3PhysicsParamSetContactBreakingThreshold(command, contactBreakingThreshold); } //-1 is disables the maxNumCmdPer1ms feature, allow it - if (maxNumCmdPer1ms>=-1) + if (maxNumCmdPer1ms >= -1) { - b3PhysicsParamSetMaxNumCommandsPer1ms(command,maxNumCmdPer1ms); + b3PhysicsParamSetMaxNumCommandsPer1ms(command, maxNumCmdPer1ms); } //ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation); @@ -682,668 +685,701 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar return Py_None; } - // Load a robot from a URDF file (universal robot description format) // function can be called without arguments and will default // to position (0,0,1) with orientation(0,0,0,1) // els(x,y,z) or // loadURDF(pos_x, pos_y, pos_z, orn_x, orn_y, orn_z, orn_w) -static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject* keywds) { - int physicsClientId = 0; - - static char *kwlist[] = { "fileName", "basePosition", "baseOrientation", "useMaximalCoordinates","useFixedBase","physicsClientId", NULL }; + int physicsClientId = 0; - static char *kwlistBackwardCompatible4[] = { "fileName", "startPosX", "startPosY", "startPosZ", NULL }; - static char *kwlistBackwardCompatible8[] = { "fileName", "startPosX", "startPosY", "startPosZ", "startOrnX", "startOrnY","startOrnZ","startOrnW", NULL }; + static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "useMaximalCoordinates", "useFixedBase", "physicsClientId", NULL}; + static char* kwlistBackwardCompatible4[] = {"fileName", "startPosX", "startPosY", "startPosZ", NULL}; + static char* kwlistBackwardCompatible8[] = {"fileName", "startPosX", "startPosY", "startPosZ", "startOrnX", "startOrnY", "startOrnZ", "startOrnW", NULL}; - int bodyIndex = -1; - const char* urdfFileName = ""; + int bodyIndex = -1; + const char* urdfFileName = ""; - double startPosX = 0.0; - double startPosY = 0.0; - double startPosZ = 0.0; - double startOrnX = 0.0; - double startOrnY = 0.0; - double startOrnZ = 0.0; - double startOrnW = 1.0; - int useMaximalCoordinates = 0; - int useFixedBase = 0; + double startPosX = 0.0; + double startPosY = 0.0; + double startPosZ = 0.0; + double startOrnX = 0.0; + double startOrnY = 0.0; + double startOrnZ = 0.0; + double startOrnW = 1.0; + int useMaximalCoordinates = 0; + int useFixedBase = 0; - int backwardsCompatibilityArgs = 0; -b3PhysicsClientHandle sm=0; - if (PyArg_ParseTupleAndKeywords(args, keywds, "sddd", kwlistBackwardCompatible4, &urdfFileName, &startPosX, - &startPosY, &startPosZ)) - { - backwardsCompatibilityArgs = 1; - } - else - { - PyErr_Clear(); - } + int backwardsCompatibilityArgs = 0; + b3PhysicsClientHandle sm = 0; + if (PyArg_ParseTupleAndKeywords(args, keywds, "sddd", kwlistBackwardCompatible4, &urdfFileName, &startPosX, + &startPosY, &startPosZ)) + { + backwardsCompatibilityArgs = 1; + } + else + { + PyErr_Clear(); + } + if (PyArg_ParseTupleAndKeywords(args, keywds, "sddddddd", kwlistBackwardCompatible8, &urdfFileName, &startPosX, + &startPosY, &startPosZ, &startOrnX, &startOrnY, &startOrnZ, &startOrnW)) + { + backwardsCompatibilityArgs = 1; + } + else + { + PyErr_Clear(); + } - if (PyArg_ParseTupleAndKeywords(args, keywds, "sddddddd", kwlistBackwardCompatible8,&urdfFileName, &startPosX, - &startPosY, &startPosZ, &startOrnX, &startOrnY,&startOrnZ, &startOrnW)) - { - backwardsCompatibilityArgs = 1; - } - else - { - PyErr_Clear(); - } + if (!backwardsCompatibilityArgs) + { + PyObject* basePosObj = 0; + PyObject* baseOrnObj = 0; + double basePos[3]; + double baseOrn[4]; - - - if (!backwardsCompatibilityArgs) - { - PyObject* basePosObj = 0; - PyObject* baseOrnObj = 0; - double basePos[3]; - double baseOrn[4]; - - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOiii", kwlist, &urdfFileName, &basePosObj, &baseOrnObj, &useMaximalCoordinates,&useFixedBase,&physicsClientId)) - { - - return NULL; - } - else - { - if (basePosObj) - { - if (!pybullet_internalSetVectord(basePosObj, basePos)) - { - PyErr_SetString(SpamError, "Cannot convert basePosition."); - return NULL; - } - startPosX = basePos[0]; - startPosY = basePos[1]; - startPosZ = basePos[2]; - - } - if (baseOrnObj) - { - if (!pybullet_internalSetVector4d(baseOrnObj, baseOrn)) - { - PyErr_SetString(SpamError, "Cannot convert baseOrientation."); - return NULL; - } - startOrnX = baseOrn[0]; - startOrnY = baseOrn[1]; - startOrnZ = baseOrn[2]; - startOrnW = baseOrn[3]; - } - } - } + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOiii", kwlist, &urdfFileName, &basePosObj, &baseOrnObj, &useMaximalCoordinates, &useFixedBase, &physicsClientId)) + { + return NULL; + } + else + { + if (basePosObj) + { + if (!pybullet_internalSetVectord(basePosObj, basePos)) + { + PyErr_SetString(SpamError, "Cannot convert basePosition."); + return NULL; + } + startPosX = basePos[0]; + startPosY = basePos[1]; + startPosZ = basePos[2]; + } + if (baseOrnObj) + { + if (!pybullet_internalSetVector4d(baseOrnObj, baseOrn)) + { + PyErr_SetString(SpamError, "Cannot convert baseOrientation."); + return NULL; + } + startOrnX = baseOrn[0]; + startOrnY = baseOrn[1]; + startOrnZ = baseOrn[2]; + startOrnW = baseOrn[3]; + } + } + } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - if (strlen(urdfFileName)) { - // printf("(%f, %f, %f) (%f, %f, %f, %f)\n", - // startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW); - - b3SharedMemoryStatusHandle statusHandle; - int statusType; - b3SharedMemoryCommandHandle command = - b3LoadUrdfCommandInit(sm, urdfFileName); - - // setting the initial position, orientation and other arguments are - // optional - b3LoadUrdfCommandSetStartPosition(command, startPosX, startPosY, startPosZ); - b3LoadUrdfCommandSetStartOrientation(command, startOrnX, startOrnY, - startOrnZ, startOrnW); - if (useMaximalCoordinates) + if (strlen(urdfFileName)) { - b3LoadUrdfCommandSetUseMultiBody(command, 0); - } - if (useFixedBase) - { - b3LoadUrdfCommandSetUseFixedBase(command, 1); - } + // printf("(%f, %f, %f) (%f, %f, %f, %f)\n", + // startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - statusType = b3GetStatusType(statusHandle); - if (statusType != CMD_URDF_LOADING_COMPLETED) { - PyErr_SetString(SpamError, "Cannot load URDF file."); - return NULL; - } - bodyIndex = b3GetStatusBodyIndex(statusHandle); - } else { - PyErr_SetString(SpamError, - "Empty filename, method expects 1, 4 or 8 arguments."); - return NULL; - } - return PyLong_FromLong(bodyIndex); + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle command = + b3LoadUrdfCommandInit(sm, urdfFileName); + + // setting the initial position, orientation and other arguments are + // optional + b3LoadUrdfCommandSetStartPosition(command, startPosX, startPosY, startPosZ); + b3LoadUrdfCommandSetStartOrientation(command, startOrnX, startOrnY, + startOrnZ, startOrnW); + if (useMaximalCoordinates) + { + b3LoadUrdfCommandSetUseMultiBody(command, 0); + } + if (useFixedBase) + { + b3LoadUrdfCommandSetUseFixedBase(command, 1); + } + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType != CMD_URDF_LOADING_COMPLETED) + { + PyErr_SetString(SpamError, "Cannot load URDF file."); + return NULL; + } + bodyIndex = b3GetStatusBodyIndex(statusHandle); + } + else + { + PyErr_SetString(SpamError, + "Empty filename, method expects 1, 4 or 8 arguments."); + return NULL; + } + return PyLong_FromLong(bodyIndex); } +static PyObject* pybullet_loadSDF(PyObject* self, PyObject* args, PyObject* keywds) +{ + const char* sdfFileName = ""; + int numBodies = 0; + int i; + int bodyIndicesOut[MAX_SDF_BODIES]; + PyObject* pylist = 0; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle commandHandle; + b3PhysicsClientHandle sm = 0; - - -static PyObject* pybullet_loadSDF(PyObject* self, PyObject* args, PyObject *keywds) { - const char* sdfFileName = ""; - int numBodies = 0; - int i; - int bodyIndicesOut[MAX_SDF_BODIES]; - PyObject* pylist = 0; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - b3SharedMemoryCommandHandle commandHandle; -b3PhysicsClientHandle sm = 0; - - int physicsClientId = 0; - static char *kwlist[] = { "sdfFileName","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &sdfFileName,&physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"sdfFileName", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &sdfFileName, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - commandHandle = b3LoadSdfCommandInit(sm, sdfFileName); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - if (statusType != CMD_SDF_LOADING_COMPLETED) { - PyErr_SetString(SpamError, "Cannot load SDF file."); - return NULL; - } + commandHandle = b3LoadSdfCommandInit(sm, sdfFileName); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType != CMD_SDF_LOADING_COMPLETED) + { + PyErr_SetString(SpamError, "Cannot load SDF file."); + return NULL; + } - numBodies = - b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); - if (numBodies > MAX_SDF_BODIES) { - PyErr_SetString(SpamError, "SDF exceeds body capacity"); - return NULL; - } + numBodies = + b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); + if (numBodies > MAX_SDF_BODIES) + { + PyErr_SetString(SpamError, "SDF exceeds body capacity"); + return NULL; + } - pylist = PyTuple_New(numBodies); + pylist = PyTuple_New(numBodies); - if (numBodies > 0 && numBodies <= MAX_SDF_BODIES) { - for (i = 0; i < numBodies; i++) { - PyTuple_SetItem(pylist, i, PyInt_FromLong(bodyIndicesOut[i])); - } - } - return pylist; + if (numBodies > 0 && numBodies <= MAX_SDF_BODIES) + { + for (i = 0; i < numBodies; i++) + { + PyTuple_SetItem(pylist, i, PyInt_FromLong(bodyIndicesOut[i])); + } + } + return pylist; } // Reset the simulation to remove all loaded objects -static PyObject* pybullet_resetSimulation(PyObject* self, PyObject* args, PyObject* keywds) { - - int physicsClientId = 0; - static char *kwlist[] = { "physicsClientId", NULL }; +static PyObject* pybullet_resetSimulation(PyObject* self, PyObject* args, PyObject* keywds) +{ + int physicsClientId = 0; + static char* kwlist[] = {"physicsClientId", NULL}; b3PhysicsClientHandle sm = 0; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist,&physicsClientId)) + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - { - b3SharedMemoryStatusHandle statusHandle; - statusHandle = b3SubmitClientCommandAndWaitStatus( - sm, b3InitResetSimulationCommand(sm)); - } - Py_INCREF(Py_None); - return Py_None; + { + b3SharedMemoryStatusHandle statusHandle; + statusHandle = b3SubmitClientCommandAndWaitStatus( + sm, b3InitResetSimulationCommand(sm)); + } + Py_INCREF(Py_None); + return Py_None; } //this method is obsolete, use pybullet_setJointMotorControl2 instead -static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) { - int size; - int bodyIndex, jointIndex, controlMode; +static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) +{ + int size; + int bodyIndex, jointIndex, controlMode; - double targetPosition = 0.0; - double targetVelocity = 0.0; - double maxForce = 100000.0; - double appliedForce = 0.0; - double kp = 0.1; - double kd = 1.0; - int valid = 0; - int physicsClientId = 0; - b3PhysicsClientHandle sm; + double targetPosition = 0.0; + double targetVelocity = 0.0; + double maxForce = 100000.0; + double appliedForce = 0.0; + double kp = 0.1; + double kd = 1.0; + int valid = 0; + int physicsClientId = 0; + b3PhysicsClientHandle sm; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - size = PySequence_Size(args); - if (size == 4) { - double targetValue = 0.0; - // see switch statement below for convertsions dependent on controlMode - if (!PyArg_ParseTuple(args, "iiid", &bodyIndex, &jointIndex, &controlMode, - &targetValue)) { - PyErr_SetString(SpamError, "Error parsing arguments"); - return NULL; - } - valid = 1; - switch (controlMode) { - case CONTROL_MODE_POSITION_VELOCITY_PD: { - targetPosition = targetValue; - break; - } - case CONTROL_MODE_VELOCITY: { - targetVelocity = targetValue; - break; - } - case CONTROL_MODE_TORQUE: { - appliedForce = targetValue; - break; - } - default: { valid = 0; } - } - } - if (size == 5) { - double targetValue = 0.0; - // See switch statement for conversions - if (!PyArg_ParseTuple(args, "iiidd", &bodyIndex, &jointIndex, &controlMode, - &targetValue, &maxForce)) { - PyErr_SetString(SpamError, "Error parsing arguments"); - return NULL; - } - valid = 1; + size = PySequence_Size(args); + if (size == 4) + { + double targetValue = 0.0; + // see switch statement below for convertsions dependent on controlMode + if (!PyArg_ParseTuple(args, "iiid", &bodyIndex, &jointIndex, &controlMode, + &targetValue)) + { + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; + switch (controlMode) + { + case CONTROL_MODE_POSITION_VELOCITY_PD: + { + targetPosition = targetValue; + break; + } + case CONTROL_MODE_VELOCITY: + { + targetVelocity = targetValue; + break; + } + case CONTROL_MODE_TORQUE: + { + appliedForce = targetValue; + break; + } + default: + { + valid = 0; + } + } + } + if (size == 5) + { + double targetValue = 0.0; + // See switch statement for conversions + if (!PyArg_ParseTuple(args, "iiidd", &bodyIndex, &jointIndex, &controlMode, + &targetValue, &maxForce)) + { + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; - switch (controlMode) { - case CONTROL_MODE_POSITION_VELOCITY_PD: { - targetPosition = targetValue; - break; - } - case CONTROL_MODE_VELOCITY: { - targetVelocity = targetValue; - break; - } - case CONTROL_MODE_TORQUE: { - valid = 0; - break; - } - default: { valid = 0; } - } - } - if (size == 6) { - double gain = 0.0; - double targetValue = 0.0; - if (!PyArg_ParseTuple(args, "iiiddd", &bodyIndex, &jointIndex, &controlMode, - &targetValue, &maxForce, &gain)) { - PyErr_SetString(SpamError, "Error parsing arguments"); - return NULL; - } - valid = 1; + switch (controlMode) + { + case CONTROL_MODE_POSITION_VELOCITY_PD: + { + targetPosition = targetValue; + break; + } + case CONTROL_MODE_VELOCITY: + { + targetVelocity = targetValue; + break; + } + case CONTROL_MODE_TORQUE: + { + valid = 0; + break; + } + default: + { + valid = 0; + } + } + } + if (size == 6) + { + double gain = 0.0; + double targetValue = 0.0; + if (!PyArg_ParseTuple(args, "iiiddd", &bodyIndex, &jointIndex, &controlMode, + &targetValue, &maxForce, &gain)) + { + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; - switch (controlMode) { - case CONTROL_MODE_POSITION_VELOCITY_PD: { - targetPosition = targetValue; - kp = gain; - break; - } - case CONTROL_MODE_VELOCITY: { - targetVelocity = targetValue; - kd = gain; - break; - } - case CONTROL_MODE_TORQUE: { - valid = 0; - break; - } - default: { valid = 0; } - } - } - if (size == 8) { - // only applicable for CONTROL_MODE_POSITION_VELOCITY_PD. - if (!PyArg_ParseTuple(args, "iiiddddd", &bodyIndex, &jointIndex, - &controlMode, &targetPosition, &targetVelocity, - &maxForce, &kp, &kd)) { - PyErr_SetString(SpamError, "Error parsing arguments"); - return NULL; - } - valid = 1; - } + switch (controlMode) + { + case CONTROL_MODE_POSITION_VELOCITY_PD: + { + targetPosition = targetValue; + kp = gain; + break; + } + case CONTROL_MODE_VELOCITY: + { + targetVelocity = targetValue; + kd = gain; + break; + } + case CONTROL_MODE_TORQUE: + { + valid = 0; + break; + } + default: + { + valid = 0; + } + } + } + if (size == 8) + { + // only applicable for CONTROL_MODE_POSITION_VELOCITY_PD. + if (!PyArg_ParseTuple(args, "iiiddddd", &bodyIndex, &jointIndex, + &controlMode, &targetPosition, &targetVelocity, + &maxForce, &kp, &kd)) + { + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; + } - if (valid) { - int numJoints; - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - struct b3JointInfo info; + if (valid) + { + int numJoints; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + struct b3JointInfo info; - numJoints = b3GetNumJoints(sm, bodyIndex); - if ((jointIndex >= numJoints) || (jointIndex < 0)) { - PyErr_SetString(SpamError, "Joint index out-of-range."); - return NULL; - } + numJoints = b3GetNumJoints(sm, bodyIndex); + if ((jointIndex >= numJoints) || (jointIndex < 0)) + { + PyErr_SetString(SpamError, "Joint index out-of-range."); + return NULL; + } - if ((controlMode != CONTROL_MODE_VELOCITY) && - (controlMode != CONTROL_MODE_TORQUE) && - (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) { - PyErr_SetString(SpamError, "Illegral control mode."); - return NULL; - } + if ((controlMode != CONTROL_MODE_VELOCITY) && + (controlMode != CONTROL_MODE_TORQUE) && + (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) + { + PyErr_SetString(SpamError, "Illegral control mode."); + return NULL; + } - commandHandle = b3JointControlCommandInit2(sm, bodyIndex, controlMode); + commandHandle = b3JointControlCommandInit2(sm, bodyIndex, controlMode); - b3GetJointInfo(sm, bodyIndex, jointIndex, &info); + b3GetJointInfo(sm, bodyIndex, jointIndex, &info); - switch (controlMode) { - case CONTROL_MODE_VELOCITY: { - b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, - targetVelocity); - b3JointControlSetKd(commandHandle, info.m_uIndex, kd); - b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce); - break; - } + switch (controlMode) + { + case CONTROL_MODE_VELOCITY: + { + b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, + targetVelocity); + b3JointControlSetKd(commandHandle, info.m_uIndex, kd); + b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce); + break; + } - case CONTROL_MODE_TORQUE: { - b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, - appliedForce); - break; - } + case CONTROL_MODE_TORQUE: + { + b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, + appliedForce); + break; + } - case CONTROL_MODE_POSITION_VELOCITY_PD: { - b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex, - targetPosition); - b3JointControlSetKp(commandHandle, info.m_uIndex, kp); - b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, - targetVelocity); - b3JointControlSetKd(commandHandle, info.m_uIndex, kd); - b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce); - break; - } - default: {} - }; + case CONTROL_MODE_POSITION_VELOCITY_PD: + { + b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex, + targetPosition); + b3JointControlSetKp(commandHandle, info.m_uIndex, kp); + b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, + targetVelocity); + b3JointControlSetKd(commandHandle, info.m_uIndex, kd); + b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce); + break; + } + default: + { + } + }; - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - Py_INCREF(Py_None); - return Py_None; - } - PyErr_SetString(SpamError, "Error parsing arguments in setJointControl."); - return NULL; + Py_INCREF(Py_None); + return Py_None; + } + PyErr_SetString(SpamError, "Error parsing arguments in setJointControl."); + return NULL; } - -static PyObject* pybullet_setJointMotorControl2(PyObject* self, PyObject* args, PyObject* keywds) +static PyObject* pybullet_setJointMotorControl2(PyObject* self, PyObject* args, PyObject* keywds) { - int bodyIndex, jointIndex, controlMode; + int bodyIndex, jointIndex, controlMode; - double targetPosition = 0.0; - double targetVelocity = 0.0; - double force = 100000.0; - double kp = 0.1; - double kd = 1.0; -b3PhysicsClientHandle sm = 0; + double targetPosition = 0.0; + double targetVelocity = 0.0; + double force = 100000.0; + double kp = 0.1; + double kd = 1.0; + b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "bodyIndex", "jointIndex", "controlMode", "targetPosition", "targetVelocity" - , "force", "positionGain", "velocityGain", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|dddddi", kwlist,&bodyIndex, &jointIndex, &controlMode, - &targetPosition, &targetVelocity,&force, &kp, &kd, &physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"bodyIndex", "jointIndex", "controlMode", "targetPosition", "targetVelocity", "force", "positionGain", "velocityGain", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iii|dddddi", kwlist, &bodyIndex, &jointIndex, &controlMode, + &targetPosition, &targetVelocity, &force, &kp, &kd, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - { - int numJoints; - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - struct b3JointInfo info; + { + int numJoints; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + struct b3JointInfo info; - numJoints = b3GetNumJoints(sm, bodyIndex); - if ((jointIndex >= numJoints) || (jointIndex < 0)) { - PyErr_SetString(SpamError, "Joint index out-of-range."); - return NULL; - } + numJoints = b3GetNumJoints(sm, bodyIndex); + if ((jointIndex >= numJoints) || (jointIndex < 0)) + { + PyErr_SetString(SpamError, "Joint index out-of-range."); + return NULL; + } - if ((controlMode != CONTROL_MODE_VELOCITY) && - (controlMode != CONTROL_MODE_TORQUE) && - (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) { - PyErr_SetString(SpamError, "Illegral control mode."); - return NULL; - } + if ((controlMode != CONTROL_MODE_VELOCITY) && + (controlMode != CONTROL_MODE_TORQUE) && + (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) + { + PyErr_SetString(SpamError, "Illegral control mode."); + return NULL; + } - commandHandle = b3JointControlCommandInit2(sm, bodyIndex, controlMode); + commandHandle = b3JointControlCommandInit2(sm, bodyIndex, controlMode); - b3GetJointInfo(sm, bodyIndex, jointIndex, &info); + b3GetJointInfo(sm, bodyIndex, jointIndex, &info); - switch (controlMode) { - case CONTROL_MODE_VELOCITY: { - b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, - targetVelocity); - b3JointControlSetKd(commandHandle, info.m_uIndex, kd); - b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, force); - break; - } + switch (controlMode) + { + case CONTROL_MODE_VELOCITY: + { + b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, + targetVelocity); + b3JointControlSetKd(commandHandle, info.m_uIndex, kd); + b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, force); + break; + } - case CONTROL_MODE_TORQUE: { - b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, - force); - break; - } + case CONTROL_MODE_TORQUE: + { + b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, + force); + break; + } - case CONTROL_MODE_POSITION_VELOCITY_PD: { - b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex, - targetPosition); - b3JointControlSetKp(commandHandle, info.m_uIndex, kp); - b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, - targetVelocity); - b3JointControlSetKd(commandHandle, info.m_uIndex, kd); - b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, force); - break; - } - default: {} - }; + case CONTROL_MODE_POSITION_VELOCITY_PD: + { + b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex, + targetPosition); + b3JointControlSetKp(commandHandle, info.m_uIndex, kp); + b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, + targetVelocity); + b3JointControlSetKd(commandHandle, info.m_uIndex, kd); + b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, force); + break; + } + default: + { + } + }; - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - Py_INCREF(Py_None); - return Py_None; - } -// PyErr_SetString(SpamError, "Error parsing arguments in setJointControl."); -// return NULL; + Py_INCREF(Py_None); + return Py_None; + } + // PyErr_SetString(SpamError, "Error parsing arguments in setJointControl."); + // return NULL; } static PyObject* pybullet_setRealTimeSimulation(PyObject* self, - PyObject* args, - PyObject* keywds) { - - int enableRealTimeSimulation = 0; - int ret; + PyObject* args, + PyObject* keywds) +{ + int enableRealTimeSimulation = 0; + int ret; b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "enableRealTimeSimulation", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&enableRealTimeSimulation, &physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"enableRealTimeSimulation", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &enableRealTimeSimulation, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - + { + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); + b3SharedMemoryStatusHandle statusHandle; - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); - b3SharedMemoryStatusHandle statusHandle; + ret = + b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation); - ret = - b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); + } - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); - } - - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } - - static PyObject* pybullet_setInternalSimFlags(PyObject* self, - PyObject* args, PyObject* keywds) { - - int flags = 0; - int ret; - int physicsClientId = 0; -b3PhysicsClientHandle sm = 0; + PyObject* args, PyObject* keywds) +{ + int flags = 0; + int ret; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "flags", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&flags, &physicsClientId)) + static char* kwlist[] = {"flags", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &flags, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); - b3SharedMemoryStatusHandle statusHandle; + { + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); + b3SharedMemoryStatusHandle statusHandle; - ret = - b3PhysicsParamSetInternalSimFlags(command, flags); + ret = + b3PhysicsParamSetInternalSimFlags(command, flags); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); - } + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); + } - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } // Set the gravity of the world with (x, y, z) arguments -static PyObject* pybullet_setGravity(PyObject* self, PyObject* args, PyObject* keywds) { - - { - double gravX = 0.0; - double gravY = 0.0; - double gravZ = -10.0; - int ret; - b3PhysicsClientHandle sm = 0; - b3SharedMemoryCommandHandle command; - b3SharedMemoryStatusHandle statusHandle; - - int physicsClientId = 0; - static char *kwlist[] = { "gravX", "gravY", "gravZ", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ddd|i", kwlist,&gravX, &gravY, &gravZ, &physicsClientId)) +static PyObject* pybullet_setGravity(PyObject* self, PyObject* args, PyObject* keywds) +{ { - return NULL; - } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - + double gravX = 0.0; + double gravY = 0.0; + double gravZ = -10.0; + int ret; + b3PhysicsClientHandle sm = 0; + b3SharedMemoryCommandHandle command; + b3SharedMemoryStatusHandle statusHandle; - command = b3InitPhysicsParamCommand(sm); - - ret = b3PhysicsParamSetGravity(command, gravX, gravY, gravZ); - // ret = b3PhysicsParamSetTimeStep(command, timeStep); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); - } + int physicsClientId = 0; + static char* kwlist[] = {"gravX", "gravY", "gravZ", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ddd|i", kwlist, &gravX, &gravY, &gravZ, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } - Py_INCREF(Py_None); - return Py_None; + command = b3InitPhysicsParamCommand(sm); + + ret = b3PhysicsParamSetGravity(command, gravX, gravY, gravZ); + // ret = b3PhysicsParamSetTimeStep(command, timeStep); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); + } + + Py_INCREF(Py_None); + return Py_None; } -static PyObject* pybullet_setTimeStep(PyObject* self, PyObject* args, PyObject* keywds) +static PyObject* pybullet_setTimeStep(PyObject* self, PyObject* args, PyObject* keywds) { double timeStep = 0.001; int ret; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "timeStep", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "d|i", kwlist,&timeStep, &physicsClientId)) + static char* kwlist[] = {"timeStep", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "d|i", kwlist, &timeStep, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } { + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); + b3SharedMemoryStatusHandle statusHandle; - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); - b3SharedMemoryStatusHandle statusHandle; + ret = b3PhysicsParamSetTimeStep(command, timeStep); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - ret = b3PhysicsParamSetTimeStep(command, timeStep); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - + Py_INCREF(Py_None); + return Py_None; + } +} + +static PyObject* +pybullet_setDefaultContactERP(PyObject* self, PyObject* args, PyObject* keywds) +{ + double defaultContactERP = 0.005; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + + static char* kwlist[] = {"defaultContactERP", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "d|i", kwlist, &defaultContactERP, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + { + int ret; + + b3SharedMemoryStatusHandle statusHandle; + + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); + ret = b3PhysicsParamSetDefaultContactERP(command, defaultContactERP); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + } Py_INCREF(Py_None); return Py_None; } -} - -static PyObject * -pybullet_setDefaultContactERP(PyObject* self, PyObject* args,PyObject* keywds) -{ - double defaultContactERP=0.005; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - - static char *kwlist[] = { "defaultContactERP", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "d|i", kwlist,&defaultContactERP, &physicsClientId)) - { - return NULL; - } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - { - int ret; - - b3SharedMemoryStatusHandle statusHandle; - - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); - ret = b3PhysicsParamSetDefaultContactERP(command, defaultContactERP); - - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - } - - Py_INCREF(Py_None); - return Py_None; -} static int pybullet_internalGetBaseVelocity( - int bodyIndex, double baseLinearVelocity[3], double baseAngularVelocity[3],b3PhysicsClientHandle sm) { + int bodyIndex, double baseLinearVelocity[3], double baseAngularVelocity[3], b3PhysicsClientHandle sm) +{ baseLinearVelocity[0] = 0.; baseLinearVelocity[1] = 0.; baseLinearVelocity[2] = 0.; @@ -1352,7 +1388,8 @@ static int pybullet_internalGetBaseVelocity( baseAngularVelocity[1] = 0.; baseAngularVelocity[2] = 0.; - if (0 == sm) { + if (0 == sm) + { PyErr_SetString(SpamError, "Not connected to physics server."); return 0; } @@ -1368,8 +1405,8 @@ static int pybullet_internalGetBaseVelocity( const double* actualStateQdot; // const double* jointReactionForces[]; - - if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) { + if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { PyErr_SetString(SpamError, "getBaseVelocity failed."); return 0; } @@ -1394,7 +1431,6 @@ static int pybullet_internalGetBaseVelocity( baseAngularVelocity[0] = actualStateQdot[3]; baseAngularVelocity[1] = actualStateQdot[4]; baseAngularVelocity[2] = actualStateQdot[5]; - } } return 1; @@ -1403,62 +1439,64 @@ static int pybullet_internalGetBaseVelocity( // Internal function used to get the base position and orientation // Orientation is returned in quaternions static int pybullet_internalGetBasePositionAndOrientation( - int bodyIndex, double basePosition[3], double baseOrientation[4],b3PhysicsClientHandle sm) { - basePosition[0] = 0.; - basePosition[1] = 0.; - basePosition[2] = 0.; + int bodyIndex, double basePosition[3], double baseOrientation[4], b3PhysicsClientHandle sm) +{ + basePosition[0] = 0.; + basePosition[1] = 0.; + basePosition[2] = 0.; - baseOrientation[0] = 0.; - baseOrientation[1] = 0.; - baseOrientation[2] = 0.; - baseOrientation[3] = 1.; + baseOrientation[0] = 0.; + baseOrientation[1] = 0.; + baseOrientation[2] = 0.; + baseOrientation[3] = 1.; - if (0 == sm) { - PyErr_SetString(SpamError, "Not connected to physics server."); - return 0; - } + if (0 == sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return 0; + } - { - { - b3SharedMemoryCommandHandle cmd_handle = - b3RequestActualStateCommandInit(sm, bodyIndex); - b3SharedMemoryStatusHandle status_handle = - b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + { + { + b3SharedMemoryCommandHandle cmd_handle = + b3RequestActualStateCommandInit(sm, bodyIndex); + b3SharedMemoryStatusHandle status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); - const int status_type = b3GetStatusType(status_handle); - const double* actualStateQ; - // const double* jointReactionForces[]; - + const int status_type = b3GetStatusType(status_handle); + const double* actualStateQ; + // const double* jointReactionForces[]; - if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) { - PyErr_SetString(SpamError, "getBasePositionAndOrientation failed."); - return 0; - } + if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { + PyErr_SetString(SpamError, "getBasePositionAndOrientation failed."); + return 0; + } - b3GetStatusActualState( - status_handle, 0 /* body_unique_id */, - 0 /* num_degree_of_freedom_q */, 0 /* num_degree_of_freedom_u */, - 0 /*root_local_inertial_frame*/, &actualStateQ, - 0 /* actual_state_q_dot */, 0 /* joint_reaction_forces */); + b3GetStatusActualState( + status_handle, 0 /* body_unique_id */, + 0 /* num_degree_of_freedom_q */, 0 /* num_degree_of_freedom_u */, + 0 /*root_local_inertial_frame*/, &actualStateQ, + 0 /* actual_state_q_dot */, 0 /* joint_reaction_forces */); - // printf("joint reaction forces="); - // for (i=0; i < (sizeof(jointReactionForces)/sizeof(double)); i++) { - // printf("%f ", jointReactionForces[i]); - // } - // now, position x,y,z = actualStateQ[0],actualStateQ[1],actualStateQ[2] - // and orientation x,y,z,w = - // actualStateQ[3],actualStateQ[4],actualStateQ[5],actualStateQ[6] - basePosition[0] = actualStateQ[0]; - basePosition[1] = actualStateQ[1]; - basePosition[2] = actualStateQ[2]; + // printf("joint reaction forces="); + // for (i=0; i < (sizeof(jointReactionForces)/sizeof(double)); i++) { + // printf("%f ", jointReactionForces[i]); + // } + // now, position x,y,z = actualStateQ[0],actualStateQ[1],actualStateQ[2] + // and orientation x,y,z,w = + // actualStateQ[3],actualStateQ[4],actualStateQ[5],actualStateQ[6] + basePosition[0] = actualStateQ[0]; + basePosition[1] = actualStateQ[1]; + basePosition[2] = actualStateQ[2]; - baseOrientation[0] = actualStateQ[3]; - baseOrientation[1] = actualStateQ[4]; - baseOrientation[2] = actualStateQ[5]; - baseOrientation[3] = actualStateQ[6]; - } - } - return 1; + baseOrientation[0] = actualStateQ[3]; + baseOrientation[1] = actualStateQ[4]; + baseOrientation[2] = actualStateQ[5]; + baseOrientation[3] = actualStateQ[6]; + } + } + return 1; } // Get the positions (x,y,z) and orientation (x,y,z,w) in quaternion @@ -1466,92 +1504,97 @@ static int pybullet_internalGetBasePositionAndOrientation( // Object is retrieved based on body index, which is the order // the object was loaded into the simulation (0-based) static PyObject* pybullet_getBasePositionAndOrientation(PyObject* self, - PyObject* args, PyObject* keywds) { - int bodyUniqueId = -1; - double basePosition[3]; - double baseOrientation[4]; - PyObject* pylistPos; - PyObject* pylistOrientation; - b3PhysicsClientHandle sm = 0; + PyObject* args, PyObject* keywds) +{ + int bodyUniqueId = -1; + double basePosition[3]; + double baseOrientation[4]; + PyObject* pylistPos; + PyObject* pylistOrientation; + b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "bodyUniqueId", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&bodyUniqueId, &physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &bodyUniqueId, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - if (0 == pybullet_internalGetBasePositionAndOrientation( - bodyUniqueId, basePosition, baseOrientation,sm)) { - PyErr_SetString(SpamError, - "GetBasePositionAndOrientation failed."); - return NULL; - } - { - PyObject* item; - int i; - int num = 3; - pylistPos = PyTuple_New(num); - for (i = 0; i < num; i++) { - item = PyFloat_FromDouble(basePosition[i]); - PyTuple_SetItem(pylistPos, i, item); - } - } + if (0 == pybullet_internalGetBasePositionAndOrientation( + bodyUniqueId, basePosition, baseOrientation, sm)) + { + PyErr_SetString(SpamError, + "GetBasePositionAndOrientation failed."); + return NULL; + } - { - PyObject* item; - int i; - int num = 4; - pylistOrientation = PyTuple_New(num); - for (i = 0; i < num; i++) { - item = PyFloat_FromDouble(baseOrientation[i]); - PyTuple_SetItem(pylistOrientation, i, item); - } - } + { + PyObject* item; + int i; + int num = 3; + pylistPos = PyTuple_New(num); + for (i = 0; i < num; i++) + { + item = PyFloat_FromDouble(basePosition[i]); + PyTuple_SetItem(pylistPos, i, item); + } + } - { - PyObject* pylist; - pylist = PyTuple_New(2); - PyTuple_SetItem(pylist, 0, pylistPos); - PyTuple_SetItem(pylist, 1, pylistOrientation); - return pylist; - } + { + PyObject* item; + int i; + int num = 4; + pylistOrientation = PyTuple_New(num); + for (i = 0; i < num; i++) + { + item = PyFloat_FromDouble(baseOrientation[i]); + PyTuple_SetItem(pylistOrientation, i, item); + } + } + + { + PyObject* pylist; + pylist = PyTuple_New(2); + PyTuple_SetItem(pylist, 0, pylistPos); + PyTuple_SetItem(pylist, 1, pylistOrientation); + return pylist; + } } - static PyObject* pybullet_getBaseVelocity(PyObject* self, - PyObject* args, PyObject* keywds) { + PyObject* args, PyObject* keywds) +{ int bodyUniqueId = -1; double baseLinearVelocity[3]; double baseAngularVelocity[3]; - PyObject* pylistLinVel=0; - PyObject* pylistAngVel=0; + PyObject* pylistLinVel = 0; + PyObject* pylistAngVel = 0; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "bodyUniqueId", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&bodyUniqueId, &physicsClientId)) + static char* kwlist[] = {"bodyUniqueId", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &bodyUniqueId, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + if (0 == pybullet_internalGetBaseVelocity( - bodyUniqueId, baseLinearVelocity, baseAngularVelocity,sm)) { + bodyUniqueId, baseLinearVelocity, baseAngularVelocity, sm)) + { PyErr_SetString(SpamError, - "getBaseVelocity failed."); + "getBaseVelocity failed."); return NULL; } @@ -1560,7 +1603,8 @@ static PyObject* pybullet_getBaseVelocity(PyObject* self, int i; int num = 3; pylistLinVel = PyTuple_New(num); - for (i = 0; i < num; i++) { + for (i = 0; i < num; i++) + { item = PyFloat_FromDouble(baseLinearVelocity[i]); PyTuple_SetItem(pylistLinVel, i, item); } @@ -1571,7 +1615,8 @@ static PyObject* pybullet_getBaseVelocity(PyObject* self, int i; int num = 3; pylistAngVel = PyTuple_New(num); - for (i = 0; i < num; i++) { + for (i = 0; i < num; i++) + { item = PyFloat_FromDouble(baseAngularVelocity[i]); PyTuple_SetItem(pylistAngVel, i, item); } @@ -1590,331 +1635,314 @@ static PyObject* pybullet_getNumBodies(PyObject* self, PyObject* args, PyObject* int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist,&physicsClientId)) + static char* kwlist[] = {"physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - int numBodies = b3GetNumBodies(sm); + { + int numBodies = b3GetNumBodies(sm); #if PY_MAJOR_VERSION >= 3 - return PyLong_FromLong(numBodies); + return PyLong_FromLong(numBodies); #else - return PyInt_FromLong(numBodies); + return PyInt_FromLong(numBodies); #endif - } + } } - static PyObject* pybullet_getBodyUniqueId(PyObject* self, PyObject* args, PyObject* keywds) { -int physicsClientId = 0; -int serialIndex=-1; -b3PhysicsClientHandle sm = 0; + int physicsClientId = 0; + int serialIndex = -1; + b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "serialIndex", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&serialIndex, &physicsClientId)) + static char* kwlist[] = {"serialIndex", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &serialIndex, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - { - - int bodyUniqueId = -1; - bodyUniqueId = b3GetBodyUniqueId(sm, serialIndex); + int bodyUniqueId = -1; + bodyUniqueId = b3GetBodyUniqueId(sm, serialIndex); #if PY_MAJOR_VERSION >= 3 - return PyLong_FromLong(bodyUniqueId); + return PyLong_FromLong(bodyUniqueId); #else - return PyInt_FromLong(bodyUniqueId); + return PyInt_FromLong(bodyUniqueId); #endif - } + } } static PyObject* pybullet_getBodyInfo(PyObject* self, PyObject* args, PyObject* keywds) { - { - int bodyUniqueId= -1; - b3PhysicsClientHandle sm = 0; + int bodyUniqueId = -1; + b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "bodyUniqueId", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&bodyUniqueId, &physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &bodyUniqueId, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + struct b3BodyInfo info; + if (b3GetBodyInfo(sm, bodyUniqueId, &info)) + { + PyObject* pyListJointInfo = PyTuple_New(1); + PyTuple_SetItem(pyListJointInfo, 0, PyString_FromString(info.m_baseName)); + return pyListJointInfo; + } + else + { + PyErr_SetString(SpamError, "Couldn't get body info"); + return NULL; + } + } + } + + PyErr_SetString(SpamError, "error in getBodyInfo."); + return NULL; +} + +static PyObject* pybullet_getConstraintInfo(PyObject* self, PyObject* args, PyObject* keywds) +{ + { + int constraintUniqueId = -1; + b3PhysicsClientHandle sm = 0; + + int physicsClientId = 0; + static char* kwlist[] = {"constraintUniqueId", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &constraintUniqueId, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + struct b3UserConstraint constraintInfo; + + if (b3GetUserConstraintInfo(sm, constraintUniqueId, &constraintInfo)) + { + PyObject* pyListConstraintInfo = PyTuple_New(11); + + PyTuple_SetItem(pyListConstraintInfo, 0, PyLong_FromLong(constraintInfo.m_parentBodyIndex)); + PyTuple_SetItem(pyListConstraintInfo, 1, PyLong_FromLong(constraintInfo.m_parentJointIndex)); + PyTuple_SetItem(pyListConstraintInfo, 2, PyLong_FromLong(constraintInfo.m_childBodyIndex)); + PyTuple_SetItem(pyListConstraintInfo, 3, PyLong_FromLong(constraintInfo.m_childJointIndex)); + PyTuple_SetItem(pyListConstraintInfo, 4, PyLong_FromLong(constraintInfo.m_jointType)); + + { + PyObject* axisObj = PyTuple_New(3); + PyTuple_SetItem(axisObj, 0, PyFloat_FromDouble(constraintInfo.m_jointAxis[0])); + PyTuple_SetItem(axisObj, 1, PyFloat_FromDouble(constraintInfo.m_jointAxis[1])); + PyTuple_SetItem(axisObj, 2, PyFloat_FromDouble(constraintInfo.m_jointAxis[2])); + PyTuple_SetItem(pyListConstraintInfo, 5, axisObj); + } + { + PyObject* parentFramePositionObj = PyTuple_New(3); + PyTuple_SetItem(parentFramePositionObj, 0, PyFloat_FromDouble(constraintInfo.m_parentFrame[0])); + PyTuple_SetItem(parentFramePositionObj, 1, PyFloat_FromDouble(constraintInfo.m_parentFrame[1])); + PyTuple_SetItem(parentFramePositionObj, 2, PyFloat_FromDouble(constraintInfo.m_parentFrame[2])); + PyTuple_SetItem(pyListConstraintInfo, 6, parentFramePositionObj); + } + { + PyObject* childFramePositionObj = PyTuple_New(3); + PyTuple_SetItem(childFramePositionObj, 0, PyFloat_FromDouble(constraintInfo.m_childFrame[0])); + PyTuple_SetItem(childFramePositionObj, 1, PyFloat_FromDouble(constraintInfo.m_childFrame[1])); + PyTuple_SetItem(childFramePositionObj, 2, PyFloat_FromDouble(constraintInfo.m_childFrame[2])); + PyTuple_SetItem(pyListConstraintInfo, 7, childFramePositionObj); + } + { + PyObject* parentFrameOrientationObj = PyTuple_New(4); + PyTuple_SetItem(parentFrameOrientationObj, 0, PyFloat_FromDouble(constraintInfo.m_parentFrame[3])); + PyTuple_SetItem(parentFrameOrientationObj, 1, PyFloat_FromDouble(constraintInfo.m_parentFrame[4])); + PyTuple_SetItem(parentFrameOrientationObj, 2, PyFloat_FromDouble(constraintInfo.m_parentFrame[5])); + PyTuple_SetItem(parentFrameOrientationObj, 3, PyFloat_FromDouble(constraintInfo.m_parentFrame[6])); + PyTuple_SetItem(pyListConstraintInfo, 8, parentFrameOrientationObj); + } + { + PyObject* childFrameOrientation = PyTuple_New(4); + PyTuple_SetItem(childFrameOrientation, 0, PyFloat_FromDouble(constraintInfo.m_childFrame[3])); + PyTuple_SetItem(childFrameOrientation, 1, PyFloat_FromDouble(constraintInfo.m_childFrame[4])); + PyTuple_SetItem(childFrameOrientation, 2, PyFloat_FromDouble(constraintInfo.m_childFrame[5])); + PyTuple_SetItem(childFrameOrientation, 3, PyFloat_FromDouble(constraintInfo.m_childFrame[6])); + PyTuple_SetItem(pyListConstraintInfo, 9, childFrameOrientation); + } + PyTuple_SetItem(pyListConstraintInfo, 10, PyFloat_FromDouble(constraintInfo.m_maxAppliedForce)); + + return pyListConstraintInfo; + } + else + { + PyErr_SetString(SpamError, "Couldn't get user constraint info"); + return NULL; + } + } + } + + PyErr_SetString(SpamError, "error in getConstraintInfo."); + return NULL; +} + +static PyObject* pybullet_getNumConstraints(PyObject* self, PyObject* args, PyObject* keywds) +{ + int numConstraints = 0; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - { - struct b3BodyInfo info; - if (b3GetBodyInfo(sm,bodyUniqueId,&info)) - { - PyObject* pyListJointInfo = PyTuple_New(1); - PyTuple_SetItem(pyListJointInfo, 0, PyString_FromString(info.m_baseName)); - return pyListJointInfo; - } else - { - PyErr_SetString(SpamError, "Couldn't get body info"); - return NULL; - } - } - } + numConstraints = b3GetNumUserConstraints(sm); - PyErr_SetString(SpamError, "error in getBodyInfo."); - return NULL; -} - - -static PyObject* pybullet_getConstraintInfo(PyObject* self, PyObject* args, PyObject* keywds) -{ - - { - int constraintUniqueId= -1; - b3PhysicsClientHandle sm = 0; - - int physicsClientId = 0; - static char *kwlist[] = { "constraintUniqueId", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&constraintUniqueId, &physicsClientId)) - { - return NULL; - } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - { - struct b3UserConstraint constraintInfo; - - if (b3GetUserConstraintInfo(sm,constraintUniqueId, &constraintInfo)) - { - PyObject* pyListConstraintInfo = PyTuple_New(11); - - PyTuple_SetItem(pyListConstraintInfo,0,PyLong_FromLong(constraintInfo.m_parentBodyIndex)); - PyTuple_SetItem(pyListConstraintInfo,1,PyLong_FromLong(constraintInfo.m_parentJointIndex)); - PyTuple_SetItem(pyListConstraintInfo,2,PyLong_FromLong(constraintInfo.m_childBodyIndex)); - PyTuple_SetItem(pyListConstraintInfo,3,PyLong_FromLong(constraintInfo.m_childJointIndex)); - PyTuple_SetItem(pyListConstraintInfo,4,PyLong_FromLong(constraintInfo.m_jointType)); - - { - PyObject* axisObj = PyTuple_New(3); - PyTuple_SetItem(axisObj,0,PyFloat_FromDouble(constraintInfo.m_jointAxis[0])); - PyTuple_SetItem(axisObj,1,PyFloat_FromDouble(constraintInfo.m_jointAxis[1])); - PyTuple_SetItem(axisObj,2,PyFloat_FromDouble(constraintInfo.m_jointAxis[2])); - PyTuple_SetItem(pyListConstraintInfo,5,axisObj); - } - { - PyObject* parentFramePositionObj = PyTuple_New(3); - PyTuple_SetItem(parentFramePositionObj,0,PyFloat_FromDouble(constraintInfo.m_parentFrame[0])); - PyTuple_SetItem(parentFramePositionObj,1,PyFloat_FromDouble(constraintInfo.m_parentFrame[1])); - PyTuple_SetItem(parentFramePositionObj,2,PyFloat_FromDouble(constraintInfo.m_parentFrame[2])); - PyTuple_SetItem(pyListConstraintInfo,6,parentFramePositionObj); - } - { - PyObject* childFramePositionObj = PyTuple_New(3); - PyTuple_SetItem(childFramePositionObj,0,PyFloat_FromDouble(constraintInfo.m_childFrame[0])); - PyTuple_SetItem(childFramePositionObj,1,PyFloat_FromDouble(constraintInfo.m_childFrame[1])); - PyTuple_SetItem(childFramePositionObj,2,PyFloat_FromDouble(constraintInfo.m_childFrame[2])); - PyTuple_SetItem(pyListConstraintInfo,7,childFramePositionObj); - } - { - PyObject* parentFrameOrientationObj = PyTuple_New(4); - PyTuple_SetItem(parentFrameOrientationObj,0,PyFloat_FromDouble(constraintInfo.m_parentFrame[3])); - PyTuple_SetItem(parentFrameOrientationObj,1,PyFloat_FromDouble(constraintInfo.m_parentFrame[4])); - PyTuple_SetItem(parentFrameOrientationObj,2,PyFloat_FromDouble(constraintInfo.m_parentFrame[5])); - PyTuple_SetItem(parentFrameOrientationObj,3,PyFloat_FromDouble(constraintInfo.m_parentFrame[6])); - PyTuple_SetItem(pyListConstraintInfo,8,parentFrameOrientationObj); - } - { - PyObject* childFrameOrientation = PyTuple_New(4); - PyTuple_SetItem(childFrameOrientation,0,PyFloat_FromDouble(constraintInfo.m_childFrame[3])); - PyTuple_SetItem(childFrameOrientation,1,PyFloat_FromDouble(constraintInfo.m_childFrame[4])); - PyTuple_SetItem(childFrameOrientation,2,PyFloat_FromDouble(constraintInfo.m_childFrame[5])); - PyTuple_SetItem(childFrameOrientation,3,PyFloat_FromDouble(constraintInfo.m_childFrame[6])); - PyTuple_SetItem(pyListConstraintInfo,9,childFrameOrientation); - } - PyTuple_SetItem(pyListConstraintInfo,10,PyFloat_FromDouble(constraintInfo.m_maxAppliedForce)); - - return pyListConstraintInfo; - } else - { - PyErr_SetString(SpamError, "Couldn't get user constraint info"); - return NULL; - } - } - } - - PyErr_SetString(SpamError, "error in getConstraintInfo."); - return NULL; -} - - -static PyObject* pybullet_getNumConstraints(PyObject* self, PyObject* args, PyObject* keywds) -{ - int numConstraints = 0; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) - { - return NULL; - } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - numConstraints = b3GetNumUserConstraints(sm); - #if PY_MAJOR_VERSION >= 3 - return PyLong_FromLong(numConstraints); + return PyLong_FromLong(numConstraints); #else - return PyInt_FromLong(numConstraints); + return PyInt_FromLong(numConstraints); #endif - - } - - // Return the number of joints in an object based on // body index; body index is based on order of sequence // the object is loaded into simulation -static PyObject* pybullet_getNumJoints(PyObject* self, PyObject* args, PyObject* keywds) +static PyObject* pybullet_getNumJoints(PyObject* self, PyObject* args, PyObject* keywds) { int bodyUniqueId = -1; - int numJoints = 0; + int numJoints = 0; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "bodyUniqueId", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&bodyUniqueId, &physicsClientId)) + static char* kwlist[] = {"bodyUniqueId", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &bodyUniqueId, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - numJoints = b3GetNumJoints(sm, bodyUniqueId); + + numJoints = b3GetNumJoints(sm, bodyUniqueId); #if PY_MAJOR_VERSION >= 3 - return PyLong_FromLong(numJoints); + return PyLong_FromLong(numJoints); #else - return PyInt_FromLong(numJoints); + return PyInt_FromLong(numJoints); #endif - } // Initalize all joint positions given a list of values -static PyObject* pybullet_resetJointState(PyObject* self, PyObject* args, PyObject* keywds) { - +static PyObject* pybullet_resetJointState(PyObject* self, PyObject* args, PyObject* keywds) { - int bodyUniqueId; - int jointIndex; - double targetValue; - b3PhysicsClientHandle sm = 0; - - int physicsClientId = 0; - static char *kwlist[] = { "bodyUniqueId", "jointIndex", "targetValue","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|i", kwlist,&bodyUniqueId, &jointIndex, &targetValue, &physicsClientId)) { - return NULL; - } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - - { - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int numJoints; - - numJoints = b3GetNumJoints(sm, bodyUniqueId); - if ((jointIndex >= numJoints) || (jointIndex < 0)) { - PyErr_SetString(SpamError, "Joint index out-of-range."); - return NULL; - } - - commandHandle = b3CreatePoseCommandInit(sm, bodyUniqueId); - - b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex, - targetValue); - - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - Py_INCREF(Py_None); - return Py_None; - } - } - PyErr_SetString(SpamError, "error in resetJointState."); - return NULL; -} - - - - -static PyObject* pybullet_resetBaseVelocity(PyObject* self, PyObject* args, PyObject *keywds) -{ - static char *kwlist[] = { "objectUniqueId", "linearVelocity", "angularVelocity","physicsClientId", NULL }; - - - { - int bodyIndex=0; - PyObject* linVelObj=0; - PyObject* angVelObj=0; - double linVel[3] = { 0, 0, 0 }; - double angVel[3] = { 0, 0, 0 }; - int physicsClientId = 0; + int bodyUniqueId; + int jointIndex; + double targetValue; b3PhysicsClientHandle sm = 0; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOi", kwlist, &bodyIndex, &linVelObj, &angVelObj,&physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "jointIndex", "targetValue", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|i", kwlist, &bodyUniqueId, &jointIndex, &targetValue, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int numJoints; + + numJoints = b3GetNumJoints(sm, bodyUniqueId); + if ((jointIndex >= numJoints) || (jointIndex < 0)) + { + PyErr_SetString(SpamError, "Joint index out-of-range."); + return NULL; + } + + commandHandle = b3CreatePoseCommandInit(sm, bodyUniqueId); + + b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex, + targetValue); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + Py_INCREF(Py_None); + return Py_None; + } + } + PyErr_SetString(SpamError, "error in resetJointState."); + return NULL; +} + +static PyObject* pybullet_resetBaseVelocity(PyObject* self, PyObject* args, PyObject* keywds) +{ + static char* kwlist[] = {"objectUniqueId", "linearVelocity", "angularVelocity", "physicsClientId", NULL}; + + { + int bodyIndex = 0; + PyObject* linVelObj = 0; + PyObject* angVelObj = 0; + double linVel[3] = {0, 0, 0}; + double angVel[3] = {0, 0, 0}; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOi", kwlist, &bodyIndex, &linVelObj, &angVelObj, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } if (linVelObj || angVelObj) { - b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; @@ -1946,87 +1974,93 @@ static PyObject* pybullet_resetBaseVelocity(PyObject* self, PyObject* args, PyOb return NULL; } - - // Reset the position and orientation of the base/root link, position [x,y,z] // and orientation quaternion [x,y,z,w] static PyObject* pybullet_resetBasePositionAndOrientation(PyObject* self, - PyObject* args, PyObject* keywds) { - - { - int bodyUniqueId; - PyObject* posObj; - PyObject* ornObj; - double pos[3]; - double orn[4]; // as a quaternion - b3PhysicsClientHandle sm = 0; - - int physicsClientId = 0; - static char *kwlist[] = { "bodyUniqueId", "posObj", "ornObj", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOO|i", kwlist,&bodyUniqueId, &posObj, &ornObj, &physicsClientId)) + PyObject* args, PyObject* keywds) +{ { - return NULL; + int bodyUniqueId; + PyObject* posObj; + PyObject* ornObj; + double pos[3]; + double orn[4]; // as a quaternion + b3PhysicsClientHandle sm = 0; + + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "posObj", "ornObj", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOO|i", kwlist, &bodyUniqueId, &posObj, &ornObj, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + + { + PyObject* seq; + int len, i; + seq = PySequence_Fast(posObj, "expected a sequence"); + len = PySequence_Size(posObj); + if (len == 3) + { + for (i = 0; i < 3; i++) + { + pos[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + } + else + { + PyErr_SetString(SpamError, "position needs a 3 coordinates [x,y,z]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + } + + { + PyObject* seq; + int len, i; + seq = PySequence_Fast(ornObj, "expected a sequence"); + len = PySequence_Size(ornObj); + if (len == 4) + { + for (i = 0; i < 4; i++) + { + orn[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + } + else + { + PyErr_SetString( + SpamError, + "orientation needs a 4 coordinates, quaternion [x,y,z,w]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + } + + commandHandle = b3CreatePoseCommandInit(sm, bodyUniqueId); + + b3CreatePoseCommandSetBasePosition(commandHandle, pos[0], pos[1], pos[2]); + b3CreatePoseCommandSetBaseOrientation(commandHandle, orn[0], orn[1], + orn[2], orn[3]); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + Py_INCREF(Py_None); + return Py_None; + } } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - { - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - - { - PyObject* seq; - int len, i; - seq = PySequence_Fast(posObj, "expected a sequence"); - len = PySequence_Size(posObj); - if (len == 3) { - for (i = 0; i < 3; i++) { - pos[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - } else { - PyErr_SetString(SpamError, "position needs a 3 coordinates [x,y,z]."); - Py_DECREF(seq); - return NULL; - } - Py_DECREF(seq); - } - - { - PyObject* seq; - int len, i; - seq = PySequence_Fast(ornObj, "expected a sequence"); - len = PySequence_Size(ornObj); - if (len == 4) { - for (i = 0; i < 4; i++) { - orn[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - } else { - PyErr_SetString( - SpamError, - "orientation needs a 4 coordinates, quaternion [x,y,z,w]."); - Py_DECREF(seq); - return NULL; - } - Py_DECREF(seq); - } - - commandHandle = b3CreatePoseCommandInit(sm, bodyUniqueId); - - b3CreatePoseCommandSetBasePosition(commandHandle, pos[0], pos[1], pos[2]); - b3CreatePoseCommandSetBaseOrientation(commandHandle, orn[0], orn[1], - orn[2], orn[3]); - - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - Py_INCREF(Py_None); - return Py_None; - } - } - PyErr_SetString(SpamError, "error in resetJointState."); - return NULL; + PyErr_SetString(SpamError, "error in resetJointState."); + return NULL; } // Get the a single joint info for a specific bodyIndex @@ -2043,67 +2077,70 @@ static PyObject* pybullet_resetBasePositionAndOrientation(PyObject* self, // [int, str, int, int, int, int, float, float] // // TODO(hellojas): get joint positions for a body -static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args,PyObject* keywds) { - PyObject* pyListJointInfo; +static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject* keywds) +{ + PyObject* pyListJointInfo; - struct b3JointInfo info; + struct b3JointInfo info; - int bodyUniqueId = -1; - int jointIndex = -1; - int jointInfoSize = 8; // size of struct b3JointInfo -b3PhysicsClientHandle sm = 0; -int physicsClientId = 0; - static char *kwlist[] = { "bodyUniqueId", "jointIndex", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist,&bodyUniqueId, &jointIndex, &physicsClientId)) + int bodyUniqueId = -1; + int jointIndex = -1; + int jointInfoSize = 8; // size of struct b3JointInfo + b3PhysicsClientHandle sm = 0; + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "jointIndex", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &jointIndex, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { { - // printf("body index = %d, joint index =%d\n", bodyIndex, jointIndex); + { + // printf("body index = %d, joint index =%d\n", bodyIndex, jointIndex); - pyListJointInfo = PyTuple_New(jointInfoSize); + pyListJointInfo = PyTuple_New(jointInfoSize); - if (b3GetJointInfo(sm, bodyUniqueId, jointIndex, &info)) { - // printf("Joint%d %s, type %d, at q-index %d and u-index %d\n", - // info.m_jointIndex, - // info.m_jointName, - // info.m_jointType, - // info.m_qIndex, - // info.m_uIndex); - // printf(" flags=%d jointDamping=%f jointFriction=%f\n", - // info.m_flags, - // info.m_jointDamping, - // info.m_jointFriction); - PyTuple_SetItem(pyListJointInfo, 0, PyInt_FromLong(info.m_jointIndex)); - PyTuple_SetItem(pyListJointInfo, 1, - PyString_FromString(info.m_jointName)); - PyTuple_SetItem(pyListJointInfo, 2, PyInt_FromLong(info.m_jointType)); - PyTuple_SetItem(pyListJointInfo, 3, PyInt_FromLong(info.m_qIndex)); - PyTuple_SetItem(pyListJointInfo, 4, PyInt_FromLong(info.m_uIndex)); - PyTuple_SetItem(pyListJointInfo, 5, PyInt_FromLong(info.m_flags)); - PyTuple_SetItem(pyListJointInfo, 6, - PyFloat_FromDouble(info.m_jointDamping)); - PyTuple_SetItem(pyListJointInfo, 7, - PyFloat_FromDouble(info.m_jointFriction)); - return pyListJointInfo; - } else { - PyErr_SetString(SpamError, "GetJointInfo failed."); - return NULL; - } - } - } + if (b3GetJointInfo(sm, bodyUniqueId, jointIndex, &info)) + { + // printf("Joint%d %s, type %d, at q-index %d and u-index %d\n", + // info.m_jointIndex, + // info.m_jointName, + // info.m_jointType, + // info.m_qIndex, + // info.m_uIndex); + // printf(" flags=%d jointDamping=%f jointFriction=%f\n", + // info.m_flags, + // info.m_jointDamping, + // info.m_jointFriction); + PyTuple_SetItem(pyListJointInfo, 0, PyInt_FromLong(info.m_jointIndex)); + PyTuple_SetItem(pyListJointInfo, 1, + PyString_FromString(info.m_jointName)); + PyTuple_SetItem(pyListJointInfo, 2, PyInt_FromLong(info.m_jointType)); + PyTuple_SetItem(pyListJointInfo, 3, PyInt_FromLong(info.m_qIndex)); + PyTuple_SetItem(pyListJointInfo, 4, PyInt_FromLong(info.m_uIndex)); + PyTuple_SetItem(pyListJointInfo, 5, PyInt_FromLong(info.m_flags)); + PyTuple_SetItem(pyListJointInfo, 6, + PyFloat_FromDouble(info.m_jointDamping)); + PyTuple_SetItem(pyListJointInfo, 7, + PyFloat_FromDouble(info.m_jointFriction)); + return pyListJointInfo; + } + else + { + PyErr_SetString(SpamError, "GetJointInfo failed."); + return NULL; + } + } + } - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } // Returns the state of a specific joint in a given bodyIndex @@ -2119,212 +2156,219 @@ int physicsClientId = 0; // TODO(hellojas): check accuracy of position and velocity // TODO(hellojas): check force torque values -static PyObject* pybullet_getJointState(PyObject* self, PyObject* args,PyObject* keywds) { - PyObject* pyListJointForceTorque; - PyObject* pyListJointState; +static PyObject* pybullet_getJointState(PyObject* self, PyObject* args, PyObject* keywds) +{ + PyObject* pyListJointForceTorque; + PyObject* pyListJointState; + struct b3JointSensorState sensorState; - struct b3JointSensorState sensorState; - - int bodyUniqueId = -1; - int jointIndex = -1; - int sensorStateSize = 4; // size of struct b3JointSensorState - int forceTorqueSize = 6; // size of force torque list from b3JointSensorState - int j; + int bodyUniqueId = -1; + int jointIndex = -1; + int sensorStateSize = 4; // size of struct b3JointSensorState + int forceTorqueSize = 6; // size of force torque list from b3JointSensorState + int j; b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "bodyUniqueId", "jointIndex","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist,&bodyUniqueId, &jointIndex, &physicsClientId)) + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "jointIndex", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &jointIndex, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - { - int status_type = 0; - b3SharedMemoryCommandHandle cmd_handle; - b3SharedMemoryStatusHandle status_handle; + { + int status_type = 0; + b3SharedMemoryCommandHandle cmd_handle; + b3SharedMemoryStatusHandle status_handle; + if (bodyUniqueId < 0) + { + PyErr_SetString(SpamError, "getJointState failed; invalid bodyIndex"); + return NULL; + } + if (jointIndex < 0) + { + PyErr_SetString(SpamError, "getJointState failed; invalid jointIndex"); + return NULL; + } - if (bodyUniqueId < 0) { - PyErr_SetString(SpamError, "getJointState failed; invalid bodyIndex"); - return NULL; - } - if (jointIndex < 0) { - PyErr_SetString(SpamError, "getJointState failed; invalid jointIndex"); - return NULL; - } + cmd_handle = + b3RequestActualStateCommandInit(sm, bodyUniqueId); + status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); - - cmd_handle = - b3RequestActualStateCommandInit(sm, bodyUniqueId); - status_handle = - b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + status_type = b3GetStatusType(status_handle); + if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { + PyErr_SetString(SpamError, "getJointState failed."); + return NULL; + } - status_type = b3GetStatusType(status_handle); - if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) { - PyErr_SetString(SpamError, "getJointState failed."); - return NULL; - } + pyListJointState = PyTuple_New(sensorStateSize); + pyListJointForceTorque = PyTuple_New(forceTorqueSize); - pyListJointState = PyTuple_New(sensorStateSize); - pyListJointForceTorque = PyTuple_New(forceTorqueSize); + if (b3GetJointState(sm, status_handle, jointIndex, &sensorState)) + { + PyTuple_SetItem(pyListJointState, 0, + PyFloat_FromDouble(sensorState.m_jointPosition)); + PyTuple_SetItem(pyListJointState, 1, + PyFloat_FromDouble(sensorState.m_jointVelocity)); - if (b3GetJointState(sm, status_handle, jointIndex, &sensorState)) - { - PyTuple_SetItem(pyListJointState, 0, - PyFloat_FromDouble(sensorState.m_jointPosition)); - PyTuple_SetItem(pyListJointState, 1, - PyFloat_FromDouble(sensorState.m_jointVelocity)); + for (j = 0; j < forceTorqueSize; j++) + { + PyTuple_SetItem(pyListJointForceTorque, j, + PyFloat_FromDouble(sensorState.m_jointForceTorque[j])); + } - for (j = 0; j < forceTorqueSize; j++) { - PyTuple_SetItem(pyListJointForceTorque, j, - PyFloat_FromDouble(sensorState.m_jointForceTorque[j])); - } + PyTuple_SetItem(pyListJointState, 2, pyListJointForceTorque); - PyTuple_SetItem(pyListJointState, 2, pyListJointForceTorque); + PyTuple_SetItem(pyListJointState, 3, + PyFloat_FromDouble(sensorState.m_jointMotorTorque)); - PyTuple_SetItem(pyListJointState, 3, - PyFloat_FromDouble(sensorState.m_jointMotorTorque)); + return pyListJointState; + } + else + { + PyErr_SetString(SpamError, "getJointState failed (2)."); + return NULL; + } + } + } - return pyListJointState; - } else - { - PyErr_SetString(SpamError, "getJointState failed (2)."); - return NULL; - } - } - } - - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } -static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args,PyObject* keywds) { - PyObject* pyLinkState; - PyObject* pyLinkStateWorldPosition; - PyObject* pyLinkStateWorldOrientation; - PyObject* pyLinkStateLocalInertialPosition; - PyObject* pyLinkStateLocalInertialOrientation; - PyObject* pyLinkStateWorldLinkFramePosition; - PyObject* pyLinkStateWorldLinkFrameOrientation; +static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject* keywds) +{ + PyObject* pyLinkState; + PyObject* pyLinkStateWorldPosition; + PyObject* pyLinkStateWorldOrientation; + PyObject* pyLinkStateLocalInertialPosition; + PyObject* pyLinkStateLocalInertialOrientation; + PyObject* pyLinkStateWorldLinkFramePosition; + PyObject* pyLinkStateWorldLinkFrameOrientation; - struct b3LinkState linkState; + struct b3LinkState linkState; - int bodyUniqueId = -1; - int linkIndex = -1; - int i; -b3PhysicsClientHandle sm = 0; + int bodyUniqueId = -1; + int linkIndex = -1; + int i; + b3PhysicsClientHandle sm = 0; - int physicsClientId = 0; - static char *kwlist[] = { "bodyUniqueId", "linkIndex", "physicsClientId", NULL }; + int physicsClientId = 0; + static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { + { - int status_type = 0; - b3SharedMemoryCommandHandle cmd_handle; - b3SharedMemoryStatusHandle status_handle; + { + int status_type = 0; + b3SharedMemoryCommandHandle cmd_handle; + b3SharedMemoryStatusHandle status_handle; - if (bodyUniqueId < 0) { - PyErr_SetString(SpamError, "getLinkState failed; invalid bodyIndex"); - return NULL; - } - if (linkIndex < 0) { - PyErr_SetString(SpamError, "getLinkState failed; invalid linkIndex"); - return NULL; - } + if (bodyUniqueId < 0) + { + PyErr_SetString(SpamError, "getLinkState failed; invalid bodyIndex"); + return NULL; + } + if (linkIndex < 0) + { + PyErr_SetString(SpamError, "getLinkState failed; invalid linkIndex"); + return NULL; + } + cmd_handle = + b3RequestActualStateCommandInit(sm, bodyUniqueId); + status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); - cmd_handle = - b3RequestActualStateCommandInit(sm, bodyUniqueId); - status_handle = - b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + status_type = b3GetStatusType(status_handle); + if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { + PyErr_SetString(SpamError, "getLinkState failed."); + return NULL; + } - status_type = b3GetStatusType(status_handle); - if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) { - PyErr_SetString(SpamError, "getLinkState failed."); - return NULL; - } + if (b3GetLinkState(sm, status_handle, linkIndex, &linkState)) + { + pyLinkStateWorldPosition = PyTuple_New(3); + for (i = 0; i < 3; ++i) + { + PyTuple_SetItem(pyLinkStateWorldPosition, i, + PyFloat_FromDouble(linkState.m_worldPosition[i])); + } - if (b3GetLinkState(sm, status_handle, linkIndex, &linkState)) - { - pyLinkStateWorldPosition = PyTuple_New(3); - for (i = 0; i < 3; ++i) { - PyTuple_SetItem(pyLinkStateWorldPosition, i, - PyFloat_FromDouble(linkState.m_worldPosition[i])); - } + pyLinkStateWorldOrientation = PyTuple_New(4); + for (i = 0; i < 4; ++i) + { + PyTuple_SetItem(pyLinkStateWorldOrientation, i, + PyFloat_FromDouble(linkState.m_worldOrientation[i])); + } - pyLinkStateWorldOrientation = PyTuple_New(4); - for (i = 0; i < 4; ++i) { - PyTuple_SetItem(pyLinkStateWorldOrientation, i, - PyFloat_FromDouble(linkState.m_worldOrientation[i])); - } + pyLinkStateLocalInertialPosition = PyTuple_New(3); + for (i = 0; i < 3; ++i) + { + PyTuple_SetItem(pyLinkStateLocalInertialPosition, i, + PyFloat_FromDouble(linkState.m_localInertialPosition[i])); + } - pyLinkStateLocalInertialPosition = PyTuple_New(3); - for (i = 0; i < 3; ++i) { - PyTuple_SetItem(pyLinkStateLocalInertialPosition, i, - PyFloat_FromDouble(linkState.m_localInertialPosition[i])); - } + pyLinkStateLocalInertialOrientation = PyTuple_New(4); + for (i = 0; i < 4; ++i) + { + PyTuple_SetItem(pyLinkStateLocalInertialOrientation, i, + PyFloat_FromDouble(linkState.m_localInertialOrientation[i])); + } - pyLinkStateLocalInertialOrientation = PyTuple_New(4); - for (i = 0; i < 4; ++i) { - PyTuple_SetItem(pyLinkStateLocalInertialOrientation, i, - PyFloat_FromDouble(linkState.m_localInertialOrientation[i])); - } + pyLinkStateWorldLinkFramePosition = PyTuple_New(3); + for (i = 0; i < 3; ++i) + { + PyTuple_SetItem(pyLinkStateWorldLinkFramePosition, i, + PyFloat_FromDouble(linkState.m_worldLinkFramePosition[i])); + } - pyLinkStateWorldLinkFramePosition = PyTuple_New(3); - for (i = 0; i < 3; ++i) { - PyTuple_SetItem(pyLinkStateWorldLinkFramePosition , i, - PyFloat_FromDouble(linkState.m_worldLinkFramePosition[i])); - } + pyLinkStateWorldLinkFrameOrientation = PyTuple_New(4); + for (i = 0; i < 4; ++i) + { + PyTuple_SetItem(pyLinkStateWorldLinkFrameOrientation, i, + PyFloat_FromDouble(linkState.m_worldLinkFrameOrientation[i])); + } - pyLinkStateWorldLinkFrameOrientation = PyTuple_New(4); - for (i = 0; i < 4; ++i) { - PyTuple_SetItem(pyLinkStateWorldLinkFrameOrientation, i, - PyFloat_FromDouble(linkState.m_worldLinkFrameOrientation[i])); - } + pyLinkState = PyTuple_New(6); + PyTuple_SetItem(pyLinkState, 0, pyLinkStateWorldPosition); + PyTuple_SetItem(pyLinkState, 1, pyLinkStateWorldOrientation); + PyTuple_SetItem(pyLinkState, 2, pyLinkStateLocalInertialPosition); + PyTuple_SetItem(pyLinkState, 3, pyLinkStateLocalInertialOrientation); + PyTuple_SetItem(pyLinkState, 4, pyLinkStateWorldLinkFramePosition); + PyTuple_SetItem(pyLinkState, 5, pyLinkStateWorldLinkFrameOrientation); + return pyLinkState; + } + } + } - pyLinkState = PyTuple_New(6); - PyTuple_SetItem(pyLinkState, 0, pyLinkStateWorldPosition); - PyTuple_SetItem(pyLinkState, 1, pyLinkStateWorldOrientation); - PyTuple_SetItem(pyLinkState, 2, pyLinkStateLocalInertialPosition); - PyTuple_SetItem(pyLinkState, 3, pyLinkStateLocalInertialOrientation); - PyTuple_SetItem(pyLinkState, 4, pyLinkStateWorldLinkFramePosition ); - PyTuple_SetItem(pyLinkState, 5, pyLinkStateWorldLinkFrameOrientation); - - return pyLinkState; - } - } - } - - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } - -static PyObject* pybullet_readUserDebugParameter(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_readUserDebugParameter(PyObject* self, PyObject* args, PyObject* keywds) { - b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; int statusType; @@ -2332,28 +2376,28 @@ static PyObject* pybullet_readUserDebugParameter(PyObject* self, PyObject* args, int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "itemUniqueId", "physicsClientId", NULL }; + static char* kwlist[] = {"itemUniqueId", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&itemUniqueId, &physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &itemUniqueId, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - commandHandle = b3InitUserDebugReadParameter(sm,itemUniqueId); + commandHandle = b3InitUserDebugReadParameter(sm, itemUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_USER_DEBUG_DRAW_PARAMETER_COMPLETED) + if (statusType == CMD_USER_DEBUG_DRAW_PARAMETER_COMPLETED) { - double paramValue=0.f; - int ok = b3GetStatusDebugParameterValue(statusHandle,¶mValue); + double paramValue = 0.f; + int ok = b3GetStatusDebugParameterValue(statusHandle, ¶mValue); if (ok) { PyObject* item = PyFloat_FromDouble(paramValue); @@ -2363,220 +2407,200 @@ static PyObject* pybullet_readUserDebugParameter(PyObject* self, PyObject* args, PyErr_SetString(SpamError, "Failed to read parameter."); return NULL; - } - - -static PyObject* pybullet_addUserDebugParameter(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_addUserDebugParameter(PyObject* self, PyObject* args, PyObject* keywds) { - - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; - char* text; + char* text; - - double rangeMin = 0.f; - double rangeMax = 1.f; - double startValue = 0.f; - int physicsClientId = 0; - b3PhysicsClientHandle sm=0; - static char *kwlist[] = { "paramName", "rangeMin", "rangeMax","startValue", "physicsClientId", NULL }; + double rangeMin = 0.f; + double rangeMax = 1.f; + double startValue = 0.f; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"paramName", "rangeMin", "rangeMax", "startValue", "physicsClientId", NULL}; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|dddi", kwlist, &text, &rangeMin, &rangeMax,&startValue, &physicsClientId)) - { - return NULL; - } + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|dddi", kwlist, &text, &rangeMin, &rangeMax, &startValue, &physicsClientId)) + { + return NULL; + } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - commandHandle = b3InitUserDebugAddParameter(sm,text,rangeMin,rangeMax, startValue); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - - if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) + commandHandle = b3InitUserDebugAddParameter(sm, text, rangeMin, rangeMax, startValue); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + + if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) { int debugItemUniqueId = b3GetDebugItemUniqueId(statusHandle); PyObject* item = PyInt_FromLong(debugItemUniqueId); return item; } - - PyErr_SetString(SpamError, "Error in addUserDebugParameter."); - return NULL; + PyErr_SetString(SpamError, "Error in addUserDebugParameter."); + return NULL; } - -static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObject* keywds) { - - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - int res = 0; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int res = 0; -char* text; - double posXYZ[3]; - double colorRGB[3]={1,1,1}; + char* text; + double posXYZ[3]; + double colorRGB[3] = {1, 1, 1}; - - PyObject* textPositionObj=0; - PyObject* textColorRGBObj=0; - double textSize = 1.f; - double lifeTime = 0.f; - int physicsClientId = 0; - b3PhysicsClientHandle sm=0; - static char *kwlist[] = { "text", "textPosition", "textColorRGB", "textSize", "lifeTime","physicsClientId", NULL }; + PyObject* textPositionObj = 0; + PyObject* textColorRGBObj = 0; + double textSize = 1.f; + double lifeTime = 0.f; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"text", "textPosition", "textColorRGB", "textSize", "lifeTime", "physicsClientId", NULL}; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "sO|Oddi", kwlist, &text, &textPositionObj, &textColorRGBObj,&textSize, &lifeTime,&physicsClientId)) - { - return NULL; - } + if (!PyArg_ParseTupleAndKeywords(args, keywds, "sO|Oddi", kwlist, &text, &textPositionObj, &textColorRGBObj, &textSize, &lifeTime, &physicsClientId)) + { + return NULL; + } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } + res = pybullet_internalSetVectord(textPositionObj, posXYZ); + if (!res) + { + PyErr_SetString(SpamError, "Error converting textPositionObj[3]"); + return NULL; + } - res = pybullet_internalSetVectord(textPositionObj,posXYZ); - if (!res) - { - PyErr_SetString(SpamError, "Error converting textPositionObj[3]"); - return NULL; - } + if (textColorRGBObj) + { + res = pybullet_internalSetVectord(textColorRGBObj, colorRGB); + if (!res) + { + PyErr_SetString(SpamError, "Error converting textColorRGBObj[3]"); + return NULL; + } + } - if (textColorRGBObj) - { - res = pybullet_internalSetVectord(textColorRGBObj,colorRGB); - if (!res) - { - PyErr_SetString(SpamError, "Error converting textColorRGBObj[3]"); - return NULL; - } - } + commandHandle = b3InitUserDebugDrawAddText3D(sm, text, posXYZ, colorRGB, textSize, lifeTime); - - commandHandle = b3InitUserDebugDrawAddText3D(sm,text,posXYZ,colorRGB,textSize,lifeTime); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) + { + int debugItemUniqueId = b3GetDebugItemUniqueId(statusHandle); + PyObject* item = PyInt_FromLong(debugItemUniqueId); + return item; + } - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) - { - int debugItemUniqueId = b3GetDebugItemUniqueId(statusHandle); - PyObject* item = PyInt_FromLong(debugItemUniqueId); - return item; - } - - PyErr_SetString(SpamError, "Error in addUserDebugText."); - return NULL; + PyErr_SetString(SpamError, "Error in addUserDebugText."); + return NULL; } - -static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObject* keywds) { - - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - int res = 0; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int res = 0; - - double fromXYZ[3]; - double toXYZ[3]; - double colorRGB[3]={1,1,1}; + double fromXYZ[3]; + double toXYZ[3]; + double colorRGB[3] = {1, 1, 1}; - PyObject* lineFromObj=0; - PyObject* lineToObj=0; - PyObject* lineColorRGBObj=0; - double lineWidth = 1.f; - double lifeTime = 0.f; - int physicsClientId = 0; - b3PhysicsClientHandle sm=0; - static char *kwlist[] = { "lineFromXYZ", "lineToXYZ", "lineColorRGB", "lineWidth", "lifeTime","physicsClientId", NULL }; + PyObject* lineFromObj = 0; + PyObject* lineToObj = 0; + PyObject* lineColorRGBObj = 0; + double lineWidth = 1.f; + double lifeTime = 0.f; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"lineFromXYZ", "lineToXYZ", "lineColorRGB", "lineWidth", "lifeTime", "physicsClientId", NULL}; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|Oddi", kwlist, &lineFromObj, &lineToObj, &lineColorRGBObj,&lineWidth, &lifeTime,&physicsClientId)) - { - return NULL; - } + if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|Oddi", kwlist, &lineFromObj, &lineToObj, &lineColorRGBObj, &lineWidth, &lifeTime, &physicsClientId)) + { + return NULL; + } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - res = pybullet_internalSetVectord(lineFromObj,fromXYZ); - if (!res) - { - PyErr_SetString(SpamError, "Error converting lineFrom[3]"); - return NULL; - } + res = pybullet_internalSetVectord(lineFromObj, fromXYZ); + if (!res) + { + PyErr_SetString(SpamError, "Error converting lineFrom[3]"); + return NULL; + } - res = pybullet_internalSetVectord(lineToObj,toXYZ); - if (!res) - { - PyErr_SetString(SpamError, "Error converting lineTo[3]"); - return NULL; - } - if (lineColorRGBObj) - { - res = pybullet_internalSetVectord(lineColorRGBObj,colorRGB); - } - - commandHandle = b3InitUserDebugDrawAddLine3D(sm,fromXYZ,toXYZ,colorRGB,lineWidth,lifeTime); + res = pybullet_internalSetVectord(lineToObj, toXYZ); + if (!res) + { + PyErr_SetString(SpamError, "Error converting lineTo[3]"); + return NULL; + } + if (lineColorRGBObj) + { + res = pybullet_internalSetVectord(lineColorRGBObj, colorRGB); + } - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) - { - int debugItemUniqueId = b3GetDebugItemUniqueId(statusHandle); - PyObject* item = PyInt_FromLong(debugItemUniqueId); - return item; - } + commandHandle = b3InitUserDebugDrawAddLine3D(sm, fromXYZ, toXYZ, colorRGB, lineWidth, lifeTime); - PyErr_SetString(SpamError, "Error in addUserDebugLine."); - return NULL; + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) + { + int debugItemUniqueId = b3GetDebugItemUniqueId(statusHandle); + PyObject* item = PyInt_FromLong(debugItemUniqueId); + return item; + } + + PyErr_SetString(SpamError, "Error in addUserDebugLine."); + return NULL; } - - - -static PyObject* pybullet_removeUserDebugItem(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_removeUserDebugItem(PyObject* self, PyObject* args, PyObject* keywds) { - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - int itemUniqueId; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int itemUniqueId; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "itemUniqueId", "physicsClientId", NULL }; + static char* kwlist[] = {"itemUniqueId", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&itemUniqueId, &physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &itemUniqueId, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - commandHandle = b3InitUserDebugDrawRemove(sm,itemUniqueId); + commandHandle = b3InitUserDebugDrawRemove(sm, itemUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); @@ -2585,38 +2609,36 @@ static PyObject* pybullet_removeUserDebugItem(PyObject* self, PyObject* args, Py return Py_None; } -static PyObject* pybullet_removeAllUserDebugItems(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_removeAllUserDebugItems(PyObject* self, PyObject* args, PyObject* keywds) { - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist,&physicsClientId)) + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - commandHandle = b3InitUserDebugDrawRemoveAll(sm); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); - Py_INCREF(Py_None); return Py_None; } -static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyObject* keywds) { b3SharedMemoryStatusHandle statusHandle; int statusType; @@ -2625,17 +2647,17 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb int loggingType = -1; char* fileName = 0; PyObject* objectUniqueIdsObj = 0; - int maxLogDof=-1; + int maxLogDof = -1; - static char *kwlist[] = { "loggingType", "fileName", "objectUniqueIds", "maxLogDof", "physicsClientId", NULL }; + static char* kwlist[] = {"loggingType", "fileName", "objectUniqueIds", "maxLogDof", "physicsClientId", NULL}; int physicsClientId = 0; - + if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|Oii", kwlist, - &loggingType, &fileName, &objectUniqueIdsObj,&maxLogDof, &physicsClientId)) + &loggingType, &fileName, &objectUniqueIdsObj, &maxLogDof, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; @@ -2643,8 +2665,8 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb { b3SharedMemoryCommandHandle commandHandle; commandHandle = b3StateLoggingCommandInit(sm); - - b3StateLoggingStart(commandHandle,loggingType,fileName); + + b3StateLoggingStart(commandHandle, loggingType, fileName); if (objectUniqueIdsObj) { @@ -2653,23 +2675,23 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb { int len = PySequence_Size(objectUniqueIdsObj); int i; - for ( i=0;i0) + if (maxLogDof > 0) { b3StateLoggingSetMaxLogDof(commandHandle, maxLogDof); } - + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); - if (statusType==CMD_STATE_LOGGING_START_COMPLETED) + if (statusType == CMD_STATE_LOGGING_START_COMPLETED) { int loggingUniqueId = b3GetStatusLoggingUniqueId(statusHandle); PyObject* loggingUidObj = PyInt_FromLong(loggingUniqueId); @@ -2681,140 +2703,139 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb return Py_None; } -static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObject* keywds) { b3SharedMemoryStatusHandle statusHandle; int statusType; - int loggingId=-1; + int loggingId = -1; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "loggingId", "physicsClientId", NULL }; - int physicsClientId = 0; - + static char* kwlist[] = {"loggingId", "physicsClientId", NULL}; + int physicsClientId = 0; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, - &loggingId,&physicsClientId)) + &loggingId, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - if (loggingId>=0) + if (loggingId >= 0) { b3SharedMemoryCommandHandle commandHandle; commandHandle = b3StateLoggingCommandInit(sm); b3StateLoggingStop(commandHandle, loggingId); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); - } Py_INCREF(Py_None); return Py_None; } -static PyObject* pybullet_setTimeOut(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_setTimeOut(PyObject* self, PyObject* args, PyObject* keywds) { - static char *kwlist[] = { "timeOutInSeconds", "physicsClientId", NULL }; + static char* kwlist[] = {"timeOutInSeconds", "physicsClientId", NULL}; double timeOutInSeconds = -1; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; if (!PyArg_ParseTupleAndKeywords(args, keywds, "d|i", kwlist, - &timeOutInSeconds, &physicsClientId)) + &timeOutInSeconds, &physicsClientId)) return NULL; - if (timeOutInSeconds>=0) + if (timeOutInSeconds >= 0) { sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - b3SetTimeOut(sm,timeOutInSeconds); + b3SetTimeOut(sm, timeOutInSeconds); } Py_INCREF(Py_None); return Py_None; } -static PyObject* pybullet_rayTest(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_rayTest(PyObject* self, PyObject* args, PyObject* keywds) { b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; int statusType; - PyObject* rayFromObj=0; - PyObject* rayToObj=0; + PyObject* rayFromObj = 0; + PyObject* rayToObj = 0; double from[3]; double to[3]; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "rayFromPosition", "rayToPosition", "physicsClientId", NULL }; - int physicsClientId = 0; - + static char* kwlist[] = {"rayFromPosition", "rayToPosition", "physicsClientId", NULL}; + int physicsClientId = 0; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|i", kwlist, - &rayFromObj, &rayToObj,&physicsClientId)) + &rayFromObj, &rayToObj, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - pybullet_internalSetVectord(rayFromObj,from); - pybullet_internalSetVectord(rayToObj,to); + pybullet_internalSetVectord(rayFromObj, from); + pybullet_internalSetVectord(rayToObj, to); - commandHandle = b3CreateRaycastCommandInit(sm, from[0],from[1],from[2], - to[0],to[1],to[2]); + commandHandle = b3CreateRaycastCommandInit(sm, from[0], from[1], from[2], + to[0], to[1], to[2]); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); - if (statusType==CMD_REQUEST_RAY_CAST_INTERSECTIONS_COMPLETED) + if (statusType == CMD_REQUEST_RAY_CAST_INTERSECTIONS_COMPLETED) { struct b3RaycastInformation raycastInfo; PyObject* rayHitsObj = 0; int i; b3GetRaycastInformation(sm, &raycastInfo); - + rayHitsObj = PyTuple_New(raycastInfo.m_numRayHits); - for (i=0;i=-1) + if (trackObjectUid >= -1) { - b3SetVRCameraTrackingObject(commandHandle,trackObjectUid); + b3SetVRCameraTrackingObject(commandHandle, trackObjectUid); } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); @@ -2902,10 +2922,9 @@ static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObj Py_INCREF(Py_None); return Py_None; - } -static PyObject* pybullet_getKeyboardEvents(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_getKeyboardEvents(PyObject* self, PyObject* args, PyObject* keywds) { b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; @@ -2914,16 +2933,16 @@ static PyObject* pybullet_getKeyboardEvents(PyObject* self, PyObject* args, PyOb b3PhysicsClientHandle sm = 0; struct b3KeyboardEventsData keyboardEventsData; PyObject* keyEventsObj = 0; - int i=0; + int i = 0; - static char *kwlist[] = { "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist,&physicsClientId)) + static char* kwlist[] = {"physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) { return NULL; } - + sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; @@ -2931,166 +2950,161 @@ static PyObject* pybullet_getKeyboardEvents(PyObject* self, PyObject* args, PyOb commandHandle = b3RequestKeyboardEventsCommandInit(sm); b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - b3GetKeyboardEventsData(sm,&keyboardEventsData); + b3GetKeyboardEventsData(sm, &keyboardEventsData); keyEventsObj = PyDict_New(); - - for (i=0;i=0) && (cameraYaw>=0) && (cameraPitch>=0)) + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"cameraDistance", "cameraYaw", "cameraPitch", "cameraTargetPosition", "physicsClientId", NULL}; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "fffO|i", kwlist, + &cameraDistance, &cameraYaw, &cameraPitch, &cameraTargetPosObj, &physicsClientId)) + return NULL; + + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(sm); + if ((cameraDistance >= 0) && (cameraYaw >= 0) && (cameraPitch >= 0)) { float cameraTargetPosition[3]; - if (pybullet_internalSetVector(cameraTargetPosObj,cameraTargetPosition)) + if (pybullet_internalSetVector(cameraTargetPosObj, cameraTargetPosition)) { - b3ConfigureOpenGLVisualizerSetViewMatrix(commandHandle,cameraDistance,cameraPitch, cameraYaw, cameraTargetPosition); + b3ConfigureOpenGLVisualizerSetViewMatrix(commandHandle, cameraDistance, cameraPitch, cameraYaw, cameraTargetPosition); } } - b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - } - Py_INCREF(Py_None); - return Py_None; + b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + } + Py_INCREF(Py_None); + return Py_None; } -static PyObject* pybullet_setDebugObjectColor(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_setDebugObjectColor(PyObject* self, PyObject* args, PyObject* keywds) { PyObject* objectColorRGBObj = 0; double objectColorRGB[3]; @@ -3098,15 +3112,15 @@ static PyObject* pybullet_setDebugObjectColor(PyObject* self, PyObject* args, Py int objectUniqueId = -1; int linkIndex = -2; int physicsClientId = 0; - b3PhysicsClientHandle sm=0; - static char *kwlist[] = { "objectUniqueId", "linkIndex","objectDebugColorRGB", "physicsClientId", NULL }; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"objectUniqueId", "linkIndex", "objectDebugColorRGB", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|Oi", kwlist, - &objectUniqueId, &linkIndex, &objectColorRGBObj,&physicsClientId)) + &objectUniqueId, &linkIndex, &objectColorRGBObj, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; @@ -3130,9 +3144,8 @@ static PyObject* pybullet_setDebugObjectColor(PyObject* self, PyObject* args, Py Py_INCREF(Py_None); return Py_None; } - -static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyObject* keywds) +static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyObject* keywds) { int objectUniqueId = -1; b3SharedMemoryCommandHandle commandHandle; @@ -3143,22 +3156,19 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO PyObject* pyResultList = 0; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "objectUniqueId", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&objectUniqueId,&physicsClientId)) + static char* kwlist[] = {"objectUniqueId", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &objectUniqueId, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - { - - commandHandle = b3InitRequestVisualShapeInformation(sm, objectUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); @@ -3172,10 +3182,10 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO PyObject* item; item = PyInt_FromLong(visualShapeInfo.m_visualShapeData[i].m_objectUniqueId); PyTuple_SetItem(visualShapeObList, 0, item); - + item = PyInt_FromLong(visualShapeInfo.m_visualShapeData[i].m_linkIndex); PyTuple_SetItem(visualShapeObList, 1, item); - + item = PyInt_FromLong(visualShapeInfo.m_visualShapeData[i].m_visualGeometryType); PyTuple_SetItem(visualShapeObList, 2, item); @@ -3189,7 +3199,7 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO PyTuple_SetItem(vec, 2, item); PyTuple_SetItem(visualShapeObList, 3, vec); } - + item = PyString_FromString(visualShapeInfo.m_visualShapeData[i].m_meshAssetFileName); PyTuple_SetItem(visualShapeObList, 4, item); @@ -3217,19 +3227,18 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO PyTuple_SetItem(visualShapeObList, 6, vec); } - { - PyObject* rgba = PyTuple_New(4); - item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[0]); - PyTuple_SetItem(rgba, 0, item); - item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[1]); - PyTuple_SetItem(rgba, 1, item); - item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[2]); - PyTuple_SetItem(rgba, 2, item); - item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[3]); - PyTuple_SetItem(rgba, 3, item); - PyTuple_SetItem(visualShapeObList, 7, rgba); - } - + { + PyObject* rgba = PyTuple_New(4); + item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[0]); + PyTuple_SetItem(rgba, 0, item); + item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[1]); + PyTuple_SetItem(rgba, 1, item); + item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[2]); + PyTuple_SetItem(rgba, 2, item); + item = PyFloat_FromDouble(visualShapeInfo.m_visualShapeData[i].m_rgbaColor[3]); + PyTuple_SetItem(rgba, 3, item); + PyTuple_SetItem(visualShapeObList, 7, rgba); + } PyTuple_SetItem(pyResultList, i, visualShapeObList); } @@ -3246,94 +3255,89 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO return Py_None; } -static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args,PyObject* keywds) +static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args, PyObject* keywds) { - - int objectUniqueId = -1; - int jointIndex = -1; - int shapeIndex = -1; - int textureUniqueId = -1; - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - int physicsClientId = 0; + int objectUniqueId = -1; + int jointIndex = -1; + int shapeIndex = -1; + int textureUniqueId = -1; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "objectUniqueId", "jointIndex", "shapeIndex", "textureUniqueId", "physicsClientId", NULL }; + static char* kwlist[] = {"objectUniqueId", "jointIndex", "shapeIndex", "textureUniqueId", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiii|i", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - - commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex, textureUniqueId); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_VISUAL_SHAPE_UPDATE_COMPLETED) - { - } - else - { - PyErr_SetString(SpamError, "Error resetting visual shape info"); - return NULL; - } - } - - Py_INCREF(Py_None); - return Py_None; + { + commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex, textureUniqueId); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_VISUAL_SHAPE_UPDATE_COMPLETED) + { + } + else + { + PyErr_SetString(SpamError, "Error resetting visual shape info"); + return NULL; + } + } + + Py_INCREF(Py_None); + return Py_None; } static PyObject* pybullet_loadTexture(PyObject* self, PyObject* args, PyObject* keywds) { - const char* filename = 0; - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - + const char* filename = 0; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "textureFilename", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist,&filename, &physicsClientId)) + static char* kwlist[] = {"textureFilename", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &filename, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - { - - commandHandle = b3InitLoadTexture(sm, filename); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_LOAD_TEXTURE_COMPLETED) - { - } - else - { - PyErr_SetString(SpamError, "Error loading texture"); - return NULL; - } - } - - Py_INCREF(Py_None); - return Py_None; + + { + commandHandle = b3InitLoadTexture(sm, filename); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_LOAD_TEXTURE_COMPLETED) + { + } + else + { + PyErr_SetString(SpamError, "Error loading texture"); + return NULL; + } + } + + Py_INCREF(Py_None); + return Py_None; } - -static PyObject* MyConvertContactPoint( struct b3ContactInformation* contactPointPtr) +static PyObject* MyConvertContactPoint(struct b3ContactInformation* contactPointPtr) { - /* + /* 0 int m_contactFlags; 1 int m_bodyUniqueIdA; 2 int m_bodyUniqueIdB; @@ -3353,88 +3357,87 @@ static PyObject* MyConvertContactPoint( struct b3ContactInformation* contactPoin int i; PyObject* pyResultList = PyTuple_New(contactPointPtr->m_numContactPoints); - for (i = 0; i < contactPointPtr->m_numContactPoints; i++) { - PyObject* contactObList = PyTuple_New(10); // see above 10 fields - PyObject* item; - item = - PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_contactFlags); - PyTuple_SetItem(contactObList, 0, item); - item = PyInt_FromLong( - contactPointPtr->m_contactPointData[i].m_bodyUniqueIdA); - PyTuple_SetItem(contactObList, 1, item); - item = PyInt_FromLong( - contactPointPtr->m_contactPointData[i].m_bodyUniqueIdB); - PyTuple_SetItem(contactObList, 2, item); - item = - PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_linkIndexA); - PyTuple_SetItem(contactObList, 3, item); - item = - PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_linkIndexB); - PyTuple_SetItem(contactObList, 4, item); + for (i = 0; i < contactPointPtr->m_numContactPoints; i++) + { + PyObject* contactObList = PyTuple_New(10); // see above 10 fields + PyObject* item; + item = + PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_contactFlags); + PyTuple_SetItem(contactObList, 0, item); + item = PyInt_FromLong( + contactPointPtr->m_contactPointData[i].m_bodyUniqueIdA); + PyTuple_SetItem(contactObList, 1, item); + item = PyInt_FromLong( + contactPointPtr->m_contactPointData[i].m_bodyUniqueIdB); + PyTuple_SetItem(contactObList, 2, item); + item = + PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_linkIndexA); + PyTuple_SetItem(contactObList, 3, item); + item = + PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_linkIndexB); + PyTuple_SetItem(contactObList, 4, item); - { - PyObject* posAObj = PyTuple_New(3); + { + PyObject* posAObj = PyTuple_New(3); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnAInWS[0]); - PyTuple_SetItem(posAObj, 0, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnAInWS[1]); - PyTuple_SetItem(posAObj, 1, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnAInWS[2]); - PyTuple_SetItem(posAObj, 2, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnAInWS[0]); + PyTuple_SetItem(posAObj, 0, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnAInWS[1]); + PyTuple_SetItem(posAObj, 1, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnAInWS[2]); + PyTuple_SetItem(posAObj, 2, item); - PyTuple_SetItem(contactObList, 5, posAObj); - } + PyTuple_SetItem(contactObList, 5, posAObj); + } - { - PyObject* posBObj = PyTuple_New(3); + { + PyObject* posBObj = PyTuple_New(3); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnBInWS[0]); + PyTuple_SetItem(posBObj, 0, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnBInWS[1]); + PyTuple_SetItem(posBObj, 1, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnBInWS[2]); + PyTuple_SetItem(posBObj, 2, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnBInWS[0]); - PyTuple_SetItem(posBObj, 0, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnBInWS[1]); - PyTuple_SetItem(posBObj, 1, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnBInWS[2]); - PyTuple_SetItem(posBObj, 2, item); + PyTuple_SetItem(contactObList, 6, posBObj); + } - PyTuple_SetItem(contactObList, 6, posBObj); + { + PyObject* normalOnB = PyTuple_New(3); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[0]); + PyTuple_SetItem(normalOnB, 0, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[1]); + PyTuple_SetItem(normalOnB, 1, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[2]); + PyTuple_SetItem(normalOnB, 2, item); + PyTuple_SetItem(contactObList, 7, normalOnB); + } - } + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_contactDistance); + PyTuple_SetItem(contactObList, 8, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_normalForce); + PyTuple_SetItem(contactObList, 9, item); - { - PyObject* normalOnB = PyTuple_New(3); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[0]); - PyTuple_SetItem(normalOnB, 0, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[1]); - PyTuple_SetItem(normalOnB, 1, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[2]); - PyTuple_SetItem(normalOnB, 2, item); - PyTuple_SetItem(contactObList, 7, normalOnB); - } - - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_contactDistance); - PyTuple_SetItem(contactObList, 8, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_normalForce); - PyTuple_SetItem(contactObList, 9, item); - - PyTuple_SetItem(pyResultList, i, contactObList); - } - return pyResultList; + PyTuple_SetItem(pyResultList, i, contactObList); + } + return pyResultList; } -static PyObject* pybullet_getOverlappingObjects(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_getOverlappingObjects(PyObject* self, PyObject* args, PyObject* keywds) { - PyObject* aabbMinOb=0, *aabbMaxOb=0; + PyObject *aabbMinOb = 0, *aabbMaxOb = 0; double aabbMin[3]; double aabbMax[3]; b3SharedMemoryCommandHandle commandHandle; @@ -3443,21 +3446,19 @@ static PyObject* pybullet_getOverlappingObjects(PyObject* self, PyObject* args, int i; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "aabbMin", "aabbMax", "physicsClientId",NULL }; - + static char* kwlist[] = {"aabbMin", "aabbMax", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|i", kwlist, - &aabbMinOb, &aabbMaxOb,&physicsClientId)) + &aabbMinOb, &aabbMaxOb, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - pybullet_internalSetVectord(aabbMinOb, aabbMin); pybullet_internalSetVectord(aabbMaxOb, aabbMax); @@ -3471,8 +3472,9 @@ static PyObject* pybullet_getOverlappingObjects(PyObject* self, PyObject* args, //For huge amount of overlap, we could use numpy instead (see camera pixel data) //What would Python do with huge amount of data? Pass it onto TensorFlow! - for (i = 0; i < overlapData.m_numOverlappingObjects; i++) { - PyObject* overlap = PyTuple_New(2);//body unique id and link index + for (i = 0; i < overlapData.m_numOverlappingObjects; i++) + { + PyObject* overlap = PyTuple_New(2); //body unique id and link index PyObject* item; item = @@ -3491,163 +3493,155 @@ static PyObject* pybullet_getOverlappingObjects(PyObject* self, PyObject* args, return Py_None; } - -static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, PyObject* keywds) { - int bodyUniqueIdA = -1; - int bodyUniqueIdB = -1; - int linkIndexA = -2; - int linkIndexB = -2; + int bodyUniqueIdA = -1; + int bodyUniqueIdB = -1; + int linkIndexA = -2; + int linkIndexB = -2; - double distanceThreshold = 0.f; + double distanceThreshold = 0.f; - b3SharedMemoryCommandHandle commandHandle; - struct b3ContactInformation contactPointData; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "bodyA", "bodyB", "distance", "linkIndexA","linkIndexB","physicsClientId", NULL }; + b3SharedMemoryCommandHandle commandHandle; + struct b3ContactInformation contactPointData; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"bodyA", "bodyB", "distance", "linkIndexA", "linkIndexB", "physicsClientId", NULL}; - - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|iii", kwlist, - &bodyUniqueIdA, &bodyUniqueIdB, &distanceThreshold, &linkIndexA, &linkIndexB,&physicsClientId)) - return NULL; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|iii", kwlist, + &bodyUniqueIdA, &bodyUniqueIdB, &distanceThreshold, &linkIndexA, &linkIndexB, &physicsClientId)) + return NULL; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - commandHandle = b3InitClosestDistanceQuery(sm); - b3SetClosestDistanceFilterBodyA(commandHandle, bodyUniqueIdA); - b3SetClosestDistanceFilterBodyB(commandHandle, bodyUniqueIdB); - b3SetClosestDistanceThreshold(commandHandle, distanceThreshold); - if (linkIndexA >= -1) - { - b3SetClosestDistanceFilterLinkA(commandHandle, linkIndexA); - } - if (linkIndexB >= -1) - { - b3SetClosestDistanceFilterLinkB(commandHandle, linkIndexB); - } + commandHandle = b3InitClosestDistanceQuery(sm); + b3SetClosestDistanceFilterBodyA(commandHandle, bodyUniqueIdA); + b3SetClosestDistanceFilterBodyB(commandHandle, bodyUniqueIdB); + b3SetClosestDistanceThreshold(commandHandle, distanceThreshold); + if (linkIndexA >= -1) + { + b3SetClosestDistanceFilterLinkA(commandHandle, linkIndexA); + } + if (linkIndexB >= -1) + { + b3SetClosestDistanceFilterLinkB(commandHandle, linkIndexB); + } - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) { - + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) + { + b3GetContactPointInformation(sm, &contactPointData); - b3GetContactPointInformation(sm, &contactPointData); + return MyConvertContactPoint(&contactPointData); + } - return MyConvertContactPoint(&contactPointData); - - } - - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } - -static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, PyObject* keywds) { - static char *kwlist[] = { "userConstraintUniqueId","jointChildPivot", "jointChildFrameOrientation","maxForce", "physicsClientId", NULL}; - int userConstraintUniqueId=-1; + static char* kwlist[] = {"userConstraintUniqueId", "jointChildPivot", "jointChildFrameOrientation", "maxForce", "physicsClientId", NULL}; + int userConstraintUniqueId = -1; b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; int statusType; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - PyObject* jointChildPivotObj=0; - PyObject* jointChildFrameOrnObj=0; + PyObject* jointChildPivotObj = 0; + PyObject* jointChildFrameOrnObj = 0; double jointChildPivot[3]; double jointChildFrameOrn[4]; double maxForce = -1; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOdi", kwlist,&userConstraintUniqueId,&jointChildPivotObj, &jointChildFrameOrnObj,&maxForce, &physicsClientId)) - { - return NULL; - } - - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - commandHandle = b3InitChangeUserConstraintCommand(sm,userConstraintUniqueId); - - if (pybullet_internalSetVectord(jointChildPivotObj,jointChildPivot)) - { - b3InitChangeUserConstraintSetPivotInB(commandHandle, jointChildPivot); - } - if (pybullet_internalSetVector4d(jointChildFrameOrnObj,jointChildFrameOrn)) - { - b3InitChangeUserConstraintSetFrameInB(commandHandle, jointChildFrameOrn); - } - if (maxForce>=0) - { - b3InitChangeUserConstraintSetMaxForce(commandHandle,maxForce); - } - - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - Py_INCREF(Py_None); - return Py_None; -}; - - -static PyObject* pybullet_removeUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) -{ - static char *kwlist[] = { "userConstraintUniqueId","physicsClientId", NULL}; - int userConstraintUniqueId=-1; - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int statusType; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,&userConstraintUniqueId,&physicsClientId)) - { - return NULL; - } - - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - commandHandle = b3InitRemoveUserConstraintCommand(sm,userConstraintUniqueId); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - Py_INCREF(Py_None); - return Py_None; -}; - - -/* -static PyObject* pybullet_updateUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) -{ - return NULL; -} -*/ - -static PyObject* pybullet_enableJointForceTorqueSensor(PyObject* self, PyObject* args, PyObject *keywds) -{ - int bodyUniqueId = -1; - int jointIndex = -1; - int enableSensor = 1; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - int numJoints = -1; - - static char *kwlist[] = {"bodyUniqueId", "jointIndex" ,"enableSensor", "physicsClientId" }; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ii", kwlist, &bodyUniqueId, &jointIndex, &enableSensor,&physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOdi", kwlist, &userConstraintUniqueId, &jointChildPivotObj, &jointChildFrameOrnObj, &maxForce, &physicsClientId)) + { + return NULL; + } + + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + commandHandle = b3InitChangeUserConstraintCommand(sm, userConstraintUniqueId); + + if (pybullet_internalSetVectord(jointChildPivotObj, jointChildPivot)) + { + b3InitChangeUserConstraintSetPivotInB(commandHandle, jointChildPivot); + } + if (pybullet_internalSetVector4d(jointChildFrameOrnObj, jointChildFrameOrn)) + { + b3InitChangeUserConstraintSetFrameInB(commandHandle, jointChildFrameOrn); + } + if (maxForce >= 0) + { + b3InitChangeUserConstraintSetMaxForce(commandHandle, maxForce); + } + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + Py_INCREF(Py_None); + return Py_None; +}; + +static PyObject* pybullet_removeUserConstraint(PyObject* self, PyObject* args, PyObject* keywds) +{ + static char* kwlist[] = {"userConstraintUniqueId", "physicsClientId", NULL}; + int userConstraintUniqueId = -1; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &userConstraintUniqueId, &physicsClientId)) + { + return NULL; + } + + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + commandHandle = b3InitRemoveUserConstraintCommand(sm, userConstraintUniqueId); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + Py_INCREF(Py_None); + return Py_None; +}; + +/* +static PyObject* pybullet_updateUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) +{ + return NULL; +} +*/ + +static PyObject* pybullet_enableJointForceTorqueSensor(PyObject* self, PyObject* args, PyObject* keywds) +{ + int bodyUniqueId = -1; + int jointIndex = -1; + int enableSensor = 1; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + int numJoints = -1; + + static char* kwlist[] = {"bodyUniqueId", "jointIndex", "enableSensor", "physicsClientId"}; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ii", kwlist, &bodyUniqueId, &jointIndex, &enableSensor, &physicsClientId)) { return NULL; } @@ -3659,7 +3653,6 @@ static PyObject* pybullet_enableJointForceTorqueSensor(PyObject* self, PyObject* return NULL; } - if (bodyUniqueId < 0) { PyErr_SetString(SpamError, "Error: invalid bodyUniqueId"); @@ -3692,71 +3685,66 @@ static PyObject* pybullet_enableJointForceTorqueSensor(PyObject* self, PyObject* return NULL; } - -static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, PyObject* keywds) { - b3SharedMemoryCommandHandle commandHandle; - int parentBodyUniqueId=-1; - int parentLinkIndex=-1; - int childBodyUniqueId=-1; - int childLinkIndex=-1; - int jointType=ePoint2PointType; - PyObject* jointAxisObj=0; - double jointAxis[3]={0,0,0}; + int parentBodyUniqueId = -1; + int parentLinkIndex = -1; + int childBodyUniqueId = -1; + int childLinkIndex = -1; + int jointType = ePoint2PointType; + PyObject* jointAxisObj = 0; + double jointAxis[3] = {0, 0, 0}; PyObject* parentFramePositionObj = 0; - double parentFramePosition[3]={0,0,0}; + double parentFramePosition[3] = {0, 0, 0}; PyObject* childFramePositionObj = 0; - double childFramePosition[3]={0,0,0}; + double childFramePosition[3] = {0, 0, 0}; PyObject* parentFrameOrientationObj = 0; - double parentFrameOrientation[4]={0,0,0,1}; + double parentFrameOrientation[4] = {0, 0, 0, 1}; PyObject* childFrameOrientationObj = 0; - double childFrameOrientation[4]={0,0,0,1}; + double childFrameOrientation[4] = {0, 0, 0, 1}; struct b3JointInfo jointInfo; b3SharedMemoryStatusHandle statusHandle; int statusType; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "parentBodyUniqueId", "parentLinkIndex", - "childBodyUniqueId", "childLinkIndex", - "jointType", - "jointAxis", - "parentFramePosition", - "childFramePosition", - "parentFrameOrientation", - "childFrameOrientation", - "physicsClientId", - NULL }; + static char* kwlist[] = {"parentBodyUniqueId", "parentLinkIndex", + "childBodyUniqueId", "childLinkIndex", + "jointType", + "jointAxis", + "parentFramePosition", + "childFramePosition", + "parentFrameOrientation", + "childFrameOrientation", + "physicsClientId", + NULL}; - - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiiiiOOO|OOi", kwlist,&parentBodyUniqueId,&parentLinkIndex, - &childBodyUniqueId,&childLinkIndex, - &jointType,&jointAxisObj, - &parentFramePositionObj, - &childFramePositionObj, - &parentFrameOrientationObj, - &childFrameOrientationObj, - &physicsClientId - )) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiiiiOOO|OOi", kwlist, &parentBodyUniqueId, &parentLinkIndex, + &childBodyUniqueId, &childLinkIndex, + &jointType, &jointAxisObj, + &parentFramePositionObj, + &childFramePositionObj, + &parentFrameOrientationObj, + &childFrameOrientationObj, + &physicsClientId)) { return NULL; } - + sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - pybullet_internalSetVectord(jointAxisObj,jointAxis); - pybullet_internalSetVectord(parentFramePositionObj,parentFramePosition); - pybullet_internalSetVectord(childFramePositionObj,childFramePosition); - pybullet_internalSetVector4d(parentFrameOrientationObj,parentFrameOrientation); - pybullet_internalSetVector4d(childFrameOrientationObj,childFrameOrientation); - + pybullet_internalSetVectord(jointAxisObj, jointAxis); + pybullet_internalSetVectord(parentFramePositionObj, parentFramePosition); + pybullet_internalSetVectord(childFramePositionObj, childFramePosition); + pybullet_internalSetVector4d(parentFrameOrientationObj, parentFrameOrientation); + pybullet_internalSetVector4d(childFrameOrientationObj, childFrameOrientation); + jointInfo.m_jointType = jointType; jointInfo.m_parentFrame[0] = parentFramePosition[0]; jointInfo.m_parentFrame[1] = parentFramePosition[1]; @@ -3773,103 +3761,99 @@ static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, P jointInfo.m_childFrame[4] = childFrameOrientation[1]; jointInfo.m_childFrame[5] = childFrameOrientation[2]; jointInfo.m_childFrame[6] = childFrameOrientation[3]; - + jointInfo.m_jointAxis[0] = jointAxis[0]; jointInfo.m_jointAxis[1] = jointAxis[1]; jointInfo.m_jointAxis[2] = jointAxis[2]; - commandHandle = b3InitCreateUserConstraintCommand(sm, parentBodyUniqueId, parentLinkIndex, childBodyUniqueId, childLinkIndex, &jointInfo); + commandHandle = b3InitCreateUserConstraintCommand(sm, parentBodyUniqueId, parentLinkIndex, childBodyUniqueId, childLinkIndex, &jointInfo); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); - if (statusType==CMD_USER_CONSTRAINT_COMPLETED) + if (statusType == CMD_USER_CONSTRAINT_COMPLETED) { int userConstraintUid = b3GetStatusUserConstraintUniqueId(statusHandle); PyObject* ob = PyLong_FromLong(userConstraintUid); return ob; } - PyErr_SetString(SpamError, "createConstraint failed."); return NULL; } -static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, PyObject *keywds) { - int bodyUniqueIdA = -1; - int bodyUniqueIdB = -1; - - b3SharedMemoryCommandHandle commandHandle; - struct b3ContactInformation contactPointData; - b3SharedMemoryStatusHandle statusHandle; - int statusType; +static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, PyObject* keywds) +{ + int bodyUniqueIdA = -1; + int bodyUniqueIdB = -1; + b3SharedMemoryCommandHandle commandHandle; + struct b3ContactInformation contactPointData; + b3SharedMemoryStatusHandle statusHandle; + int statusType; - static char *kwlist[] = { "bodyA", "bodyB","physicsClientId", NULL }; + static char* kwlist[] = {"bodyA", "bodyB", "physicsClientId", NULL}; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iii", kwlist, - &bodyUniqueIdA, &bodyUniqueIdB,&physicsClientId)) - return NULL; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iii", kwlist, + &bodyUniqueIdA, &bodyUniqueIdB, &physicsClientId)) + return NULL; sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - commandHandle = b3InitRequestContactPointInformation(sm); - b3SetContactFilterBodyA(commandHandle, bodyUniqueIdA); - b3SetContactFilterBodyB(commandHandle, bodyUniqueIdB); - //b3SetContactQueryMode(commandHandle, mode); + commandHandle = b3InitRequestContactPointInformation(sm); + b3SetContactFilterBodyA(commandHandle, bodyUniqueIdA); + b3SetContactFilterBodyB(commandHandle, bodyUniqueIdB); + //b3SetContactQueryMode(commandHandle, mode); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) { - - b3GetContactPointInformation(sm, &contactPointData); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) + { + b3GetContactPointInformation(sm, &contactPointData); - return MyConvertContactPoint(&contactPointData); - - } + return MyConvertContactPoint(&contactPointData); + } - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } - - /// Render an image from the current timestep of the simulation, width, height are required, other args are optional // getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, renderer) -static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject* keywds) { /// request an image from a simulated camera, using software or hardware renderer. struct b3CameraImageData imageData; - PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0; + PyObject *objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0; int width, height; float viewMatrix[16]; float projectionMatrix[16]; float lightDir[3]; - float lightColor[3]; - float lightDist = 10.0; - int hasShadow = 0; - float lightAmbientCoeff = 0.6; - float lightDiffuseCoeff = 0.35; - float lightSpecularCoeff = 0.05; - int renderer = 0; + float lightColor[3]; + float lightDist = 10.0; + int hasShadow = 0; + float lightAmbientCoeff = 0.6; + float lightDiffuseCoeff = 0.35; + float lightSpecularCoeff = 0.05; + int renderer = 0; // inialize cmd b3SharedMemoryCommandHandle command; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; // set camera resolution, optionally view, projection matrix, light direction, light color, light distance, shadow - static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "renderer", "physicsClientId", NULL }; + static char* kwlist[] = {"width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "renderer", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffii", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff, &renderer, &physicsClientId)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; @@ -3888,21 +3872,21 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec { b3RequestCameraImageSetLightDirection(command, lightDir); } - //set light color only if function succeeds - if (pybullet_internalSetVector(lightColorObj, lightColor)) - { - b3RequestCameraImageSetLightColor(command, lightColor); - } + //set light color only if function succeeds + if (pybullet_internalSetVector(lightColorObj, lightColor)) + { + b3RequestCameraImageSetLightColor(command, lightColor); + } - b3RequestCameraImageSetLightDistance(command, lightDist); - - b3RequestCameraImageSetShadow(command, hasShadow); - - b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff); - b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff); - b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff); - - b3RequestCameraImageSelectRenderer(command, renderer); + b3RequestCameraImageSetLightDistance(command, lightDist); + + b3RequestCameraImageSetShadow(command, hasShadow); + + b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff); + b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff); + b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff); + + b3RequestCameraImageSelectRenderer(command, renderer); if (b3CanSubmitCommand(sm)) { @@ -3913,7 +3897,8 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_CAMERA_IMAGE_COMPLETED) { + if (statusType == CMD_CAMERA_IMAGE_COMPLETED) + { PyObject* item2; PyObject* pyResultList; // store 4 elements in this result: width, // height, rgbData, depth @@ -3933,26 +3918,26 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values - npy_intp rgb_dims[3] = { imageData.m_pixelHeight, imageData.m_pixelWidth, - bytesPerPixel }; - npy_intp dep_dims[2] = { imageData.m_pixelHeight, imageData.m_pixelWidth }; - npy_intp seg_dims[2] = { imageData.m_pixelHeight, imageData.m_pixelWidth }; + npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth, + bytesPerPixel}; + npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; + npy_intp seg_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8); pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32); pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32); memcpy(PyArray_DATA(pyRGB), imageData.m_rgbColorData, - imageData.m_pixelHeight * imageData.m_pixelWidth * bytesPerPixel); + imageData.m_pixelHeight * imageData.m_pixelWidth * bytesPerPixel); memcpy(PyArray_DATA(pyDep), imageData.m_depthValues, - imageData.m_pixelHeight * imageData.m_pixelWidth); + imageData.m_pixelHeight * imageData.m_pixelWidth); memcpy(PyArray_DATA(pySeg), imageData.m_segmentationMaskValues, - imageData.m_pixelHeight * imageData.m_pixelWidth); + imageData.m_pixelHeight * imageData.m_pixelWidth); PyTuple_SetItem(pyResultList, 2, pyRGB); PyTuple_SetItem(pyResultList, 3, pyDep); PyTuple_SetItem(pyResultList, 4, pySeg); -#else//PYBULLET_USE_NUMPY +#else //PYBULLET_USE_NUMPY PyObject* pylistRGB; PyObject* pylistDep; PyObject* pylistSeg; @@ -3975,8 +3960,10 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); pylistSeg = PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); - for (i = 0; i < imageData.m_pixelWidth; i++) { - for (j = 0; j < imageData.m_pixelHeight; j++) { + for (i = 0; i < imageData.m_pixelWidth; i++) + { + for (j = 0; j < imageData.m_pixelHeight; j++) + { // TODO(hellojas): validate depth values make sense int depIndex = i + j * imageData.m_pixelWidth; { @@ -3989,7 +3976,8 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec PyTuple_SetItem(pylistSeg, depIndex, item2); } - for (p = 0; p < bytesPerPixel; p++) { + for (p = 0; p < bytesPerPixel; p++) + { int pixelIndex = bytesPerPixel * (i + j * imageData.m_pixelWidth) + p; item = PyInt_FromLong(imageData.m_rgbColorData[pixelIndex]); @@ -4003,7 +3991,7 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec PyTuple_SetItem(pyResultList, 3, pylistDep); PyTuple_SetItem(pyResultList, 4, pylistSeg); return pyResultList; -#endif//PYBULLET_USE_NUMPY +#endif //PYBULLET_USE_NUMPY return pyResultList; } @@ -4011,12 +3999,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec Py_INCREF(Py_None); return Py_None; - } - - -static PyObject* pybullet_computeViewMatrix(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_computeViewMatrix(PyObject* self, PyObject* args, PyObject* keywds) { PyObject* camEyeObj = 0; PyObject* camTargetPositionObj = 0; @@ -4026,7 +4011,7 @@ static PyObject* pybullet_computeViewMatrix(PyObject* self, PyObject* args, PyOb float camUpVector[3]; // set camera resolution, optionally view, projection matrix, light position - static char *kwlist[] = { "cameraEyePosition", "cameraTargetPosition", "cameraUpVector",NULL }; + static char* kwlist[] = {"cameraEyePosition", "cameraTargetPosition", "cameraUpVector", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "OOO", kwlist, &camEyeObj, &camTargetPositionObj, &camUpVectorObj)) { @@ -4038,7 +4023,7 @@ static PyObject* pybullet_computeViewMatrix(PyObject* self, PyObject* args, PyOb pybullet_internalSetVector(camUpVectorObj, camUpVector)) { float viewMatrix[16]; - PyObject* pyResultList=0; + PyObject* pyResultList = 0; int i; b3ComputeViewMatrixFromPositions(camEye, camTargetPosition, camUpVector, viewMatrix); @@ -4056,7 +4041,7 @@ static PyObject* pybullet_computeViewMatrix(PyObject* self, PyObject* args, PyOb } ///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices -static PyObject* pybullet_computeViewMatrixFromYawPitchRoll(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_computeViewMatrixFromYawPitchRoll(PyObject* self, PyObject* args, PyObject* keywds) { PyObject* cameraTargetPositionObj = 0; float cameraTargetPosition[3]; @@ -4067,9 +4052,9 @@ static PyObject* pybullet_computeViewMatrixFromYawPitchRoll(PyObject* self, PyOb int i; // set camera resolution, optionally view, projection matrix, light position - static char *kwlist[] = { "cameraTargetPosition", "distance", "yaw", "pitch", "roll", "upAxisIndex" ,NULL }; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "Offffi", kwlist, &cameraTargetPositionObj, &distance,&yaw,&pitch,&roll, &upAxisIndex)) + static char* kwlist[] = {"cameraTargetPosition", "distance", "yaw", "pitch", "roll", "upAxisIndex", NULL}; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "Offffi", kwlist, &cameraTargetPositionObj, &distance, &yaw, &pitch, &roll, &upAxisIndex)) { return NULL; } @@ -4089,12 +4074,10 @@ static PyObject* pybullet_computeViewMatrixFromYawPitchRoll(PyObject* self, PyOb PyTuple_SetItem(pyResultList, i, item); } return pyResultList; - - } ///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices -static PyObject* pybullet_computeProjectionMatrix(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_computeProjectionMatrix(PyObject* self, PyObject* args, PyObject* keywds) { PyObject* pyResultList = 0; float left; @@ -4107,14 +4090,13 @@ static PyObject* pybullet_computeProjectionMatrix(PyObject* self, PyObject* args int i; // set camera resolution, optionally view, projection matrix, light position - static char *kwlist[] = { "left", "right", "bottom", "top", "nearVal", "farVal" ,NULL }; + static char* kwlist[] = {"left", "right", "bottom", "top", "nearVal", "farVal", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "ffffff", kwlist, &left, &right, &bottom, &top, &nearVal, &farVal)) { return NULL; } - b3ComputeProjectionMatrix(left, right, bottom, top, nearVal, farVal, projectionMatrix); pyResultList = PyTuple_New(16); @@ -4124,23 +4106,22 @@ static PyObject* pybullet_computeProjectionMatrix(PyObject* self, PyObject* args PyTuple_SetItem(pyResultList, i, item); } return pyResultList; - } -static PyObject* pybullet_computeProjectionMatrixFOV(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_computeProjectionMatrixFOV(PyObject* self, PyObject* args, PyObject* keywds) { - float fov, aspect, nearVal, farVal; + float fov, aspect, nearVal, farVal; PyObject* pyResultList = 0; float projectionMatrix[16]; int i; - static char *kwlist[] = { "fov","aspect","nearVal","farVal",NULL }; + static char* kwlist[] = {"fov", "aspect", "nearVal", "farVal", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "ffff", kwlist, &fov, &aspect, &nearVal, &farVal)) { return NULL; } - + b3ComputeProjectionMatrixFOV(fov, aspect, nearVal, farVal, projectionMatrix); pyResultList = PyTuple_New(16); @@ -4150,10 +4131,8 @@ static PyObject* pybullet_computeProjectionMatrixFOV(PyObject* self, PyObject* a PyTuple_SetItem(pyResultList, i, item); } return pyResultList; - } - // Render an image from the current timestep of the simulation // // Examples: @@ -4177,561 +4156,620 @@ static PyObject* pybullet_computeProjectionMatrixFOV(PyObject* self, PyObject* a // TODO(hellojas): fix image is cut off at head // TODO(hellojas): should we add check to give minimum image resolution // to see object based on camera position? -static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) { - /// request an image from a simulated camera, using a software renderer. - struct b3CameraImageData imageData; - PyObject* objViewMat, *objProjMat; - PyObject* objCameraPos, *objTargetPos, *objCameraUp; +static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) +{ + /// request an image from a simulated camera, using a software renderer. + struct b3CameraImageData imageData; + PyObject *objViewMat, *objProjMat; + PyObject *objCameraPos, *objTargetPos, *objCameraUp; - int width, height; - int size = PySequence_Size(args); - float viewMatrix[16]; - float projectionMatrix[16]; + int width, height; + int size = PySequence_Size(args); + float viewMatrix[16]; + float projectionMatrix[16]; - float cameraPos[3]; - float targetPos[3]; - float cameraUp[3]; + float cameraPos[3]; + float targetPos[3]; + float cameraUp[3]; - float left, right, bottom, top, aspect; - float nearVal, farVal; - float fov; + float left, right, bottom, top, aspect; + float nearVal, farVal; + float fov; - // inialize cmd - b3SharedMemoryCommandHandle command; - b3PhysicsClientHandle sm; - int physicsClientId = 0; + // inialize cmd + b3SharedMemoryCommandHandle command; + b3PhysicsClientHandle sm; + int physicsClientId = 0; - sm = getPhysicsClient(physicsClientId); - if (sm == 0) + sm = getPhysicsClient(physicsClientId); + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - command = b3InitRequestCameraImage(sm); + command = b3InitRequestCameraImage(sm); - if (size == 2) // only set camera resolution - { - if (PyArg_ParseTuple(args, "ii", &width, &height)) { - b3RequestCameraImageSetPixelResolution(command, width, height); - } - } else if (size == 4) // set camera resolution and view and projection matrix - { - if (PyArg_ParseTuple(args, "iiOO", &width, &height, &objViewMat, - &objProjMat)) { - b3RequestCameraImageSetPixelResolution(command, width, height); + if (size == 2) // only set camera resolution + { + if (PyArg_ParseTuple(args, "ii", &width, &height)) + { + b3RequestCameraImageSetPixelResolution(command, width, height); + } + } + else if (size == 4) // set camera resolution and view and projection matrix + { + if (PyArg_ParseTuple(args, "iiOO", &width, &height, &objViewMat, + &objProjMat)) + { + b3RequestCameraImageSetPixelResolution(command, width, height); - // set camera matrices only if set matrix function succeeds - if (pybullet_internalSetMatrix(objViewMat, viewMatrix) && - (pybullet_internalSetMatrix(objProjMat, projectionMatrix))) { - b3RequestCameraImageSetCameraMatrices(command, viewMatrix, - projectionMatrix); - } else { - PyErr_SetString(SpamError, "Error parsing view or projection matrix."); - return NULL; - } - } - } else if (size == 7) // set camera resolution, camera positions and - // calculate projection using near/far values. - { - if (PyArg_ParseTuple(args, "iiOOOff", &width, &height, &objCameraPos, - &objTargetPos, &objCameraUp, &nearVal, &farVal)) { - b3RequestCameraImageSetPixelResolution(command, width, height); - if (pybullet_internalSetVector(objCameraPos, cameraPos) && - pybullet_internalSetVector(objTargetPos, targetPos) && - pybullet_internalSetVector(objCameraUp, cameraUp)) - { - b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos, - cameraUp); - } else { - PyErr_SetString(SpamError, - "Error parsing camera position, target or up."); - return NULL; - } + // set camera matrices only if set matrix function succeeds + if (pybullet_internalSetMatrix(objViewMat, viewMatrix) && + (pybullet_internalSetMatrix(objProjMat, projectionMatrix))) + { + b3RequestCameraImageSetCameraMatrices(command, viewMatrix, + projectionMatrix); + } + else + { + PyErr_SetString(SpamError, "Error parsing view or projection matrix."); + return NULL; + } + } + } + else if (size == 7) // set camera resolution, camera positions and + // calculate projection using near/far values. + { + if (PyArg_ParseTuple(args, "iiOOOff", &width, &height, &objCameraPos, + &objTargetPos, &objCameraUp, &nearVal, &farVal)) + { + b3RequestCameraImageSetPixelResolution(command, width, height); + if (pybullet_internalSetVector(objCameraPos, cameraPos) && + pybullet_internalSetVector(objTargetPos, targetPos) && + pybullet_internalSetVector(objCameraUp, cameraUp)) + { + b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos, + cameraUp); + } + else + { + PyErr_SetString(SpamError, + "Error parsing camera position, target or up."); + return NULL; + } - aspect = width / height; - left = -aspect * nearVal; - right = aspect * nearVal; - bottom = -nearVal; - top = nearVal; - b3RequestCameraImageSetProjectionMatrix(command, left, right, bottom, top, - nearVal, farVal); - } - } else if (size == 8) // set camera resolution, camera positions and - // calculate projection using near/far values & field - // of view - { - if (PyArg_ParseTuple(args, "iiOOOfff", &width, &height, &objCameraPos, - &objTargetPos, &objCameraUp, &nearVal, &farVal, - &fov)) { - b3RequestCameraImageSetPixelResolution(command, width, height); - if (pybullet_internalSetVector(objCameraPos, cameraPos) && - pybullet_internalSetVector(objTargetPos, targetPos) && - pybullet_internalSetVector(objCameraUp, cameraUp)) { - b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos, - cameraUp); - } else { - PyErr_SetString(SpamError, - "Error parsing camera position, target or up."); - return NULL; - } + aspect = width / height; + left = -aspect * nearVal; + right = aspect * nearVal; + bottom = -nearVal; + top = nearVal; + b3RequestCameraImageSetProjectionMatrix(command, left, right, bottom, top, + nearVal, farVal); + } + } + else if (size == 8) // set camera resolution, camera positions and + // calculate projection using near/far values & field + // of view + { + if (PyArg_ParseTuple(args, "iiOOOfff", &width, &height, &objCameraPos, + &objTargetPos, &objCameraUp, &nearVal, &farVal, + &fov)) + { + b3RequestCameraImageSetPixelResolution(command, width, height); + if (pybullet_internalSetVector(objCameraPos, cameraPos) && + pybullet_internalSetVector(objTargetPos, targetPos) && + pybullet_internalSetVector(objCameraUp, cameraUp)) + { + b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos, + cameraUp); + } + else + { + PyErr_SetString(SpamError, + "Error parsing camera position, target or up."); + return NULL; + } - aspect = width / height; - b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, - farVal); - } - } else if (size == 11) { - int upAxisIndex = 1; - float camDistance, yaw, pitch, roll; + aspect = width / height; + b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, + farVal); + } + } + else if (size == 11) + { + int upAxisIndex = 1; + float camDistance, yaw, pitch, roll; - // sometimes more arguments are better :-) - if (PyArg_ParseTuple(args, "iiOffffifff", &width, &height, &objTargetPos, - &camDistance, &yaw, &pitch, &roll, &upAxisIndex, - &nearVal, &farVal, &fov)) { - b3RequestCameraImageSetPixelResolution(command, width, height); - if (pybullet_internalSetVector(objTargetPos, targetPos)) { - // printf("width = %d, height = %d, targetPos = %f,%f,%f, distance = %f, - // yaw = %f, pitch = %f, upAxisIndex = %d, near=%f, far=%f, - // fov=%f\n",width,height,targetPos[0],targetPos[1],targetPos[2],camDistance,yaw,pitch,upAxisIndex,nearVal,farVal,fov); + // sometimes more arguments are better :-) + if (PyArg_ParseTuple(args, "iiOffffifff", &width, &height, &objTargetPos, + &camDistance, &yaw, &pitch, &roll, &upAxisIndex, + &nearVal, &farVal, &fov)) + { + b3RequestCameraImageSetPixelResolution(command, width, height); + if (pybullet_internalSetVector(objTargetPos, targetPos)) + { + // printf("width = %d, height = %d, targetPos = %f,%f,%f, distance = %f, + // yaw = %f, pitch = %f, upAxisIndex = %d, near=%f, far=%f, + // fov=%f\n",width,height,targetPos[0],targetPos[1],targetPos[2],camDistance,yaw,pitch,upAxisIndex,nearVal,farVal,fov); - b3RequestCameraImageSetViewMatrix2(command, targetPos, camDistance, yaw, - pitch, roll, upAxisIndex); - aspect = width / height; - b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, - nearVal, farVal); - } else { - PyErr_SetString(SpamError, "Error parsing camera target pos"); - } - } else { - PyErr_SetString(SpamError, "Error parsing arguments"); - } + b3RequestCameraImageSetViewMatrix2(command, targetPos, camDistance, yaw, + pitch, roll, upAxisIndex); + aspect = width / height; + b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, + nearVal, farVal); + } + else + { + PyErr_SetString(SpamError, "Error parsing camera target pos"); + } + } + else + { + PyErr_SetString(SpamError, "Error parsing arguments"); + } + } + else + { + PyErr_SetString(SpamError, "Invalid number of args passed to renderImage."); + return NULL; + } - } else { - PyErr_SetString(SpamError, "Invalid number of args passed to renderImage."); - return NULL; - } + if (b3CanSubmitCommand(sm)) + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; - if (b3CanSubmitCommand(sm)) { - b3SharedMemoryStatusHandle statusHandle; - int statusType; + // b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL); - // b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL); - - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_CAMERA_IMAGE_COMPLETED) { - PyObject* item2; - PyObject* pyResultList; // store 4 elements in this result: width, - // height, rgbData, depth + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_CAMERA_IMAGE_COMPLETED) + { + PyObject* item2; + PyObject* pyResultList; // store 4 elements in this result: width, + // height, rgbData, depth #ifdef PYBULLET_USE_NUMPY - PyObject* pyRGB; - PyObject* pyDep; - PyObject* pySeg; + PyObject* pyRGB; + PyObject* pyDep; + PyObject* pySeg; - int i, j, p; + int i, j, p; - b3GetCameraImageData(sm, &imageData); - // TODO(hellojas): error handling if image size is 0 - pyResultList = PyTuple_New(5); - PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); - PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + b3GetCameraImageData(sm, &imageData); + // TODO(hellojas): error handling if image size is 0 + pyResultList = PyTuple_New(5); + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); + PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); - int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values - npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth, - bytesPerPixel}; - npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; - npy_intp seg_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; + npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth, + bytesPerPixel}; + npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; + npy_intp seg_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; - pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8); - pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32); - pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32); + pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8); + pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32); + pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32); - memcpy(PyArray_DATA(pyRGB), imageData.m_rgbColorData, - imageData.m_pixelHeight * imageData.m_pixelWidth * bytesPerPixel); - memcpy(PyArray_DATA(pyDep), imageData.m_depthValues, - imageData.m_pixelHeight * imageData.m_pixelWidth); - memcpy(PyArray_DATA(pySeg), imageData.m_segmentationMaskValues, - imageData.m_pixelHeight * imageData.m_pixelWidth); - - PyTuple_SetItem(pyResultList, 2, pyRGB); - PyTuple_SetItem(pyResultList, 3, pyDep); - PyTuple_SetItem(pyResultList, 4, pySeg); -#else//PYBULLET_USE_NUMPY - PyObject* pylistRGB; - PyObject* pylistDep; - PyObject* pylistSeg; + memcpy(PyArray_DATA(pyRGB), imageData.m_rgbColorData, + imageData.m_pixelHeight * imageData.m_pixelWidth * bytesPerPixel); + memcpy(PyArray_DATA(pyDep), imageData.m_depthValues, + imageData.m_pixelHeight * imageData.m_pixelWidth); + memcpy(PyArray_DATA(pySeg), imageData.m_segmentationMaskValues, + imageData.m_pixelHeight * imageData.m_pixelWidth); - int i, j, p; + PyTuple_SetItem(pyResultList, 2, pyRGB); + PyTuple_SetItem(pyResultList, 3, pyDep); + PyTuple_SetItem(pyResultList, 4, pySeg); +#else //PYBULLET_USE_NUMPY + PyObject* pylistRGB; + PyObject* pylistDep; + PyObject* pylistSeg; - b3GetCameraImageData(sm, &imageData); - // TODO(hellojas): error handling if image size is 0 - pyResultList = PyTuple_New(5); - PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); - PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + int i, j, p; - { - PyObject* item; - int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values - int num = - bytesPerPixel * imageData.m_pixelWidth * imageData.m_pixelHeight; - pylistRGB = PyTuple_New(num); - pylistDep = - PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); - pylistSeg = - PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); - for (i = 0; i < imageData.m_pixelWidth; i++) { - for (j = 0; j < imageData.m_pixelHeight; j++) { - // TODO(hellojas): validate depth values make sense - int depIndex = i + j * imageData.m_pixelWidth; - { - item = PyFloat_FromDouble(imageData.m_depthValues[depIndex]); - PyTuple_SetItem(pylistDep, depIndex, item); - } - { - item2 = - PyLong_FromLong(imageData.m_segmentationMaskValues[depIndex]); - PyTuple_SetItem(pylistSeg, depIndex, item2); - } + b3GetCameraImageData(sm, &imageData); + // TODO(hellojas): error handling if image size is 0 + pyResultList = PyTuple_New(5); + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); + PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); - for (p = 0; p < bytesPerPixel; p++) { - int pixelIndex = - bytesPerPixel * (i + j * imageData.m_pixelWidth) + p; - item = PyInt_FromLong(imageData.m_rgbColorData[pixelIndex]); - PyTuple_SetItem(pylistRGB, pixelIndex, item); - } - } - } - } + { + PyObject* item; + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values + int num = + bytesPerPixel * imageData.m_pixelWidth * imageData.m_pixelHeight; + pylistRGB = PyTuple_New(num); + pylistDep = + PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); + pylistSeg = + PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); + for (i = 0; i < imageData.m_pixelWidth; i++) + { + for (j = 0; j < imageData.m_pixelHeight; j++) + { + // TODO(hellojas): validate depth values make sense + int depIndex = i + j * imageData.m_pixelWidth; + { + item = PyFloat_FromDouble(imageData.m_depthValues[depIndex]); + PyTuple_SetItem(pylistDep, depIndex, item); + } + { + item2 = + PyLong_FromLong(imageData.m_segmentationMaskValues[depIndex]); + PyTuple_SetItem(pylistSeg, depIndex, item2); + } - PyTuple_SetItem(pyResultList, 2, pylistRGB); - PyTuple_SetItem(pyResultList, 3, pylistDep); - PyTuple_SetItem(pyResultList, 4, pylistSeg); - return pyResultList; -#endif//PYBULLET_USE_NUMPY + for (p = 0; p < bytesPerPixel; p++) + { + int pixelIndex = + bytesPerPixel * (i + j * imageData.m_pixelWidth) + p; + item = PyInt_FromLong(imageData.m_rgbColorData[pixelIndex]); + PyTuple_SetItem(pylistRGB, pixelIndex, item); + } + } + } + } - return pyResultList; - } - } + PyTuple_SetItem(pyResultList, 2, pylistRGB); + PyTuple_SetItem(pyResultList, 3, pylistDep); + PyTuple_SetItem(pyResultList, 4, pylistSeg); + return pyResultList; +#endif //PYBULLET_USE_NUMPY - Py_INCREF(Py_None); - return Py_None; + return pyResultList; + } + } + + Py_INCREF(Py_None); + return Py_None; } -static PyObject* pybullet_applyExternalForce(PyObject* self, PyObject* args,PyObject* keywds) { - - { - int objectUniqueId=-1, linkIndex=-1, flags; - double force[3]; - double position[3] = {0.0, 0.0, 0.0}; - PyObject* forceObj=0, *posObj=0; - - b3SharedMemoryCommandHandle command; - b3SharedMemoryStatusHandle statusHandle; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "objectUniqueId", "linkIndex", - "forceObj", "posObj", "flags", "physicsClientId", NULL }; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiOOi|i", kwlist,&objectUniqueId, &linkIndex, - &forceObj, &posObj, &flags, &physicsClientId)) +static PyObject* pybullet_applyExternalForce(PyObject* self, PyObject* args, PyObject* keywds) +{ { - return NULL; + int objectUniqueId = -1, linkIndex = -1, flags; + double force[3]; + double position[3] = {0.0, 0.0, 0.0}; + PyObject *forceObj = 0, *posObj = 0; + + b3SharedMemoryCommandHandle command; + b3SharedMemoryStatusHandle statusHandle; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"objectUniqueId", "linkIndex", + "forceObj", "posObj", "flags", "physicsClientId", NULL}; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiOOi|i", kwlist, &objectUniqueId, &linkIndex, + &forceObj, &posObj, &flags, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + { + PyObject* seq; + int len, i; + seq = PySequence_Fast(forceObj, "expected a sequence"); + len = PySequence_Size(forceObj); + if (len == 3) + { + for (i = 0; i < 3; i++) + { + force[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + } + else + { + PyErr_SetString(SpamError, "force needs a 3 coordinates [x,y,z]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + } + { + PyObject* seq; + int len, i; + seq = PySequence_Fast(posObj, "expected a sequence"); + len = PySequence_Size(posObj); + if (len == 3) + { + for (i = 0; i < 3; i++) + { + position[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + } + else + { + PyErr_SetString(SpamError, "position needs a 3 coordinates [x,y,z]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + } + if ((flags != EF_WORLD_FRAME) && (flags != EF_LINK_FRAME)) + { + PyErr_SetString(SpamError, + "flag has to be either WORLD_FRAME or LINK_FRAME"); + return NULL; + } + command = b3ApplyExternalForceCommandInit(sm); + b3ApplyExternalForce(command, objectUniqueId, linkIndex, force, position, + flags); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - { - PyObject* seq; - int len, i; - seq = PySequence_Fast(forceObj, "expected a sequence"); - len = PySequence_Size(forceObj); - if (len == 3) { - for (i = 0; i < 3; i++) { - force[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - } else { - PyErr_SetString(SpamError, "force needs a 3 coordinates [x,y,z]."); - Py_DECREF(seq); - return NULL; - } - Py_DECREF(seq); - } - { - PyObject* seq; - int len, i; - seq = PySequence_Fast(posObj, "expected a sequence"); - len = PySequence_Size(posObj); - if (len == 3) { - for (i = 0; i < 3; i++) { - position[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - } else { - PyErr_SetString(SpamError, "position needs a 3 coordinates [x,y,z]."); - Py_DECREF(seq); - return NULL; - } - Py_DECREF(seq); - } - if ((flags != EF_WORLD_FRAME) && (flags != EF_LINK_FRAME)) { - PyErr_SetString(SpamError, - "flag has to be either WORLD_FRAME or LINK_FRAME"); - return NULL; - } - command = b3ApplyExternalForceCommandInit(sm); - b3ApplyExternalForce(command, objectUniqueId, linkIndex, force, position, - flags); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - } - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } -static PyObject* pybullet_applyExternalTorque(PyObject* self, PyObject* args,PyObject* keywds) { - - { - int objectUniqueId, linkIndex, flags; - double torque[3]; - PyObject* torqueObj; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "objectUniqueId", "linkIndex", "torqueObj", - "flags", "physicsClientId", NULL }; - - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiOi|i", kwlist,&objectUniqueId, &linkIndex, &torqueObj, - &flags, &physicsClientId)) +static PyObject* pybullet_applyExternalTorque(PyObject* self, PyObject* args, PyObject* keywds) +{ { - return NULL; - } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - { - PyObject* seq; - int len, i; - seq = PySequence_Fast(torqueObj, "expected a sequence"); - len = PySequence_Size(torqueObj); - if (len == 3) { - for (i = 0; i < 3; i++) { - torque[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - } else { - PyErr_SetString(SpamError, "torque needs a 3 coordinates [x,y,z]."); - Py_DECREF(seq); - return NULL; - } - Py_DECREF(seq); + int objectUniqueId, linkIndex, flags; + double torque[3]; + PyObject* torqueObj; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"objectUniqueId", "linkIndex", "torqueObj", + "flags", "physicsClientId", NULL}; - if (linkIndex < -1) { - PyErr_SetString(SpamError, - "Invalid link index, has to be -1 or larger"); - return NULL; - } - if ((flags != EF_WORLD_FRAME) && (flags != EF_LINK_FRAME)) { - PyErr_SetString(SpamError, - "flag has to be either WORLD_FRAME or LINK_FRAME"); - return NULL; - } - { - b3SharedMemoryStatusHandle statusHandle; - b3SharedMemoryCommandHandle command = - b3ApplyExternalForceCommandInit(sm); - b3ApplyExternalTorque(command, objectUniqueId, -1, torque, flags); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - } - } - } + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiOi|i", kwlist, &objectUniqueId, &linkIndex, &torqueObj, + &flags, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } - Py_INCREF(Py_None); - return Py_None; + { + PyObject* seq; + int len, i; + seq = PySequence_Fast(torqueObj, "expected a sequence"); + len = PySequence_Size(torqueObj); + if (len == 3) + { + for (i = 0; i < 3; i++) + { + torque[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + } + else + { + PyErr_SetString(SpamError, "torque needs a 3 coordinates [x,y,z]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + + if (linkIndex < -1) + { + PyErr_SetString(SpamError, + "Invalid link index, has to be -1 or larger"); + return NULL; + } + if ((flags != EF_WORLD_FRAME) && (flags != EF_LINK_FRAME)) + { + PyErr_SetString(SpamError, + "flag has to be either WORLD_FRAME or LINK_FRAME"); + return NULL; + } + { + b3SharedMemoryStatusHandle statusHandle; + b3SharedMemoryCommandHandle command = + b3ApplyExternalForceCommandInit(sm); + b3ApplyExternalTorque(command, objectUniqueId, -1, torque, flags); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + } + } + } + + Py_INCREF(Py_None); + return Py_None; } static PyObject* pybullet_getQuaternionFromEuler(PyObject* self, - PyObject* args) { - double rpy[3]; + PyObject* args) +{ + double rpy[3]; - PyObject* eulerObj; + PyObject* eulerObj; - if (PyArg_ParseTuple(args, "O", &eulerObj)) { - PyObject* seq; - int len, i; - seq = PySequence_Fast(eulerObj, "expected a sequence"); - len = PySequence_Size(eulerObj); - if (len == 3) { - for (i = 0; i < 3; i++) { - rpy[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - } else { - PyErr_SetString(SpamError, - "Euler angles need a 3 coordinates [roll, pitch, yaw]."); - Py_DECREF(seq); - return NULL; - } - Py_DECREF(seq); - } else { - PyErr_SetString(SpamError, - "Euler angles need a 3 coordinates [roll, pitch, yaw]."); - return NULL; - } + if (PyArg_ParseTuple(args, "O", &eulerObj)) + { + PyObject* seq; + int len, i; + seq = PySequence_Fast(eulerObj, "expected a sequence"); + len = PySequence_Size(eulerObj); + if (len == 3) + { + for (i = 0; i < 3; i++) + { + rpy[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + } + else + { + PyErr_SetString(SpamError, + "Euler angles need a 3 coordinates [roll, pitch, yaw]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + } + else + { + PyErr_SetString(SpamError, + "Euler angles need a 3 coordinates [roll, pitch, yaw]."); + return NULL; + } - { - double phi, the, psi; - double roll = rpy[0]; - double pitch = rpy[1]; - double yaw = rpy[2]; - phi = roll / 2.0; - the = pitch / 2.0; - psi = yaw / 2.0; - { - double quat[4] = { - sin(phi) * cos(the) * cos(psi) - cos(phi) * sin(the) * sin(psi), - cos(phi) * sin(the) * cos(psi) + sin(phi) * cos(the) * sin(psi), - cos(phi) * cos(the) * sin(psi) - sin(phi) * sin(the) * cos(psi), - cos(phi) * cos(the) * cos(psi) + sin(phi) * sin(the) * sin(psi)}; + { + double phi, the, psi; + double roll = rpy[0]; + double pitch = rpy[1]; + double yaw = rpy[2]; + phi = roll / 2.0; + the = pitch / 2.0; + psi = yaw / 2.0; + { + double quat[4] = { + sin(phi) * cos(the) * cos(psi) - cos(phi) * sin(the) * sin(psi), + cos(phi) * sin(the) * cos(psi) + sin(phi) * cos(the) * sin(psi), + cos(phi) * cos(the) * sin(psi) - sin(phi) * sin(the) * cos(psi), + cos(phi) * cos(the) * cos(psi) + sin(phi) * sin(the) * sin(psi)}; - // normalize the quaternion - double len = sqrt(quat[0] * quat[0] + quat[1] * quat[1] + - quat[2] * quat[2] + quat[3] * quat[3]); - quat[0] /= len; - quat[1] /= len; - quat[2] /= len; - quat[3] /= len; - { - PyObject* pylist; - int i; - pylist = PyTuple_New(4); - for (i = 0; i < 4; i++) - PyTuple_SetItem(pylist, i, PyFloat_FromDouble(quat[i])); - return pylist; - } - } - } - Py_INCREF(Py_None); - return Py_None; + // normalize the quaternion + double len = sqrt(quat[0] * quat[0] + quat[1] * quat[1] + + quat[2] * quat[2] + quat[3] * quat[3]); + quat[0] /= len; + quat[1] /= len; + quat[2] /= len; + quat[3] /= len; + { + PyObject* pylist; + int i; + pylist = PyTuple_New(4); + for (i = 0; i < 4; i++) + PyTuple_SetItem(pylist, i, PyFloat_FromDouble(quat[i])); + return pylist; + } + } + } + Py_INCREF(Py_None); + return Py_None; } /// quaternion <-> euler yaw/pitch/roll convention from URDF/SDF, see Gazebo /// https://github.com/arpg/Gazebo/blob/master/gazebo/math/Quaternion.cc static PyObject* pybullet_getEulerFromQuaternion(PyObject* self, - PyObject* args) { - double squ; - double sqx; - double sqy; - double sqz; + PyObject* args) +{ + double squ; + double sqx; + double sqy; + double sqz; - double quat[4]; + double quat[4]; - PyObject* quatObj; + PyObject* quatObj; - if (PyArg_ParseTuple(args, "O", &quatObj)) { - PyObject* seq; - int len, i; - seq = PySequence_Fast(quatObj, "expected a sequence"); - len = PySequence_Size(quatObj); - if (len == 4) { - for (i = 0; i < 4; i++) { - quat[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - } else { - PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w]."); - Py_DECREF(seq); - return NULL; - } - Py_DECREF(seq); - } else { - PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w]."); - return NULL; - } + if (PyArg_ParseTuple(args, "O", &quatObj)) + { + PyObject* seq; + int len, i; + seq = PySequence_Fast(quatObj, "expected a sequence"); + len = PySequence_Size(quatObj); + if (len == 4) + { + for (i = 0; i < 4; i++) + { + quat[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + } + else + { + PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + } + else + { + PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w]."); + return NULL; + } - { - double rpy[3]; - double sarg; - sqx = quat[0] * quat[0]; - sqy = quat[1] * quat[1]; - sqz = quat[2] * quat[2]; - squ = quat[3] * quat[3]; - rpy[0] = atan2(2 * (quat[1] * quat[2] + quat[3] * quat[0]), - squ - sqx - sqy + sqz); - sarg = -2 * (quat[0] * quat[2] - quat[3] * quat[1]); - rpy[1] = sarg <= -1.0 ? -0.5 * 3.141592538 - : (sarg >= 1.0 ? 0.5 * 3.141592538 : asin(sarg)); - rpy[2] = atan2(2 * (quat[0] * quat[1] + quat[3] * quat[2]), - squ + sqx - sqy - sqz); - { - PyObject* pylist; - int i; - pylist = PyTuple_New(3); - for (i = 0; i < 3; i++) - PyTuple_SetItem(pylist, i, PyFloat_FromDouble(rpy[i])); - return pylist; - } - } - Py_INCREF(Py_None); - return Py_None; + { + double rpy[3]; + double sarg; + sqx = quat[0] * quat[0]; + sqy = quat[1] * quat[1]; + sqz = quat[2] * quat[2]; + squ = quat[3] * quat[3]; + rpy[0] = atan2(2 * (quat[1] * quat[2] + quat[3] * quat[0]), + squ - sqx - sqy + sqz); + sarg = -2 * (quat[0] * quat[2] - quat[3] * quat[1]); + rpy[1] = sarg <= -1.0 ? -0.5 * 3.141592538 + : (sarg >= 1.0 ? 0.5 * 3.141592538 : asin(sarg)); + rpy[2] = atan2(2 * (quat[0] * quat[1] + quat[3] * quat[2]), + squ + sqx - sqy - sqz); + { + PyObject* pylist; + int i; + pylist = PyTuple_New(3); + for (i = 0; i < 3; i++) + PyTuple_SetItem(pylist, i, PyFloat_FromDouble(rpy[i])); + return pylist; + } + } + Py_INCREF(Py_None); + return Py_None; } - ///Inverse Kinematics binding static PyObject* pybullet_calculateInverseKinematics(PyObject* self, - PyObject* args, PyObject* keywds) + PyObject* args, PyObject* keywds) - { - int bodyIndex; - int endEffectorLinkIndex; - - PyObject* targetPosObj=0; - PyObject* targetOrnObj=0; +{ + int bodyIndex; + int endEffectorLinkIndex; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - PyObject* lowerLimitsObj = 0; - PyObject* upperLimitsObj = 0; - PyObject* jointRangesObj = 0; - PyObject* restPosesObj = 0; - PyObject* jointDampingObj = 0; + PyObject* targetPosObj = 0; + PyObject* targetOrnObj = 0; - static char *kwlist[] = { "bodyIndex", "endEffectorLinkIndex", "targetPosition", "targetOrientation","lowerLimits", "upperLimits", "jointRanges", "restPoses", "physicsClientId", "jointDamping", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiO|OOOOOiO", kwlist, &bodyIndex, &endEffectorLinkIndex, &targetPosObj,&targetOrnObj,&lowerLimitsObj, &upperLimitsObj, &jointRangesObj, &restPosesObj, &physicsClientId, & jointDampingObj)) + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + PyObject* lowerLimitsObj = 0; + PyObject* upperLimitsObj = 0; + PyObject* jointRangesObj = 0; + PyObject* restPosesObj = 0; + PyObject* jointDampingObj = 0; + + static char* kwlist[] = {"bodyIndex", "endEffectorLinkIndex", "targetPosition", "targetOrientation", "lowerLimits", "upperLimits", "jointRanges", "restPoses", "physicsClientId", "jointDamping", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiO|OOOOOiO", kwlist, &bodyIndex, &endEffectorLinkIndex, &targetPosObj, &targetOrnObj, &lowerLimitsObj, &upperLimitsObj, &jointRangesObj, &restPosesObj, &physicsClientId, &jointDampingObj)) { return NULL; } sm = getPhysicsClient(physicsClientId); - if (sm == 0) + if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } { double pos[3]; - double ori[4]={0,1.0,0,0}; - int hasPos =pybullet_internalSetVectord(targetPosObj,pos); - int hasOrn = pybullet_internalSetVector4d(targetOrnObj,ori); + double ori[4] = {0, 1.0, 0, 0}; + int hasPos = pybullet_internalSetVectord(targetPosObj, pos); + int hasOrn = pybullet_internalSetVector4d(targetOrnObj, ori); int szLowerLimits = lowerLimitsObj ? PySequence_Size(lowerLimitsObj) : 0; - int szUpperLimits = upperLimitsObj? PySequence_Size(upperLimitsObj): 0; - int szJointRanges = jointRangesObj? PySequence_Size(jointRangesObj):0; - int szRestPoses = restPosesObj? PySequence_Size(restPosesObj):0; - int szJointDamping = jointDampingObj? PySequence_Size(jointDampingObj):0; + int szUpperLimits = upperLimitsObj ? PySequence_Size(upperLimitsObj) : 0; + int szJointRanges = jointRangesObj ? PySequence_Size(jointRangesObj) : 0; + int szRestPoses = restPosesObj ? PySequence_Size(restPosesObj) : 0; + int szJointDamping = jointDampingObj ? PySequence_Size(jointDampingObj) : 0; int numJoints = b3GetNumJoints(sm, bodyIndex); - int hasNullSpace = 0; - int hasJointDamping = 0; + int hasJointDamping = 0; double* lowerLimits = 0; double* upperLimits = 0; double* jointRanges = 0; double* restPoses = 0; - double* jointDamping = 0; - + double* jointDamping = 0; + if (numJoints && (szLowerLimits == numJoints) && (szUpperLimits == numJoints) && - (szJointRanges == numJoints) && (szRestPoses == numJoints)) + (szJointRanges == numJoints) && (szRestPoses == numJoints)) { int szInBytes = sizeof(double) * numJoints; int i; @@ -4740,77 +4778,80 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self, jointRanges = (double*)malloc(szInBytes); restPoses = (double*)malloc(szInBytes); - for (i = 0; i < numJoints; i++) + for (i = 0; i < numJoints; i++) { - lowerLimits[i] = - pybullet_internalGetFloatFromSequence(lowerLimitsObj, i); - upperLimits[i] = - pybullet_internalGetFloatFromSequence(upperLimitsObj, i); - jointRanges[i] = - pybullet_internalGetFloatFromSequence(jointRangesObj, i); - restPoses[i] = - pybullet_internalGetFloatFromSequence(restPosesObj, i); + lowerLimits[i] = + pybullet_internalGetFloatFromSequence(lowerLimitsObj, i); + upperLimits[i] = + pybullet_internalGetFloatFromSequence(upperLimitsObj, i); + jointRanges[i] = + pybullet_internalGetFloatFromSequence(jointRangesObj, i); + restPoses[i] = + pybullet_internalGetFloatFromSequence(restPosesObj, i); } hasNullSpace = 1; } - - if (numJoints && (szJointDamping == numJoints)) - { - int szInBytes = sizeof(double) * numJoints; - int i; - jointDamping = (double*)malloc(szInBytes); - for (i = 0; i < numJoints; i++) - { - jointDamping[i] = pybullet_internalGetFloatFromSequence(jointDampingObj, i); - } - hasJointDamping = 1; - } + + if (numJoints && (szJointDamping == numJoints)) + { + int szInBytes = sizeof(double) * numJoints; + int i; + jointDamping = (double*)malloc(szInBytes); + for (i = 0; i < numJoints; i++) + { + jointDamping[i] = pybullet_internalGetFloatFromSequence(jointDampingObj, i); + } + hasJointDamping = 1; + } if (hasPos) { b3SharedMemoryStatusHandle statusHandle; - int numPos=0; + int numPos = 0; int resultBodyIndex; int result; - b3SharedMemoryCommandHandle command = b3CalculateInverseKinematicsCommandInit(sm,bodyIndex); + b3SharedMemoryCommandHandle command = b3CalculateInverseKinematicsCommandInit(sm, bodyIndex); if (hasNullSpace) { if (hasOrn) { b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(command, numJoints, endEffectorLinkIndex, pos, ori, lowerLimits, upperLimits, jointRanges, restPoses); - } else - { - b3CalculateInverseKinematicsPosWithNullSpaceVel(command,numJoints, endEffectorLinkIndex, pos, lowerLimits, upperLimits, jointRanges, restPoses); } - } else + else + { + b3CalculateInverseKinematicsPosWithNullSpaceVel(command, numJoints, endEffectorLinkIndex, pos, lowerLimits, upperLimits, jointRanges, restPoses); + } + } + else { if (hasOrn) { - b3CalculateInverseKinematicsAddTargetPositionWithOrientation(command,endEffectorLinkIndex,pos,ori); - } else + b3CalculateInverseKinematicsAddTargetPositionWithOrientation(command, endEffectorLinkIndex, pos, ori); + } + else { - b3CalculateInverseKinematicsAddTargetPurePosition(command,endEffectorLinkIndex,pos); + b3CalculateInverseKinematicsAddTargetPurePosition(command, endEffectorLinkIndex, pos); } } - - if (hasJointDamping) - { - b3CalculateInverseKinematicsSetJointDamping(command, numJoints, jointDamping); - } + + if (hasJointDamping) + { + b3CalculateInverseKinematicsSetJointDamping(command, numJoints, jointDamping); + } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - + result = b3GetStatusInverseKinematicsJointPositions(statusHandle, - &resultBodyIndex, - &numPos, - 0); + &resultBodyIndex, + &numPos, + 0); if (result && numPos) { int i; PyObject* pylist; - double* ikOutPutJointPos = (double*)malloc(numPos*sizeof(double)); + double* ikOutPutJointPos = (double*)malloc(numPos * sizeof(double)); result = b3GetStatusInverseKinematicsJointPositions(statusHandle, &resultBodyIndex, &numPos, @@ -4821,7 +4862,7 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self, PyTuple_SetItem(pylist, i, PyFloat_FromDouble(ikOutPutJointPos[i])); } - + free(ikOutPutJointPos); return pylist; } @@ -4831,440 +4872,408 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self, "Error in calculateInverseKinematics"); return NULL; } - } else + } + else { PyErr_SetString(SpamError, - "calculateInverseKinematics couldn't extract position vector3"); + "calculateInverseKinematics couldn't extract position vector3"); return NULL; } } - - Py_INCREF(Py_None); - return Py_None; + + Py_INCREF(Py_None); + return Py_None; } - - /// Given an object id, joint positions, joint velocities and joint /// accelerations, /// compute the joint forces using Inverse Dynamics static PyObject* pybullet_calculateInverseDynamics(PyObject* self, - PyObject* args,PyObject* keywds) + PyObject* args, PyObject* keywds) { - - - { - int bodyIndex; - PyObject* objPositionsQ; - PyObject* objVelocitiesQdot; - PyObject* objAccelerations; - int physicsClientId = 0; - b3PhysicsClientHandle sm = 0; - static char *kwlist[] = { "bodyIndex", "objPositions", "objVelocities", "objAccelerations","physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOOO|i", kwlist, &bodyIndex, &objPositionsQ, - &objVelocitiesQdot, &objAccelerations,&physicsClientId)) { - return NULL; + int bodyIndex; + PyObject* objPositionsQ; + PyObject* objVelocitiesQdot; + PyObject* objAccelerations; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + static char* kwlist[] = {"bodyIndex", "objPositions", "objVelocities", "objAccelerations", "physicsClientId", NULL}; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOOO|i", kwlist, &bodyIndex, &objPositionsQ, + &objVelocitiesQdot, &objAccelerations, &physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + int szObPos = PySequence_Size(objPositionsQ); + int szObVel = PySequence_Size(objVelocitiesQdot); + int szObAcc = PySequence_Size(objAccelerations); + int numJoints = b3GetNumJoints(sm, bodyIndex); + if (numJoints && (szObPos == numJoints) && (szObVel == numJoints) && + (szObAcc == numJoints)) + { + int szInBytes = sizeof(double) * numJoints; + int i; + PyObject* pylist = 0; + double* jointPositionsQ = (double*)malloc(szInBytes); + double* jointVelocitiesQdot = (double*)malloc(szInBytes); + double* jointAccelerations = (double*)malloc(szInBytes); + double* jointForcesOutput = (double*)malloc(szInBytes); + + for (i = 0; i < numJoints; i++) + { + jointPositionsQ[i] = + pybullet_internalGetFloatFromSequence(objPositionsQ, i); + jointVelocitiesQdot[i] = + pybullet_internalGetFloatFromSequence(objVelocitiesQdot, i); + jointAccelerations[i] = + pybullet_internalGetFloatFromSequence(objAccelerations, i); + } + + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle commandHandle = + b3CalculateInverseDynamicsCommandInit( + sm, bodyIndex, jointPositionsQ, jointVelocitiesQdot, + jointAccelerations); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + + statusType = b3GetStatusType(statusHandle); + + if (statusType == CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED) + { + int bodyUniqueId; + int dofCount; + + b3GetStatusInverseDynamicsJointForces(statusHandle, &bodyUniqueId, + &dofCount, 0); + + if (dofCount) + { + b3GetStatusInverseDynamicsJointForces(statusHandle, 0, 0, + jointForcesOutput); + { + { + int i; + pylist = PyTuple_New(dofCount); + for (i = 0; i < dofCount; i++) + PyTuple_SetItem(pylist, i, + PyFloat_FromDouble(jointForcesOutput[i])); + } + } + } + } + else + { + PyErr_SetString(SpamError, + "Internal error in calculateInverseDynamics"); + } + } + free(jointPositionsQ); + free(jointVelocitiesQdot); + free(jointAccelerations); + free(jointForcesOutput); + if (pylist) return pylist; + } + else + { + PyErr_SetString(SpamError, + "calculateInverseDynamics numJoints needs to be " + "positive and [joint positions], [joint velocities], " + "[joint accelerations] need to match the number of " + "joints."); + return NULL; + } + } } - sm = getPhysicsClient(physicsClientId); - if (sm == 0) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - { - int szObPos = PySequence_Size(objPositionsQ); - int szObVel = PySequence_Size(objVelocitiesQdot); - int szObAcc = PySequence_Size(objAccelerations); - int numJoints = b3GetNumJoints(sm, bodyIndex); - if (numJoints && (szObPos == numJoints) && (szObVel == numJoints) && - (szObAcc == numJoints)) { - int szInBytes = sizeof(double) * numJoints; - int i; - PyObject* pylist = 0; - double* jointPositionsQ = (double*)malloc(szInBytes); - double* jointVelocitiesQdot = (double*)malloc(szInBytes); - double* jointAccelerations = (double*)malloc(szInBytes); - double* jointForcesOutput = (double*)malloc(szInBytes); - - for (i = 0; i < numJoints; i++) { - jointPositionsQ[i] = - pybullet_internalGetFloatFromSequence(objPositionsQ, i); - jointVelocitiesQdot[i] = - pybullet_internalGetFloatFromSequence(objVelocitiesQdot, i); - jointAccelerations[i] = - pybullet_internalGetFloatFromSequence(objAccelerations, i); - } - - { - b3SharedMemoryStatusHandle statusHandle; - int statusType; - b3SharedMemoryCommandHandle commandHandle = - b3CalculateInverseDynamicsCommandInit( - sm, bodyIndex, jointPositionsQ, jointVelocitiesQdot, - jointAccelerations); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - - statusType = b3GetStatusType(statusHandle); - - if (statusType == CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED) { - int bodyUniqueId; - int dofCount; - - b3GetStatusInverseDynamicsJointForces(statusHandle, &bodyUniqueId, - &dofCount, 0); - - if (dofCount) { - b3GetStatusInverseDynamicsJointForces(statusHandle, 0, 0, - jointForcesOutput); - { - { - int i; - pylist = PyTuple_New(dofCount); - for (i = 0; i < dofCount; i++) - PyTuple_SetItem(pylist, i, - PyFloat_FromDouble(jointForcesOutput[i])); - } - } - } - - } else { - PyErr_SetString(SpamError, - "Internal error in calculateInverseDynamics"); - } - } - free(jointPositionsQ); - free(jointVelocitiesQdot); - free(jointAccelerations); - free(jointForcesOutput); - if (pylist) return pylist; - } else { - PyErr_SetString(SpamError, - "calculateInverseDynamics numJoints needs to be " - "positive and [joint positions], [joint velocities], " - "[joint accelerations] need to match the number of " - "joints."); - return NULL; - } - - } - } - Py_INCREF(Py_None); - return Py_None; + Py_INCREF(Py_None); + return Py_None; } static PyMethodDef SpamMethods[] = { - {"connect",(PyCFunction)pybullet_connectPhysicsServer, METH_VARARGS|METH_KEYWORDS, - "Connect to an existing physics server (using shared memory by default)."}, + {"connect", (PyCFunction)pybullet_connectPhysicsServer, METH_VARARGS | METH_KEYWORDS, + "Connect to an existing physics server (using shared memory by default)."}, - {"disconnect", (PyCFunction)pybullet_disconnectPhysicsServer, METH_VARARGS|METH_KEYWORDS, - "Disconnect from the physics server."}, + {"disconnect", (PyCFunction)pybullet_disconnectPhysicsServer, METH_VARARGS | METH_KEYWORDS, + "Disconnect from the physics server."}, - {"resetSimulation", (PyCFunction)pybullet_resetSimulation, METH_VARARGS|METH_KEYWORDS, - "Reset the simulation: remove all objects and start from an empty world."}, + {"resetSimulation", (PyCFunction)pybullet_resetSimulation, METH_VARARGS | METH_KEYWORDS, + "Reset the simulation: remove all objects and start from an empty world."}, - {"stepSimulation", (PyCFunction)pybullet_stepSimulation, METH_VARARGS|METH_KEYWORDS, - "Step the simulation using forward dynamics."}, + {"stepSimulation", (PyCFunction)pybullet_stepSimulation, METH_VARARGS | METH_KEYWORDS, + "Step the simulation using forward dynamics."}, - {"setGravity", (PyCFunction)pybullet_setGravity, METH_VARARGS|METH_KEYWORDS, - "Set the gravity acceleration (x,y,z)."}, + {"setGravity", (PyCFunction)pybullet_setGravity, METH_VARARGS | METH_KEYWORDS, + "Set the gravity acceleration (x,y,z)."}, - {"setTimeStep",(PyCFunction) pybullet_setTimeStep, METH_VARARGS|METH_KEYWORDS, - "Set the amount of time to proceed at each call to stepSimulation. (unit " - "is seconds, typically range is 0.01 or 0.001)"}, + {"setTimeStep", (PyCFunction)pybullet_setTimeStep, METH_VARARGS | METH_KEYWORDS, + "Set the amount of time to proceed at each call to stepSimulation. (unit " + "is seconds, typically range is 0.01 or 0.001)"}, - - - {"setDefaultContactERP", (PyCFunction) pybullet_setDefaultContactERP, METH_VARARGS| METH_KEYWORDS, - "Set the amount of contact penetration Error Recovery Paramater " - "(ERP) in each time step. \ + {"setDefaultContactERP", (PyCFunction)pybullet_setDefaultContactERP, METH_VARARGS | METH_KEYWORDS, + "Set the amount of contact penetration Error Recovery Paramater " + "(ERP) in each time step. \ This is an tuning parameter to control resting contact stability. " - "This value depends on the time step."}, - - { "setRealTimeSimulation",(PyCFunction) pybullet_setRealTimeSimulation, METH_VARARGS| METH_KEYWORDS, - "Enable or disable real time simulation (using the real time clock," - " RTC) in the physics server. Expects one integer argument, 0 or 1" }, + "This value depends on the time step."}, - { "setPhysicsEngineParameter", (PyCFunction)pybullet_setPhysicsEngineParameter, METH_VARARGS | METH_KEYWORDS, - "Set some internal physics engine parameter, such as cfm or erp etc." }, + {"setRealTimeSimulation", (PyCFunction)pybullet_setRealTimeSimulation, METH_VARARGS | METH_KEYWORDS, + "Enable or disable real time simulation (using the real time clock," + " RTC) in the physics server. Expects one integer argument, 0 or 1"}, - { "setInternalSimFlags", (PyCFunction)pybullet_setInternalSimFlags, METH_VARARGS| METH_KEYWORDS, - "This is for experimental purposes, use at own risk, magic may or not happen"}, - - {"loadURDF", (PyCFunction) pybullet_loadURDF, METH_VARARGS | METH_KEYWORDS, - "Create a multibody by loading a URDF file."}, + {"setPhysicsEngineParameter", (PyCFunction)pybullet_setPhysicsEngineParameter, METH_VARARGS | METH_KEYWORDS, + "Set some internal physics engine parameter, such as cfm or erp etc."}, - {"loadSDF", (PyCFunction)pybullet_loadSDF, METH_VARARGS| METH_KEYWORDS, - "Load multibodies from an SDF file."}, + {"setInternalSimFlags", (PyCFunction)pybullet_setInternalSimFlags, METH_VARARGS | METH_KEYWORDS, + "This is for experimental purposes, use at own risk, magic may or not happen"}, - { "loadBullet", (PyCFunction)pybullet_loadBullet, METH_VARARGS| METH_KEYWORDS, - "Restore the full state of the world from a .bullet file." }, + {"loadURDF", (PyCFunction)pybullet_loadURDF, METH_VARARGS | METH_KEYWORDS, + "Create a multibody by loading a URDF file."}, - { "saveBullet", (PyCFunction)pybullet_saveBullet, METH_VARARGS| METH_KEYWORDS, - "Save the full state of the world to a .bullet file." }, + {"loadSDF", (PyCFunction)pybullet_loadSDF, METH_VARARGS | METH_KEYWORDS, + "Load multibodies from an SDF file."}, - { "loadMJCF",(PyCFunction) pybullet_loadMJCF, METH_VARARGS| METH_KEYWORDS, - "Load multibodies from an MJCF file." }, + {"loadBullet", (PyCFunction)pybullet_loadBullet, METH_VARARGS | METH_KEYWORDS, + "Restore the full state of the world from a .bullet file."}, - {"createConstraint", (PyCFunction)pybullet_createUserConstraint, METH_VARARGS | METH_KEYWORDS, - "Create a constraint between two bodies. Returns a (int) unique id, if successfull." - }, + {"saveBullet", (PyCFunction)pybullet_saveBullet, METH_VARARGS | METH_KEYWORDS, + "Save the full state of the world to a .bullet file."}, + + {"loadMJCF", (PyCFunction)pybullet_loadMJCF, METH_VARARGS | METH_KEYWORDS, + "Load multibodies from an MJCF file."}, + + {"createConstraint", (PyCFunction)pybullet_createUserConstraint, METH_VARARGS | METH_KEYWORDS, + "Create a constraint between two bodies. Returns a (int) unique id, if successfull."}, {"changeConstraint", (PyCFunction)pybullet_changeUserConstraint, METH_VARARGS | METH_KEYWORDS, - "Change some parameters of an existing constraint, such as the child pivot or child frame orientation, using its unique id." - }, - + "Change some parameters of an existing constraint, such as the child pivot or child frame orientation, using its unique id."}, {"removeConstraint", (PyCFunction)pybullet_removeUserConstraint, METH_VARARGS | METH_KEYWORDS, - "Remove a constraint using its unique id." - }, - - { "enableJointForceTorqueSensor", (PyCFunction)pybullet_enableJointForceTorqueSensor, METH_VARARGS | METH_KEYWORDS, - "Enable or disable a joint force/torque sensor measuring the joint reaction forces." - }, + "Remove a constraint using its unique id."}, - {"saveWorld", (PyCFunction)pybullet_saveWorld, METH_VARARGS| METH_KEYWORDS, - "Save a approximate Python file to reproduce the current state of the world: saveWorld" - "(filename). (very preliminary and approximately)"}, + {"enableJointForceTorqueSensor", (PyCFunction)pybullet_enableJointForceTorqueSensor, METH_VARARGS | METH_KEYWORDS, + "Enable or disable a joint force/torque sensor measuring the joint reaction forces."}, - {"getNumBodies", (PyCFunction)pybullet_getNumBodies, METH_VARARGS| METH_KEYWORDS, - "Get the number of bodies in the simulation."}, + {"saveWorld", (PyCFunction)pybullet_saveWorld, METH_VARARGS | METH_KEYWORDS, + "Save a approximate Python file to reproduce the current state of the world: saveWorld" + "(filename). (very preliminary and approximately)"}, - {"getBodyUniqueId", (PyCFunction)pybullet_getBodyUniqueId, METH_VARARGS| METH_KEYWORDS, - "getBodyUniqueId is used after connecting to server with existing bodies." + {"getNumBodies", (PyCFunction)pybullet_getNumBodies, METH_VARARGS | METH_KEYWORDS, + "Get the number of bodies in the simulation."}, + + {"getBodyUniqueId", (PyCFunction)pybullet_getBodyUniqueId, METH_VARARGS | METH_KEYWORDS, + "getBodyUniqueId is used after connecting to server with existing bodies." "Get the unique id of the body, given a integer range [0.. number of bodies)."}, - {"getBodyInfo",(PyCFunction) pybullet_getBodyInfo, METH_VARARGS | METH_KEYWORDS, - "Get the body info, given a body unique id."}, - - {"getNumConstraints", (PyCFunction)pybullet_getNumConstraints, METH_VARARGS| METH_KEYWORDS, - "Get the number of user-created constraints in the simulation."}, + {"getBodyInfo", (PyCFunction)pybullet_getBodyInfo, METH_VARARGS | METH_KEYWORDS, + "Get the body info, given a body unique id."}, - {"getConstraintInfo",(PyCFunction) pybullet_getConstraintInfo, METH_VARARGS | METH_KEYWORDS, - "Get the user-created constraint info, given a constraint unique id."}, - - {"getConstraintUniqueId", (PyCFunction)pybullet_getBodyUniqueId, METH_VARARGS| METH_KEYWORDS, - "Get the unique id of the constraint, given a integer index in range [0.. number of constraints)."}, - - {"getBasePositionAndOrientation",(PyCFunction) pybullet_getBasePositionAndOrientation, - METH_VARARGS | METH_KEYWORDS, - "Get the world position and orientation of the base of the object. " - "(x,y,z) position vector and (x,y,z,w) quaternion orientation."}, + {"getNumConstraints", (PyCFunction)pybullet_getNumConstraints, METH_VARARGS | METH_KEYWORDS, + "Get the number of user-created constraints in the simulation."}, - {"resetBasePositionAndOrientation", - (PyCFunction) pybullet_resetBasePositionAndOrientation, METH_VARARGS| METH_KEYWORDS, - "Reset the world position and orientation of the base of the object " - "instantaneously, not through physics simulation. (x,y,z) position vector " - "and (x,y,z,w) quaternion orientation."}, + {"getConstraintInfo", (PyCFunction)pybullet_getConstraintInfo, METH_VARARGS | METH_KEYWORDS, + "Get the user-created constraint info, given a constraint unique id."}, - { "getBaseVelocity", (PyCFunction)pybullet_getBaseVelocity, - METH_VARARGS| METH_KEYWORDS, - "Get the linear and angular velocity of the base of the object " - " in world space coordinates. " - "(x,y,z) linear velocity vector and (x,y,z) angular velocity vector." }, + {"getConstraintUniqueId", (PyCFunction)pybullet_getBodyUniqueId, METH_VARARGS | METH_KEYWORDS, + "Get the unique id of the constraint, given a integer index in range [0.. number of constraints)."}, - { "resetBaseVelocity", (PyCFunction)pybullet_resetBaseVelocity, METH_VARARGS | METH_KEYWORDS, - "Reset the linear and/or angular velocity of the base of the object " - " in world space coordinates. " - "linearVelocity (x,y,z) and angularVelocity (x,y,z)." }, + {"getBasePositionAndOrientation", (PyCFunction)pybullet_getBasePositionAndOrientation, + METH_VARARGS | METH_KEYWORDS, + "Get the world position and orientation of the base of the object. " + "(x,y,z) position vector and (x,y,z,w) quaternion orientation."}, - {"getNumJoints", (PyCFunction)pybullet_getNumJoints, METH_VARARGS| METH_KEYWORDS, - "Get the number of joints for an object."}, + {"resetBasePositionAndOrientation", + (PyCFunction)pybullet_resetBasePositionAndOrientation, METH_VARARGS | METH_KEYWORDS, + "Reset the world position and orientation of the base of the object " + "instantaneously, not through physics simulation. (x,y,z) position vector " + "and (x,y,z,w) quaternion orientation."}, - {"getJointInfo", (PyCFunction)pybullet_getJointInfo, METH_VARARGS| METH_KEYWORDS, - "Get the name and type info for a joint on a body."}, + {"getBaseVelocity", (PyCFunction)pybullet_getBaseVelocity, + METH_VARARGS | METH_KEYWORDS, + "Get the linear and angular velocity of the base of the object " + " in world space coordinates. " + "(x,y,z) linear velocity vector and (x,y,z) angular velocity vector."}, - {"getJointState",(PyCFunction) pybullet_getJointState, METH_VARARGS| METH_KEYWORDS, - "Get the state (position, velocity etc) for a joint on a body."}, + {"resetBaseVelocity", (PyCFunction)pybullet_resetBaseVelocity, METH_VARARGS | METH_KEYWORDS, + "Reset the linear and/or angular velocity of the base of the object " + " in world space coordinates. " + "linearVelocity (x,y,z) and angularVelocity (x,y,z)."}, - {"getLinkState", (PyCFunction)pybullet_getLinkState, METH_VARARGS| METH_KEYWORDS, - "Provides extra information such as the Cartesian world coordinates" - " center of mass (COM) of the link, relative to the world reference" - " frame."}, + {"getNumJoints", (PyCFunction)pybullet_getNumJoints, METH_VARARGS | METH_KEYWORDS, + "Get the number of joints for an object."}, - {"resetJointState",(PyCFunction) pybullet_resetJointState, METH_VARARGS| METH_KEYWORDS, - "Reset the state (position, velocity etc) for a joint on a body " - "instantaneously, not through physics simulation."}, + {"getJointInfo", (PyCFunction)pybullet_getJointInfo, METH_VARARGS | METH_KEYWORDS, + "Get the name and type info for a joint on a body."}, - {"setJointMotorControl",(PyCFunction) pybullet_setJointMotorControl, METH_VARARGS, - "This (obsolete) method cannot select non-zero physicsClientId, use setJointMotorControl2 instead." + {"getJointState", (PyCFunction)pybullet_getJointState, METH_VARARGS | METH_KEYWORDS, + "Get the state (position, velocity etc) for a joint on a body."}, + + {"getLinkState", (PyCFunction)pybullet_getLinkState, METH_VARARGS | METH_KEYWORDS, + "Provides extra information such as the Cartesian world coordinates" + " center of mass (COM) of the link, relative to the world reference" + " frame."}, + + {"resetJointState", (PyCFunction)pybullet_resetJointState, METH_VARARGS | METH_KEYWORDS, + "Reset the state (position, velocity etc) for a joint on a body " + "instantaneously, not through physics simulation."}, + + {"setJointMotorControl", (PyCFunction)pybullet_setJointMotorControl, METH_VARARGS, + "This (obsolete) method cannot select non-zero physicsClientId, use setJointMotorControl2 instead." "Set a single joint motor control mode and desired target value. There is " - "no immediate state change, stepSimulation will process the motors."}, + "no immediate state change, stepSimulation will process the motors."}, - {"setJointMotorControl2",(PyCFunction) pybullet_setJointMotorControl2, METH_VARARGS| METH_KEYWORDS, - "Set a single joint motor control mode and desired target value. There is " - "no immediate state change, stepSimulation will process the motors."}, + {"setJointMotorControl2", (PyCFunction)pybullet_setJointMotorControl2, METH_VARARGS | METH_KEYWORDS, + "Set a single joint motor control mode and desired target value. There is " + "no immediate state change, stepSimulation will process the motors."}, - {"applyExternalForce",(PyCFunction) pybullet_applyExternalForce, METH_VARARGS| METH_KEYWORDS, - "for objectUniqueId, linkIndex (-1 for base/root link), apply a force " - "[x,y,z] at the a position [x,y,z], flag to select FORCE_IN_LINK_FRAME or " - "WORLD_FRAME coordinates"}, + {"applyExternalForce", (PyCFunction)pybullet_applyExternalForce, METH_VARARGS | METH_KEYWORDS, + "for objectUniqueId, linkIndex (-1 for base/root link), apply a force " + "[x,y,z] at the a position [x,y,z], flag to select FORCE_IN_LINK_FRAME or " + "WORLD_FRAME coordinates"}, - {"applyExternalTorque", (PyCFunction)pybullet_applyExternalTorque, METH_VARARGS| METH_KEYWORDS, - "for objectUniqueId, linkIndex (-1 for base/root link) apply a torque " - "[x,y,z] in Cartesian coordinates, flag to select TORQUE_IN_LINK_FRAME or " - "WORLD_FRAME coordinates"}, + {"applyExternalTorque", (PyCFunction)pybullet_applyExternalTorque, METH_VARARGS | METH_KEYWORDS, + "for objectUniqueId, linkIndex (-1 for base/root link) apply a torque " + "[x,y,z] in Cartesian coordinates, flag to select TORQUE_IN_LINK_FRAME or " + "WORLD_FRAME coordinates"}, - {"renderImage", pybullet_renderImageObsolete, METH_VARARGS, - "obsolete, please use getCameraImage and getViewProjectionMatrices instead" - }, + {"renderImage", pybullet_renderImageObsolete, METH_VARARGS, + "obsolete, please use getCameraImage and getViewProjectionMatrices instead"}, - { "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS, - "Render an image (given the pixel resolution width, height, camera viewMatrix " - ", projectionMatrix, lightDirection, lightColor, lightDistance, shadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, and renderer), and return the " - "8-8-8bit RGB pixel data and floating point depth values" + {"getCameraImage", (PyCFunction)pybullet_getCameraImage, METH_VARARGS | METH_KEYWORDS, + "Render an image (given the pixel resolution width, height, camera viewMatrix " + ", projectionMatrix, lightDirection, lightColor, lightDistance, shadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, and renderer), and return the " + "8-8-8bit RGB pixel data and floating point depth values" #ifdef PYBULLET_USE_NUMPY - " as NumPy arrays" + " as NumPy arrays" #endif - }, - - { "computeViewMatrix", (PyCFunction)pybullet_computeViewMatrix, METH_VARARGS | METH_KEYWORDS, - "Compute a camera viewmatrix from camera eye, target position and up vector " - }, - - { "computeViewMatrixFromYawPitchRoll",(PyCFunction)pybullet_computeViewMatrixFromYawPitchRoll, METH_VARARGS | METH_KEYWORDS, - "Compute a camera viewmatrix from camera eye, target position and up vector " - }, - - { "computeProjectionMatrix", (PyCFunction)pybullet_computeProjectionMatrix, METH_VARARGS | METH_KEYWORDS, - "Compute a camera projection matrix from screen left/right/bottom/top/near/far values" }, - { "computeProjectionMatrixFOV", (PyCFunction)pybullet_computeProjectionMatrixFOV, METH_VARARGS | METH_KEYWORDS, - "Compute a camera projection matrix from fov, aspect ratio, near, far values" - }, + {"computeViewMatrix", (PyCFunction)pybullet_computeViewMatrix, METH_VARARGS | METH_KEYWORDS, + "Compute a camera viewmatrix from camera eye, target position and up vector "}, - {"getContactPoints", (PyCFunction)pybullet_getContactPointData, METH_VARARGS | METH_KEYWORDS, - "Return existing contact points after the stepSimulation command. " - "Optional arguments one or two object unique " - "ids, that need to be involved in the contact."}, + {"computeViewMatrixFromYawPitchRoll", (PyCFunction)pybullet_computeViewMatrixFromYawPitchRoll, METH_VARARGS | METH_KEYWORDS, + "Compute a camera viewmatrix from camera eye, target position and up vector "}, - {"getClosestPoints", (PyCFunction)pybullet_getClosestPointData, METH_VARARGS | METH_KEYWORDS, - "Compute the closest points between two objects, if the distance is below a given threshold." - "Input is two objects unique ids and distance threshold." - }, + {"computeProjectionMatrix", (PyCFunction)pybullet_computeProjectionMatrix, METH_VARARGS | METH_KEYWORDS, + "Compute a camera projection matrix from screen left/right/bottom/top/near/far values"}, - { "getOverlappingObjects", (PyCFunction)pybullet_getOverlappingObjects, METH_VARARGS | METH_KEYWORDS, - "Return all the objects that have overlap with a given " - "axis-aligned bounding box volume (AABB)." - "Input are two vectors defining the AABB in world space [min_x,min_y,min_z],[max_x,max_y,max_z]." - }, + {"computeProjectionMatrixFOV", (PyCFunction)pybullet_computeProjectionMatrixFOV, METH_VARARGS | METH_KEYWORDS, + "Compute a camera projection matrix from fov, aspect ratio, near, far values"}, + {"getContactPoints", (PyCFunction)pybullet_getContactPointData, METH_VARARGS | METH_KEYWORDS, + "Return existing contact points after the stepSimulation command. " + "Optional arguments one or two object unique " + "ids, that need to be involved in the contact."}, - { "addUserDebugLine", (PyCFunction)pybullet_addUserDebugLine, METH_VARARGS | METH_KEYWORDS, + {"getClosestPoints", (PyCFunction)pybullet_getClosestPointData, METH_VARARGS | METH_KEYWORDS, + "Compute the closest points between two objects, if the distance is below a given threshold." + "Input is two objects unique ids and distance threshold."}, + + {"getOverlappingObjects", (PyCFunction)pybullet_getOverlappingObjects, METH_VARARGS | METH_KEYWORDS, + "Return all the objects that have overlap with a given " + "axis-aligned bounding box volume (AABB)." + "Input are two vectors defining the AABB in world space [min_x,min_y,min_z],[max_x,max_y,max_z]."}, + + {"addUserDebugLine", (PyCFunction)pybullet_addUserDebugLine, METH_VARARGS | METH_KEYWORDS, "Add a user debug draw line with lineFrom[3], lineTo[3], lineColorRGB[3], lineWidth, lifeTime. " - "A lifeTime of 0 means permanent until removed. Returns a unique id for the user debug item." - }, + "A lifeTime of 0 means permanent until removed. Returns a unique id for the user debug item."}, - - { "addUserDebugText", (PyCFunction)pybullet_addUserDebugText, METH_VARARGS | METH_KEYWORDS, + {"addUserDebugText", (PyCFunction)pybullet_addUserDebugText, METH_VARARGS | METH_KEYWORDS, "Add a user debug draw line with text, textPosition[3], textSize and lifeTime in seconds " - "A lifeTime of 0 means permanent until removed. Returns a unique id for the user debug item." - }, + "A lifeTime of 0 means permanent until removed. Returns a unique id for the user debug item."}, - { "addUserDebugParameter", (PyCFunction)pybullet_addUserDebugParameter, METH_VARARGS | METH_KEYWORDS, - "Add a user debug parameter, such as a slider, that can be controlled using a GUI." - }, - { "readUserDebugParameter", (PyCFunction)pybullet_readUserDebugParameter, METH_VARARGS | METH_KEYWORDS, - "Read the current value of a user debug parameter, given the user debug item unique id." - }, + {"addUserDebugParameter", (PyCFunction)pybullet_addUserDebugParameter, METH_VARARGS | METH_KEYWORDS, + "Add a user debug parameter, such as a slider, that can be controlled using a GUI."}, + {"readUserDebugParameter", (PyCFunction)pybullet_readUserDebugParameter, METH_VARARGS | METH_KEYWORDS, + "Read the current value of a user debug parameter, given the user debug item unique id."}, - { "removeUserDebugItem", (PyCFunction)pybullet_removeUserDebugItem, METH_VARARGS | METH_KEYWORDS, - "remove a user debug draw item, giving its unique id" - }, + {"removeUserDebugItem", (PyCFunction)pybullet_removeUserDebugItem, METH_VARARGS | METH_KEYWORDS, + "remove a user debug draw item, giving its unique id"}, + {"removeAllUserDebugItems", (PyCFunction)pybullet_removeAllUserDebugItems, METH_VARARGS | METH_KEYWORDS, + "remove all user debug draw items"}, - { "removeAllUserDebugItems", (PyCFunction)pybullet_removeAllUserDebugItems, METH_VARARGS | METH_KEYWORDS, - "remove all user debug draw items" - }, + {"setDebugObjectColor", (PyCFunction)pybullet_setDebugObjectColor, METH_VARARGS | METH_KEYWORDS, + "Override the wireframe debug drawing color for a particular object unique id / link index." + "If you ommit the color, the custom color will be removed."}, - { "setDebugObjectColor", (PyCFunction)pybullet_setDebugObjectColor, METH_VARARGS | METH_KEYWORDS, - "Override the wireframe debug drawing color for a particular object unique id / link index." - "If you ommit the color, the custom color will be removed." - }, + {"configureDebugVisualizer", (PyCFunction)pybullet_configureDebugVisualizer, METH_VARARGS | METH_KEYWORDS, + "For the 3D OpenGL Visualizer, enable/disable GUI, shadows."}, - { "configureDebugVisualizer", (PyCFunction)pybullet_configureDebugVisualizer, METH_VARARGS | METH_KEYWORDS, - "For the 3D OpenGL Visualizer, enable/disable GUI, shadows." - }, + {"resetDebugVisualizerCamera", (PyCFunction)pybullet_resetDebugVisualizerCamera, METH_VARARGS | METH_KEYWORDS, + "For the 3D OpenGL Visualizer, set the camera distance, yaw, pitch and target position."}, - { "resetDebugVisualizerCamera", (PyCFunction)pybullet_resetDebugVisualizerCamera, METH_VARARGS | METH_KEYWORDS, - "For the 3D OpenGL Visualizer, set the camera distance, yaw, pitch and target position." - }, + {"getVisualShapeData", (PyCFunction)pybullet_getVisualShapeData, METH_VARARGS | METH_KEYWORDS, + "Return the visual shape information for one object."}, - + {"resetVisualShapeData", (PyCFunction)pybullet_resetVisualShapeData, METH_VARARGS | METH_KEYWORDS, + "Reset part of the visual shape information for one object."}, - {"getVisualShapeData", (PyCFunction)pybullet_getVisualShapeData, METH_VARARGS| METH_KEYWORDS, - "Return the visual shape information for one object." }, - - {"resetVisualShapeData", (PyCFunction)pybullet_resetVisualShapeData, METH_VARARGS| METH_KEYWORDS, - "Reset part of the visual shape information for one object." }, - - {"loadTexture", (PyCFunction)pybullet_loadTexture, METH_VARARGS| METH_KEYWORDS, - "Load texture file." }, - - {"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS, - "Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to " - "quaternion [x,y,z,w]"}, + {"loadTexture", (PyCFunction)pybullet_loadTexture, METH_VARARGS | METH_KEYWORDS, + "Load texture file."}, - {"getEulerFromQuaternion", pybullet_getEulerFromQuaternion, METH_VARARGS, - "Convert quaternion [x,y,z,w] to Euler [roll, pitch, yaw] as in URDF/SDF " - "convention"}, + {"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS, + "Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to " + "quaternion [x,y,z,w]"}, - {"getMatrixFromQuaternion", pybullet_getMatrixFromQuaternion,METH_VARARGS, - "Compute the 3x3 matrix from a quaternion, as a list of 9 values (row-major)"}, + {"getEulerFromQuaternion", pybullet_getEulerFromQuaternion, METH_VARARGS, + "Convert quaternion [x,y,z,w] to Euler [roll, pitch, yaw] as in URDF/SDF " + "convention"}, - {"calculateInverseDynamics", (PyCFunction)pybullet_calculateInverseDynamics, METH_VARARGS| METH_KEYWORDS, - "Given an object id, joint positions, joint velocities and joint " - "accelerations, compute the joint forces using Inverse Dynamics"}, - - {"calculateInverseKinematics", (PyCFunction)pybullet_calculateInverseKinematics, - METH_VARARGS| METH_KEYWORDS, - "Inverse Kinematics bindings: Given an object id, " - "current joint positions and target position" - " for the end effector," - "compute the inverse kinematics and return the new joint state"}, - - { "getVREvents", (PyCFunction)pybullet_getVREvents, METH_VARARGS | METH_KEYWORDS, - "Get Virtual Reality events, for example to track VR controllers position/buttons" - }, - { "setVRCameraState", (PyCFunction)pybullet_setVRCameraState, METH_VARARGS | METH_KEYWORDS, - "Set properties of the VR Camera such as its root transform " - "for teleporting or to track objects (camera inside a vehicle for example)." - }, - { "getKeyboardEvents", (PyCFunction)pybullet_getKeyboardEvents, METH_VARARGS | METH_KEYWORDS, - "Get Keyboard events, keycode and state (KEY_IS_DOWN, KEY_WAS_TRIGGER, KEY_WAS_RELEASED)" - }, + {"getMatrixFromQuaternion", pybullet_getMatrixFromQuaternion, METH_VARARGS, + "Compute the 3x3 matrix from a quaternion, as a list of 9 values (row-major)"}, - { "startStateLogging", (PyCFunction)pybullet_startStateLogging, METH_VARARGS | METH_KEYWORDS, - "Start logging of state, such as robot base position, orientation, joint positions etc. " - "Specify loggingType (STATE_LOG_MINITAUR, STATE_LOG_GENERIC_ROBOT, STATE_LOG_VR_CONTROLLERS etc), " - "fileName, optional objectUniqueId. Function returns int loggingUniqueId" - }, - { "stopStateLogging", (PyCFunction)pybullet_stopStateLogging, METH_VARARGS | METH_KEYWORDS, - "Stop logging of robot state, given a loggingUniqueId." - }, - { "rayTest", (PyCFunction)pybullet_rayTest, METH_VARARGS | METH_KEYWORDS, - "Cast a ray and return the first object hit, if any. " - "Takes two arguments (from position [x,y,z] and to position [x,y,z] in Cartesian world coordinates" - }, - { "setTimeOut", (PyCFunction)pybullet_setTimeOut, METH_VARARGS | METH_KEYWORDS, - "Set the timeOut in seconds, used for most of the API calls." - }, - // todo(erwincoumans) - // saveSnapshot - // loadSnapshot - // raycast info - // object names + {"calculateInverseDynamics", (PyCFunction)pybullet_calculateInverseDynamics, METH_VARARGS | METH_KEYWORDS, + "Given an object id, joint positions, joint velocities and joint " + "accelerations, compute the joint forces using Inverse Dynamics"}, - {NULL, NULL, 0, NULL} /* Sentinel */ + {"calculateInverseKinematics", (PyCFunction)pybullet_calculateInverseKinematics, + METH_VARARGS | METH_KEYWORDS, + "Inverse Kinematics bindings: Given an object id, " + "current joint positions and target position" + " for the end effector," + "compute the inverse kinematics and return the new joint state"}, + + {"getVREvents", (PyCFunction)pybullet_getVREvents, METH_VARARGS | METH_KEYWORDS, + "Get Virtual Reality events, for example to track VR controllers position/buttons"}, + {"setVRCameraState", (PyCFunction)pybullet_setVRCameraState, METH_VARARGS | METH_KEYWORDS, + "Set properties of the VR Camera such as its root transform " + "for teleporting or to track objects (camera inside a vehicle for example)."}, + {"getKeyboardEvents", (PyCFunction)pybullet_getKeyboardEvents, METH_VARARGS | METH_KEYWORDS, + "Get Keyboard events, keycode and state (KEY_IS_DOWN, KEY_WAS_TRIGGER, KEY_WAS_RELEASED)"}, + + {"startStateLogging", (PyCFunction)pybullet_startStateLogging, METH_VARARGS | METH_KEYWORDS, + "Start logging of state, such as robot base position, orientation, joint positions etc. " + "Specify loggingType (STATE_LOG_MINITAUR, STATE_LOG_GENERIC_ROBOT, STATE_LOG_VR_CONTROLLERS etc), " + "fileName, optional objectUniqueId. Function returns int loggingUniqueId"}, + {"stopStateLogging", (PyCFunction)pybullet_stopStateLogging, METH_VARARGS | METH_KEYWORDS, + "Stop logging of robot state, given a loggingUniqueId."}, + {"rayTest", (PyCFunction)pybullet_rayTest, METH_VARARGS | METH_KEYWORDS, + "Cast a ray and return the first object hit, if any. " + "Takes two arguments (from position [x,y,z] and to position [x,y,z] in Cartesian world coordinates"}, + {"setTimeOut", (PyCFunction)pybullet_setTimeOut, METH_VARARGS | METH_KEYWORDS, + "Set the timeOut in seconds, used for most of the API calls."}, + // todo(erwincoumans) + // saveSnapshot + // loadSnapshot + // raycast info + // object names + + {NULL, NULL, 0, NULL} /* Sentinel */ }; - ///copied from CommonWindowInterface.h +///copied from CommonWindowInterface.h - -enum { +enum +{ B3G_ESCAPE = 27, B3G_F1 = 0xff00, B3G_F2, @@ -5300,15 +5309,15 @@ enum { #if PY_MAJOR_VERSION >= 3 static struct PyModuleDef moduledef = { - PyModuleDef_HEAD_INIT, "pybullet", /* m_name */ - "Python bindings for Bullet Physics Robotics API (also known as Shared " - "Memory API)", /* m_doc */ - -1, /* m_size */ - SpamMethods, /* m_methods */ - NULL, /* m_reload */ - NULL, /* m_traverse */ - NULL, /* m_clear */ - NULL, /* m_free */ + PyModuleDef_HEAD_INIT, "pybullet", /* m_name */ + "Python bindings for Bullet Physics Robotics API (also known as Shared " + "Memory API)", /* m_doc */ + -1, /* m_size */ + SpamMethods, /* m_methods */ + NULL, /* m_reload */ + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL, /* m_free */ }; #endif @@ -5319,115 +5328,110 @@ PyInit_pybullet(void) initpybullet(void) #endif { - - PyObject* m; + PyObject* m; #if PY_MAJOR_VERSION >= 3 - m = PyModule_Create(&moduledef); + m = PyModule_Create(&moduledef); #else - m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet"); + m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet"); #endif #if PY_MAJOR_VERSION >= 3 - if (m == NULL) return m; + if (m == NULL) return m; #else - if (m == NULL) return; + if (m == NULL) return; #endif - PyModule_AddIntConstant(m, "SHARED_MEMORY", - eCONNECT_SHARED_MEMORY); // user read - PyModule_AddIntConstant(m, "DIRECT", eCONNECT_DIRECT); // user read - PyModule_AddIntConstant(m, "GUI", eCONNECT_GUI); // user read - PyModule_AddIntConstant(m, "UDP", eCONNECT_UDP); // user read - PyModule_AddIntConstant(m, "TCP", eCONNECT_TCP); // user read + PyModule_AddIntConstant(m, "SHARED_MEMORY", + eCONNECT_SHARED_MEMORY); // user read + PyModule_AddIntConstant(m, "DIRECT", eCONNECT_DIRECT); // user read + PyModule_AddIntConstant(m, "GUI", eCONNECT_GUI); // user read + PyModule_AddIntConstant(m, "UDP", eCONNECT_UDP); // user read + PyModule_AddIntConstant(m, "TCP", eCONNECT_TCP); // user read - PyModule_AddIntConstant(m, "JOINT_REVOLUTE", eRevoluteType); // user read - PyModule_AddIntConstant(m, "JOINT_PRISMATIC", ePrismaticType); // user read - PyModule_AddIntConstant(m, "JOINT_SPHERICAL", eSphericalType); // user read - PyModule_AddIntConstant(m, "JOINT_PLANAR", ePlanarType); // user read - PyModule_AddIntConstant(m, "JOINT_FIXED", eFixedType); // user read - PyModule_AddIntConstant(m, "JOINT_POINT2POINT", ePoint2PointType); // user read + PyModule_AddIntConstant(m, "JOINT_REVOLUTE", eRevoluteType); // user read + PyModule_AddIntConstant(m, "JOINT_PRISMATIC", ePrismaticType); // user read + PyModule_AddIntConstant(m, "JOINT_SPHERICAL", eSphericalType); // user read + PyModule_AddIntConstant(m, "JOINT_PLANAR", ePlanarType); // user read + PyModule_AddIntConstant(m, "JOINT_FIXED", eFixedType); // user read + PyModule_AddIntConstant(m, "JOINT_POINT2POINT", ePoint2PointType); // user read - PyModule_AddIntConstant(m, "SENSOR_FORCE_TORQUE", eSensorForceTorqueType); // user read + PyModule_AddIntConstant(m, "SENSOR_FORCE_TORQUE", eSensorForceTorqueType); // user read + PyModule_AddIntConstant(m, "TORQUE_CONTROL", CONTROL_MODE_TORQUE); + PyModule_AddIntConstant(m, "VELOCITY_CONTROL", + CONTROL_MODE_VELOCITY); // user read + PyModule_AddIntConstant(m, "POSITION_CONTROL", + CONTROL_MODE_POSITION_VELOCITY_PD); // user read - PyModule_AddIntConstant(m, "TORQUE_CONTROL", CONTROL_MODE_TORQUE); - PyModule_AddIntConstant(m, "VELOCITY_CONTROL", - CONTROL_MODE_VELOCITY); // user read - PyModule_AddIntConstant(m, "POSITION_CONTROL", - CONTROL_MODE_POSITION_VELOCITY_PD); // user read + PyModule_AddIntConstant(m, "LINK_FRAME", EF_LINK_FRAME); + PyModule_AddIntConstant(m, "WORLD_FRAME", EF_WORLD_FRAME); - PyModule_AddIntConstant(m, "LINK_FRAME", EF_LINK_FRAME); - PyModule_AddIntConstant(m, "WORLD_FRAME", EF_WORLD_FRAME); + PyModule_AddIntConstant(m, "CONTACT_REPORT_EXISTING", CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS); + PyModule_AddIntConstant(m, "CONTACT_RECOMPUTE_CLOSEST", CONTACT_QUERY_MODE_COMPUTE_CLOSEST_POINTS); - PyModule_AddIntConstant(m, "CONTACT_REPORT_EXISTING", CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS); - PyModule_AddIntConstant(m, "CONTACT_RECOMPUTE_CLOSEST", CONTACT_QUERY_MODE_COMPUTE_CLOSEST_POINTS); + PyModule_AddIntConstant(m, "VR_BUTTON_IS_DOWN", eButtonIsDown); + PyModule_AddIntConstant(m, "VR_BUTTON_WAS_TRIGGERED", eButtonTriggered); + PyModule_AddIntConstant(m, "VR_BUTTON_WAS_RELEASED", eButtonReleased); - PyModule_AddIntConstant(m, "VR_BUTTON_IS_DOWN", eButtonIsDown); - PyModule_AddIntConstant(m, "VR_BUTTON_WAS_TRIGGERED", eButtonTriggered); - PyModule_AddIntConstant(m, "VR_BUTTON_WAS_RELEASED", eButtonReleased); - - PyModule_AddIntConstant(m, "VR_MAX_CONTROLLERS", MAX_VR_CONTROLLERS); - PyModule_AddIntConstant(m, "VR_MAX_BUTTONS", MAX_VR_BUTTONS); + PyModule_AddIntConstant(m, "VR_MAX_CONTROLLERS", MAX_VR_CONTROLLERS); + PyModule_AddIntConstant(m, "VR_MAX_BUTTONS", MAX_VR_BUTTONS); - PyModule_AddIntConstant(m, "KEY_IS_DOWN", eButtonIsDown); - PyModule_AddIntConstant(m, "KEY_WAS_TRIGGERED", eButtonTriggered); - PyModule_AddIntConstant(m, "KEY_WAS_RELEASED", eButtonReleased); + PyModule_AddIntConstant(m, "KEY_IS_DOWN", eButtonIsDown); + PyModule_AddIntConstant(m, "KEY_WAS_TRIGGERED", eButtonTriggered); + PyModule_AddIntConstant(m, "KEY_WAS_RELEASED", eButtonReleased); - PyModule_AddIntConstant(m, "STATE_LOGGING_MINITAUR", STATE_LOGGING_MINITAUR); - PyModule_AddIntConstant(m, "STATE_LOGGING_GENERIC_ROBOT", STATE_LOGGING_GENERIC_ROBOT); - PyModule_AddIntConstant(m, "STATE_LOGGING_VR_CONTROLLERS", STATE_LOGGING_VR_CONTROLLERS); + PyModule_AddIntConstant(m, "STATE_LOGGING_MINITAUR", STATE_LOGGING_MINITAUR); + PyModule_AddIntConstant(m, "STATE_LOGGING_GENERIC_ROBOT", STATE_LOGGING_GENERIC_ROBOT); + PyModule_AddIntConstant(m, "STATE_LOGGING_VR_CONTROLLERS", STATE_LOGGING_VR_CONTROLLERS); - PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI); - PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS); - PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME); + PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI); + PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS); + PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME); - PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER); - PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL); + PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER); + PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL); - PyModule_AddIntConstant(m,"B3G_F1",B3G_F1); - PyModule_AddIntConstant(m,"B3G_F2",B3G_F2); - PyModule_AddIntConstant(m,"B3G_F3",B3G_F3); - PyModule_AddIntConstant(m,"B3G_F4",B3G_F4); - PyModule_AddIntConstant(m,"B3G_F5",B3G_F5); - PyModule_AddIntConstant(m,"B3G_F6",B3G_F6); - PyModule_AddIntConstant(m,"B3G_F7",B3G_F7); - PyModule_AddIntConstant(m,"B3G_F8",B3G_F8); - PyModule_AddIntConstant(m,"B3G_F9",B3G_F9); - PyModule_AddIntConstant(m,"B3G_F10",B3G_F10); - PyModule_AddIntConstant(m,"B3G_F11",B3G_F11); - PyModule_AddIntConstant(m,"B3G_F12",B3G_F12); - PyModule_AddIntConstant(m,"B3G_F13",B3G_F13); - PyModule_AddIntConstant(m,"B3G_F14",B3G_F14); - PyModule_AddIntConstant(m,"B3G_F15",B3G_F15); - PyModule_AddIntConstant(m,"B3G_LEFT_ARROW",B3G_LEFT_ARROW); - PyModule_AddIntConstant(m,"B3G_RIGHT_ARROW",B3G_RIGHT_ARROW); - PyModule_AddIntConstant(m,"B3G_UP_ARROW",B3G_UP_ARROW); - PyModule_AddIntConstant(m,"B3G_DOWN_ARROW",B3G_DOWN_ARROW); - PyModule_AddIntConstant(m,"B3G_PAGE_UP",B3G_PAGE_UP); - PyModule_AddIntConstant(m,"B3G_PAGE_DOWN",B3G_PAGE_DOWN); - PyModule_AddIntConstant(m,"B3G_END",B3G_END); - PyModule_AddIntConstant(m,"B3G_HOME",B3G_HOME); - PyModule_AddIntConstant(m,"B3G_INSERT",B3G_INSERT); - PyModule_AddIntConstant(m,"B3G_DELETE",B3G_DELETE); - PyModule_AddIntConstant(m,"B3G_BACKSPACE", B3G_BACKSPACE); - PyModule_AddIntConstant(m,"B3G_SHIFT", B3G_SHIFT); - PyModule_AddIntConstant(m,"B3G_CONTROL", B3G_CONTROL); - PyModule_AddIntConstant(m,"B3G_ALT", B3G_ALT); - PyModule_AddIntConstant(m,"B3G_RETURN", B3G_RETURN); + PyModule_AddIntConstant(m, "B3G_F1", B3G_F1); + PyModule_AddIntConstant(m, "B3G_F2", B3G_F2); + PyModule_AddIntConstant(m, "B3G_F3", B3G_F3); + PyModule_AddIntConstant(m, "B3G_F4", B3G_F4); + PyModule_AddIntConstant(m, "B3G_F5", B3G_F5); + PyModule_AddIntConstant(m, "B3G_F6", B3G_F6); + PyModule_AddIntConstant(m, "B3G_F7", B3G_F7); + PyModule_AddIntConstant(m, "B3G_F8", B3G_F8); + PyModule_AddIntConstant(m, "B3G_F9", B3G_F9); + PyModule_AddIntConstant(m, "B3G_F10", B3G_F10); + PyModule_AddIntConstant(m, "B3G_F11", B3G_F11); + PyModule_AddIntConstant(m, "B3G_F12", B3G_F12); + PyModule_AddIntConstant(m, "B3G_F13", B3G_F13); + PyModule_AddIntConstant(m, "B3G_F14", B3G_F14); + PyModule_AddIntConstant(m, "B3G_F15", B3G_F15); + PyModule_AddIntConstant(m, "B3G_LEFT_ARROW", B3G_LEFT_ARROW); + PyModule_AddIntConstant(m, "B3G_RIGHT_ARROW", B3G_RIGHT_ARROW); + PyModule_AddIntConstant(m, "B3G_UP_ARROW", B3G_UP_ARROW); + PyModule_AddIntConstant(m, "B3G_DOWN_ARROW", B3G_DOWN_ARROW); + PyModule_AddIntConstant(m, "B3G_PAGE_UP", B3G_PAGE_UP); + PyModule_AddIntConstant(m, "B3G_PAGE_DOWN", B3G_PAGE_DOWN); + PyModule_AddIntConstant(m, "B3G_END", B3G_END); + PyModule_AddIntConstant(m, "B3G_HOME", B3G_HOME); + PyModule_AddIntConstant(m, "B3G_INSERT", B3G_INSERT); + PyModule_AddIntConstant(m, "B3G_DELETE", B3G_DELETE); + PyModule_AddIntConstant(m, "B3G_BACKSPACE", B3G_BACKSPACE); + PyModule_AddIntConstant(m, "B3G_SHIFT", B3G_SHIFT); + PyModule_AddIntConstant(m, "B3G_CONTROL", B3G_CONTROL); + PyModule_AddIntConstant(m, "B3G_ALT", B3G_ALT); + PyModule_AddIntConstant(m, "B3G_RETURN", B3G_RETURN); - - - SpamError = PyErr_NewException("pybullet.error", NULL, NULL); - Py_INCREF(SpamError); - PyModule_AddObject(m, "error", SpamError); + SpamError = PyErr_NewException("pybullet.error", NULL, NULL); + Py_INCREF(SpamError); + PyModule_AddObject(m, "error", SpamError); #ifdef PYBULLET_USE_NUMPY - // Initialize numpy array. - import_array(); -#endif //PYBULLET_USE_NUMPY - + // Initialize numpy array. + import_array(); +#endif //PYBULLET_USE_NUMPY #if PY_MAJOR_VERSION >= 3 - return m; + return m; #endif } From fa60cc5f567efb516ff6fc02a2220abeae44ddb7 Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Tue, 14 Mar 2017 02:32:02 +0300 Subject: [PATCH 34/66] URDF loader: fix SDF branch, warn about unsupported geometry --- .../ImportURDFDemo/BulletUrdfImporter.cpp | 5 +- .../Importers/ImportURDFDemo/UrdfParser.cpp | 113 +++++++++--------- .../TinyRendererVisualShapeConverter.cpp | 2 +- 3 files changed, 61 insertions(+), 59 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 553c34b12..0820d7e5e 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -755,7 +755,8 @@ upAxisMat.setIdentity(); } // mesh case default: - b3Warning("Error: unknown visual geometry type\n"); + b3Warning("Error: unknown collision geometry type %i\n", collision->m_geometry.m_type); + // for example, URDF_GEOM_PLANE } return shape; } @@ -943,7 +944,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha } default: - b3Warning("Error: unknown visual geometry type\n"); + b3Warning("Error: unknown visual geometry type %i\n", visual->m_geometry.m_type); } //if we have a convex, tesselate into localVertices/localIndices diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index cd0a19acc..ad5247710 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -410,67 +410,68 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* geom.m_type = URDF_GEOM_CAPSULE; if (!shape->Attribute("length") || !shape->Attribute("radius")) - { - logger->reportError("Capsule shape must have both length and radius attributes"); - return false; - } + { + logger->reportError("Capsule shape must have both length and radius attributes"); + return false; + } geom.m_hasFromTo = false; geom.m_capsuleRadius = urdfLexicalCast(shape->Attribute("radius")); geom.m_capsuleHalfHeight = btScalar(0.5)*urdfLexicalCast(shape->Attribute("length")); - } - else if (type_name == "mesh") - { - geom.m_type = URDF_GEOM_MESH; - if (m_parseSDF) - { - TiXmlElement* scale = shape->FirstChildElement("scale"); - if (0==scale) - { - geom.m_meshScale.setValue(1,1,1); - } - else - { - parseVector3(geom.m_meshScale,scale->GetText(),logger); - } - - TiXmlElement* filename = shape->FirstChildElement("uri"); - geom.m_meshFileName = filename->GetText(); - } - else - { - if (!shape->Attribute("filename")) - { - logger->reportError("Mesh must contain a filename attribute"); - return false; - } - - bool success = findExistingMeshFile( - m_urdf2Model.m_sourceFile, shape->Attribute("filename"), sourceFileLocation(shape), - &geom.m_meshFileName, &geom.m_meshFileType); - if (!success) - { - // warning printed - return false; - } - geom.m_meshScale.setValue(1,1,1); + else if (type_name == "mesh") + { + geom.m_type = URDF_GEOM_MESH; + geom.m_meshScale.setValue(1,1,1); + std::string fn; - if (shape->Attribute("scale")) - { - if (!parseVector3(geom.m_meshScale,shape->Attribute("scale"),logger)) - { - logger->reportWarning("%s: scale should be a vector3, not single scalar. Workaround activated.\n"); - std::string scalar_str = shape->Attribute("scale"); - double scaleFactor = urdfLexicalCast(scalar_str.c_str()); - if (scaleFactor) - { - geom.m_meshScale.setValue(scaleFactor,scaleFactor,scaleFactor); - } - } - } else - { - } - } + if (m_parseSDF) + { + if (TiXmlElement* scale = shape->FirstChildElement("scale")) + { + parseVector3(geom.m_meshScale,scale->GetText(),logger); + } + if (TiXmlElement* filename = shape->FirstChildElement("uri")) + { + fn = filename->GetText(); + } + } + else + { + // URDF + if (shape->Attribute("filename")) + { + fn = shape->Attribute("filename"); + } + if (shape->Attribute("scale")) + { + if (!parseVector3(geom.m_meshScale, shape->Attribute("scale"), logger)) + { + logger->reportWarning("Scale should be a vector3, not single scalar. Workaround activated.\n"); + std::string scalar_str = shape->Attribute("scale"); + double scaleFactor = urdfLexicalCast(scalar_str.c_str()); + if (scaleFactor) + { + geom.m_meshScale.setValue(scaleFactor, scaleFactor, scaleFactor); + } + } + } + } + + if (fn.empty()) + { + logger->reportError("Mesh filename is empty"); + return false; + } + + geom.m_meshFileName = fn; + bool success = findExistingMeshFile( + m_urdf2Model.m_sourceFile, fn, sourceFileLocation(shape), + &geom.m_meshFileName, &geom.m_meshFileType); + if (!success) + { + // warning already printed + return false; + } } else { diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 1876e9623..d2c3b79bd 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -380,7 +380,7 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref default: { - b3Warning("Error: unknown visual geometry type\n"); + b3Warning("TinyRenderer: unknown visual geometry type %i\n", visual->m_geometry.m_type); } } From 8145203222a1d7603dcd7defaaab238fb342e0e3 Mon Sep 17 00:00:00 2001 From: Julian Date: Mon, 13 Mar 2017 22:04:16 -0700 Subject: [PATCH 35/66] add 1dof to kuka end effector --- examples/pybullet/.DS_Store | Bin 0 -> 8196 bytes examples/pybullet/vr_kuka_control.py | 25 +++++++++++++++++++++---- 2 files changed, 21 insertions(+), 4 deletions(-) create mode 100644 examples/pybullet/.DS_Store diff --git a/examples/pybullet/.DS_Store b/examples/pybullet/.DS_Store new file mode 100644 index 0000000000000000000000000000000000000000..239940476bbd0d679a427e6eaba1074db1ac5a30 GIT binary patch literal 8196 zcmeHM!EO^V5FLj~4Q*0V(TWNrv`0>rK-{=Qr9B{lgv0@H3Y&C+s@rVXZrXCog@51| z_!@qLJ0Ae=jaQ9#*P%Hf3U=k4tut>tex9*Asfd`p>ET0>9T91xQ})*J@HBqT-e|3I zB>kl8Eeg-!^RQb3)z*4e5xV8){tBB4#*t%1PH!;lqud%(P@t(9y{hv%}!fB zVBWDDLYuQ^)p^b5n*OSz-|*7>sA+FPJCPJWnGCop8Ny5cPOm-wwc?tEZT0F5`nj%c z0G{b*A}8>>!21Z}K1<(fmNtQ$qQ~&$9Jm6$4S=4)r^IJL$oUs%x9`73wbeik zFyk4#NZ~d2!^@<`g=?qhu|q7s`||B2qr$~^uwJf}>u26Q21-4sMlbWtw4EJX^Tgn& zhQY2^FdfaT7#WgdjT6kqT=B+!1-I?NEfpio(Tb&eUQ5jMLOoi}Dl)lZ^%mBXAyzY3 zv8Pa>BdKq7%u5fNnfy|tc7*tQgWWjyq7g?GbO$>fBW@CTttVCL=T!Ia!r8x7jj#n# z!hAKZcK1@7vBEQs8RFYJa^oU`;r{pheey5e|GxmBpN}K} literal 0 HcmV?d00001 diff --git a/examples/pybullet/vr_kuka_control.py b/examples/pybullet/vr_kuka_control.py index d35e8ef45..0117dcb4c 100644 --- a/examples/pybullet/vr_kuka_control.py +++ b/examples/pybullet/vr_kuka_control.py @@ -7,6 +7,7 @@ p.connect(p.SHARED_MEMORY) kuka = 3 kuka_gripper = 7 POSITION = 1 +ORIENTATION = 2 BUTTONS = 6 THRESHOLD = 1.3 @@ -71,14 +72,30 @@ while True: p.setJointMotorControl2(kuka_gripper, i, p.VELOCITY_CONTROL, targetVelocity=-5, force=50) if sq_len < THRESHOLD * THRESHOLD: + eef_pos = e[POSITION] - joint_pos = p.calculateInverseKinematics(kuka, 6, e[POSITION], (0, 1, 0, 0), + joint_pos = p.calculateInverseKinematics(kuka, 6, eef_pos, lowerLimits=LOWER_LIMITS, upperLimits=UPPER_LIMITS, jointRanges=JOINT_RANGE, restPoses=REST_POSE, jointDamping=JOINT_DAMP) - for i in range(len(joint_pos)): + + # Only need links 1- 5, no need for joint 6 with pure position IK + for i in range(len(joint_pos) - 1): p.setJointMotorControl2(kuka, i, p.POSITION_CONTROL, - targetPosition=joint_pos[i], targetVelocity=0, - positionGain=0.6, velocityGain=1.0, force=MAX_FORCE) + targetPosition=joint_pos[i], targetVelocity=0, positionGain=0.05, + velocityGain=1.0, force=MAX_FORCE) + + # Rotate the end effector + targetOrn = e[ORIENTATION] + + _, _, z = p.getEulerFromQuaternion(targetOrn) + # End effector needs protection, done by using triangular tricks + p.setJointMotorControl2(kuka, 6, p.POSITION_CONTROL, + targetPosition=np.arcsin(np.sin(z)), targetVelocity=0, positionGain=0.6, + velocityGain=1.0, force=MAX_FORCE) + + p.setJointMotorControl2(kuka, 5, p.POSITION_CONTROL, + targetPosition=-math.pi, targetVelocity=0, + positionGain=0.03, velocityGain=1.0, force=MAX_FORCE) else: # Set back to original rest pose From fabe09fe535145edb927fbf4aee49f4d70fa2037 Mon Sep 17 00:00:00 2001 From: Julian Date: Mon, 13 Mar 2017 22:04:28 -0700 Subject: [PATCH 36/66] add 1 dof to kuka end effector --- examples/pybullet/.DS_Store | Bin 8196 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 examples/pybullet/.DS_Store diff --git a/examples/pybullet/.DS_Store b/examples/pybullet/.DS_Store deleted file mode 100644 index 239940476bbd0d679a427e6eaba1074db1ac5a30..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8196 zcmeHM!EO^V5FLj~4Q*0V(TWNrv`0>rK-{=Qr9B{lgv0@H3Y&C+s@rVXZrXCog@51| z_!@qLJ0Ae=jaQ9#*P%Hf3U=k4tut>tex9*Asfd`p>ET0>9T91xQ})*J@HBqT-e|3I zB>kl8Eeg-!^RQb3)z*4e5xV8){tBB4#*t%1PH!;lqud%(P@t(9y{hv%}!fB zVBWDDLYuQ^)p^b5n*OSz-|*7>sA+FPJCPJWnGCop8Ny5cPOm-wwc?tEZT0F5`nj%c z0G{b*A}8>>!21Z}K1<(fmNtQ$qQ~&$9Jm6$4S=4)r^IJL$oUs%x9`73wbeik zFyk4#NZ~d2!^@<`g=?qhu|q7s`||B2qr$~^uwJf}>u26Q21-4sMlbWtw4EJX^Tgn& zhQY2^FdfaT7#WgdjT6kqT=B+!1-I?NEfpio(Tb&eUQ5jMLOoi}Dl)lZ^%mBXAyzY3 zv8Pa>BdKq7%u5fNnfy|tc7*tQgWWjyq7g?GbO$>fBW@CTttVCL=T!Ia!r8x7jj#n# z!hAKZcK1@7vBEQs8RFYJa^oU`;r{pheey5e|GxmBpN}K} From 7cc31e7c9802040a1fe5359448fc7d12a2b6e133 Mon Sep 17 00:00:00 2001 From: Julian Date: Mon, 13 Mar 2017 22:08:17 -0700 Subject: [PATCH 37/66] fixed minor issues, added 1dof on end effector rotation. gripper is raw --- examples/pybullet/vr_kuka_control.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/examples/pybullet/vr_kuka_control.py b/examples/pybullet/vr_kuka_control.py index 0117dcb4c..ba52b5c18 100644 --- a/examples/pybullet/vr_kuka_control.py +++ b/examples/pybullet/vr_kuka_control.py @@ -35,7 +35,7 @@ while True: for e in (events): # Only use one controller - if e[0] == min(controllers): + if e[0] == controllers[0]: break sq_len = euc_dist(p.getLinkState(kuka, 6)[0], e[POSITION]) @@ -66,7 +66,6 @@ while True: # positionGain=1, velocityGain=0.5, force=50) # avg = p.getJointState(kuka_gripper, i)[0] - if e[BUTTONS][33] & p.VR_BUTTON_WAS_RELEASED: for i in range(p.getNumJoints(kuka_gripper)): p.setJointMotorControl2(kuka_gripper, i, p.VELOCITY_CONTROL, targetVelocity=-5, force=50) @@ -78,8 +77,8 @@ while True: lowerLimits=LOWER_LIMITS, upperLimits=UPPER_LIMITS, jointRanges=JOINT_RANGE, restPoses=REST_POSE, jointDamping=JOINT_DAMP) - # Only need links 1- 5, no need for joint 6 with pure position IK - for i in range(len(joint_pos) - 1): + # Only need links 1- 4, no need for joint 5-6 with pure position IK + for i in range(len(joint_pos) - 2): p.setJointMotorControl2(kuka, i, p.POSITION_CONTROL, targetPosition=joint_pos[i], targetVelocity=0, positionGain=0.05, velocityGain=1.0, force=MAX_FORCE) @@ -90,7 +89,7 @@ while True: _, _, z = p.getEulerFromQuaternion(targetOrn) # End effector needs protection, done by using triangular tricks p.setJointMotorControl2(kuka, 6, p.POSITION_CONTROL, - targetPosition=np.arcsin(np.sin(z)), targetVelocity=0, positionGain=0.6, + targetPosition=np.arcsin(np.sin(z)), targetVelocity=0, positionGain=0.5, velocityGain=1.0, force=MAX_FORCE) p.setJointMotorControl2(kuka, 5, p.POSITION_CONTROL, From b686d1274c49e809fddb34904057b61d0218396e Mon Sep 17 00:00:00 2001 From: Julian Date: Mon, 13 Mar 2017 22:09:08 -0700 Subject: [PATCH 38/66] fixed minor issues, added 1dof on end effector rotation. gripper is raw --- examples/pybullet/vr_kuka_control.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/pybullet/vr_kuka_control.py b/examples/pybullet/vr_kuka_control.py index ba52b5c18..dccbf5453 100644 --- a/examples/pybullet/vr_kuka_control.py +++ b/examples/pybullet/vr_kuka_control.py @@ -2,6 +2,8 @@ # Require p.setInternalSimFlags(0) in kuka_setup import pybullet as p import math +import numpy as np + p.connect(p.SHARED_MEMORY) kuka = 3 From bbefc8fe7e4ffa0a259bd73918e1b55836e0a73a Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 13 Mar 2017 22:27:37 -0700 Subject: [PATCH 39/66] Apply temporary stack-memory optimization, thanks to Jim Tillander (old pull request 316 https://github.com/bulletphysics/bullet3/pull/316) You can disable this in the build system, by adding preprocessor define 'BT_DISABLE_STACK_TEMP_MEMORY' --- src/BulletCollision/BroadphaseCollision/btDbvt.h | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/BulletCollision/BroadphaseCollision/btDbvt.h b/src/BulletCollision/BroadphaseCollision/btDbvt.h index 1ca175723..b5a001458 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvt.h +++ b/src/BulletCollision/BroadphaseCollision/btDbvt.h @@ -942,7 +942,13 @@ inline void btDbvt::collideTV( const btDbvtNode* root, ATTRIBUTE_ALIGNED16(btDbvtVolume) volume(vol); btAlignedObjectArray stack; stack.resize(0); +#ifndef BT_DISABLE_STACK_TEMP_MEMORY + char tempmemory[SIMPLE_STACKSIZE*sizeof(const btDbvtNode*)]; + stack.initializeFromBuffer(tempmemory, 0, SIMPLE_STACKSIZE); +#else stack.reserve(SIMPLE_STACKSIZE); +#endif //BT_DISABLE_STACK_TEMP_MEMORY + stack.push_back(root); do { const btDbvtNode* n=stack[stack.size()-1]; @@ -1078,7 +1084,12 @@ inline void btDbvt::rayTest( const btDbvtNode* root, int depth=1; int treshold=DOUBLE_STACKSIZE-2; + char tempmemory[DOUBLE_STACKSIZE * sizeof(const btDbvtNode*)]; +#ifndef BT_DISABLE_STACK_TEMP_MEMORY + stack.initializeFromBuffer(tempmemory, DOUBLE_STACKSIZE, DOUBLE_STACKSIZE); +#else//BT_DISABLE_STACK_TEMP_MEMORY stack.resize(DOUBLE_STACKSIZE); +#endif //BT_DISABLE_STACK_TEMP_MEMORY stack[0]=root; btVector3 bounds[2]; do { From 3d2cb1cabf61ee0020e1168ec8288e8079b9e64c Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 14 Mar 2017 10:40:27 -0700 Subject: [PATCH 40/66] also allow absolute path in asset files (.obj, .stl, .dae etc) --- .../ImportURDFDemo/BulletUrdfImporter.cpp | 31 +++++++++++++------ 1 file changed, 22 insertions(+), 9 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 0820d7e5e..ae3364334 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -512,19 +512,32 @@ bool findExistingMeshFile( shorter.reverse(); std::string existing_file; - for (std::list::iterator x=shorter.begin(); x!=shorter.end(); ++x) + { - std::string attempt = *x + "/" + fn; + std::string attempt = fn; FILE* f = fopen(attempt.c_str(), "rb"); - if (!f) + if (f) { - //b3Printf("%s: tried '%s'", error_message_prefix.c_str(), attempt.c_str()); - continue; + existing_file = attempt; + fclose(f); + } + } + if (existing_file.empty()) + { + for (std::list::iterator x=shorter.begin(); x!=shorter.end(); ++x) + { + std::string attempt = *x + "/" + fn; + FILE* f = fopen(attempt.c_str(), "rb"); + if (!f) + { + //b3Printf("%s: tried '%s'", error_message_prefix.c_str(), attempt.c_str()); + continue; + } + fclose(f); + existing_file = attempt; + //b3Printf("%s: found '%s'", error_message_prefix.c_str(), attempt.c_str()); + break; } - fclose(f); - existing_file = attempt; - //b3Printf("%s: found '%s'", error_message_prefix.c_str(), attempt.c_str()); - break; } if (existing_file.empty()) From 66919cc66a6715f203afce39842d4ee5a8305621 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 14 Mar 2017 13:13:16 -0700 Subject: [PATCH 41/66] fix unreachable code --- examples/pybullet/pybullet.c | 27 ++++++--------------------- 1 file changed, 6 insertions(+), 21 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index c097ba600..36ceb794c 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1715,15 +1715,9 @@ static PyObject* pybullet_getBodyInfo(PyObject* self, PyObject* args, PyObject* PyTuple_SetItem(pyListJointInfo, 0, PyString_FromString(info.m_baseName)); return pyListJointInfo; } - else - { - PyErr_SetString(SpamError, "Couldn't get body info"); - return NULL; - } } } - - PyErr_SetString(SpamError, "error in getBodyInfo."); + PyErr_SetString(SpamError, "Couldn't get body info"); return NULL; } @@ -1800,15 +1794,10 @@ static PyObject* pybullet_getConstraintInfo(PyObject* self, PyObject* args, PyOb return pyListConstraintInfo; } - else - { - PyErr_SetString(SpamError, "Couldn't get user constraint info"); - return NULL; - } } } - PyErr_SetString(SpamError, "error in getConstraintInfo."); + PyErr_SetString(SpamError, "Couldn't get user constraint info"); return NULL; } @@ -1908,12 +1897,10 @@ static PyObject* pybullet_resetJointState(PyObject* self, PyObject* args, PyObje targetValue); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - Py_INCREF(Py_None); - return Py_None; } } - PyErr_SetString(SpamError, "error in resetJointState."); - return NULL; + Py_INCREF(Py_None); + return Py_None; } static PyObject* pybullet_resetBaseVelocity(PyObject* self, PyObject* args, PyObject* keywds) @@ -2055,12 +2042,10 @@ static PyObject* pybullet_resetBasePositionAndOrientation(PyObject* self, orn[2], orn[3]); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - Py_INCREF(Py_None); - return Py_None; } } - PyErr_SetString(SpamError, "error in resetJointState."); - return NULL; + Py_INCREF(Py_None); + return Py_None; } // Get the a single joint info for a specific bodyIndex From b0aef4466854e66de75b2f5015d8008be86921d5 Mon Sep 17 00:00:00 2001 From: Erik Ogenvik Date: Mon, 13 Mar 2017 21:20:38 +0100 Subject: [PATCH 42/66] Make it compile on Linux. I simply copied from BasicDemo/CMakeList.txt --- examples/RobotSimulator/CMakeLists.txt | 29 ++++++++++++++++++++++++-- 1 file changed, 27 insertions(+), 2 deletions(-) diff --git a/examples/RobotSimulator/CMakeLists.txt b/examples/RobotSimulator/CMakeLists.txt index 0dbf71053..c9e0a66c3 100644 --- a/examples/RobotSimulator/CMakeLists.txt +++ b/examples/RobotSimulator/CMakeLists.txt @@ -138,8 +138,34 @@ IF(BUILD_CLSOCKET) ) ENDIF() -ADD_EXECUTABLE(App_RobotSimulator ${RobotSimulator_SRCS}) +#some code to support OpenGL and Glew cross platform +IF (WIN32) + INCLUDE_DIRECTORIES( + ${BULLET_PHYSICS_SOURCE_DIR}/btgui/OpenGLWindow/GlewWindows + ) + ADD_DEFINITIONS(-DGLEW_STATIC) + LINK_LIBRARIES( ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY} ) +ELSE(WIN32) + IF(APPLE) + find_library(COCOA NAMES Cocoa) + MESSAGE(${COCOA}) + link_libraries(${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}) + + ELSE(APPLE) + INCLUDE_DIRECTORIES( + ${BULLET_PHYSICS_SOURCE_DIR}/btgui/OpenGLWindow/GlewWindows + ) + ADD_DEFINITIONS("-DGLEW_INIT_OPENGL11_FUNCTIONS=1") + ADD_DEFINITIONS("-DGLEW_STATIC") + ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1") + + LINK_LIBRARIES( pthread dl ) + ENDIF(APPLE) +ENDIF(WIN32) + + +ADD_EXECUTABLE(App_RobotSimulator ${RobotSimulator_SRCS}) SET_TARGET_PROPERTIES(App_RobotSimulator PROPERTIES VERSION ${BULLET_VERSION}) SET_TARGET_PROPERTIES(App_RobotSimulator PROPERTIES DEBUG_POSTFIX "_d") @@ -153,7 +179,6 @@ ENDIF(WIN32) - TARGET_LINK_LIBRARIES(App_RobotSimulator BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common) From f159998220cdb521cc53abbf36585e10a2d5c039 Mon Sep 17 00:00:00 2001 From: Erik Ogenvik Date: Tue, 14 Mar 2017 22:07:06 +0100 Subject: [PATCH 43/66] Added test for btKinematicCharacterController. For now just a simple instantiation unit test. --- test/BulletDynamics/CMakeLists.txt | 24 +++++++++++++++++ .../test_btKinematicCharacterController.cpp | 27 +++++++++++++++++++ test/CMakeLists.txt | 2 +- 3 files changed, 52 insertions(+), 1 deletion(-) create mode 100644 test/BulletDynamics/CMakeLists.txt create mode 100644 test/BulletDynamics/test_btKinematicCharacterController.cpp diff --git a/test/BulletDynamics/CMakeLists.txt b/test/BulletDynamics/CMakeLists.txt new file mode 100644 index 000000000..ceeb2b4f4 --- /dev/null +++ b/test/BulletDynamics/CMakeLists.txt @@ -0,0 +1,24 @@ +SUBDIRS(pendulum ) + +INCLUDE_DIRECTORIES( + "${PROJECT_SOURCE_DIR}/src" + "${PROJECT_SOURCE_DIR}/test/gtest-1.7.0/include") + +ADD_DEFINITIONS(-DUSE_GTEST) +ADD_DEFINITIONS(-D_VARIADIC_MAX=10) + +LINK_LIBRARIES(BulletDynamics BulletCollision LinearMath gtest) + +IF (NOT WIN32) + LINK_LIBRARIES(pthread) +ENDIF() + +ADD_EXECUTABLE(Test_btKinematicCharacterController test_btKinematicCharacterController.cpp) + +ADD_TEST(Test_btKinematicCharacterController_PASS Test_btKinematicCharacterController) + +IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES) + SET_TARGET_PROPERTIES(Test_btKinematicCharacterController PROPERTIES DEBUG_POSTFIX "_Debug") + SET_TARGET_PROPERTIES(Test_btKinematicCharacterController PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel") + SET_TARGET_PROPERTIES(Test_btKinematicCharacterController PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo") +ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES) diff --git a/test/BulletDynamics/test_btKinematicCharacterController.cpp b/test/BulletDynamics/test_btKinematicCharacterController.cpp new file mode 100644 index 000000000..4b0a567c0 --- /dev/null +++ b/test/BulletDynamics/test_btKinematicCharacterController.cpp @@ -0,0 +1,27 @@ + + +#include +#include +#include +#include + + +GTEST_TEST(BulletDynamics, KinematicCharacterController) { + + btPairCachingGhostObject* ghostObject = new btPairCachingGhostObject(); + btBoxShape* convexShape = new btBoxShape(btVector3(1, 1, 1)); + + //For now only a simple test that it initializes correctly. + btKinematicCharacterController* tested = new btKinematicCharacterController(ghostObject, convexShape, 1); + EXPECT_TRUE(tested); + + EXPECT_FLOAT_EQ(-9.8 * 3.0, tested->getGravity().x()); + EXPECT_FLOAT_EQ(0, tested->getGravity().y()); + EXPECT_FLOAT_EQ(0, tested->getGravity().z()); +} + + +int main(int argc, char **argv) { + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} \ No newline at end of file diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 713e4937e..ff1da9bff 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -3,5 +3,5 @@ IF(BUILD_BULLET3) SUBDIRS( InverseDynamics SharedMemory ) ENDIF(BUILD_BULLET3) -SUBDIRS( gtest-1.7.0 collision RobotLogging BulletDynamics/pendulum ) +SUBDIRS( gtest-1.7.0 collision RobotLogging BulletDynamics ) From 4ee09c264ce8941ffd7b9ab20b8de1efa6c78abc Mon Sep 17 00:00:00 2001 From: Erik Ogenvik Date: Tue, 14 Mar 2017 22:07:56 +0100 Subject: [PATCH 44/66] Avoid using unitialized values. m_gravity was used before it was initialized. Simplest way to avoid it is to call any method first after all values are initialized. --- .../Character/btKinematicCharacterController.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/BulletDynamics/Character/btKinematicCharacterController.cpp b/src/BulletDynamics/Character/btKinematicCharacterController.cpp index 06429f349..cb1aa71a1 100644 --- a/src/BulletDynamics/Character/btKinematicCharacterController.cpp +++ b/src/BulletDynamics/Character/btKinematicCharacterController.cpp @@ -137,8 +137,6 @@ btKinematicCharacterController::btKinematicCharacterController (btPairCachingGho m_ghostObject = ghostObject; m_up.setValue(0.0f, 0.0f, 1.0f); m_jumpAxis.setValue(0.0f, 0.0f, 1.0f); - setUp(up); - setStepHeight(stepHeight); m_addedMargin = 0.02; m_walkDirection.setValue(0.0,0.0,0.0); m_AngVel.setValue(0.0, 0.0, 0.0); @@ -156,13 +154,16 @@ btKinematicCharacterController::btKinematicCharacterController (btPairCachingGho m_wasOnGround = false; m_wasJumping = false; m_interpolateUp = true; - setMaxSlope(btRadians(45.0)); m_currentStepOffset = 0.0; m_maxPenetrationDepth = 0.2; full_drop = false; bounce_fix = false; m_linearDamping = btScalar(0.0); m_angularDamping = btScalar(0.0); + + setUp(up); + setStepHeight(stepHeight); + setMaxSlope(btRadians(45.0)); } btKinematicCharacterController::~btKinematicCharacterController () From bb9601bf643184a86d23547525be36adf9681696 Mon Sep 17 00:00:00 2001 From: Julian Date: Tue, 14 Mar 2017 14:43:08 -0700 Subject: [PATCH 45/66] fixed numpy dependency and gripper --- examples/pybullet/vr_kuka_control.py | 45 +++++++++++----------------- 1 file changed, 18 insertions(+), 27 deletions(-) diff --git a/examples/pybullet/vr_kuka_control.py b/examples/pybullet/vr_kuka_control.py index dccbf5453..08f71d336 100644 --- a/examples/pybullet/vr_kuka_control.py +++ b/examples/pybullet/vr_kuka_control.py @@ -2,7 +2,7 @@ # Require p.setInternalSimFlags(0) in kuka_setup import pybullet as p import math -import numpy as np +# import numpy as np p.connect(p.SHARED_MEMORY) @@ -20,6 +20,8 @@ REST_POSE = [0, 0, 0, math.pi / 2, 0, -math.pi * 0.66, 0] JOINT_DAMP = [.1, .1, .1, .1, .1, .1, .1] REST_JOINT_POS = [-0., -0., 0., 1.570793, 0., -1.036725, 0.000001] MAX_FORCE = 500 +KUKA_GRIPPER_REST_POS = [0., -0.011130, -0.206421, 0.205143, -0.009999, 0., -0.010055, 0.] +KUKA_GRIPPER_CLOZ_POS = [0.0, -0.047564246423083795, 0.6855956234759611, -0.7479294372303137, 0.05054599996976922, 0.0, 0.049838105678835724, 0.0] def euc_dist(posA, posB): dist = 0. @@ -37,40 +39,23 @@ while True: for e in (events): # Only use one controller + ########################################### + # This is important: make sure there's only one VR Controller! if e[0] == controllers[0]: break sq_len = euc_dist(p.getLinkState(kuka, 6)[0], e[POSITION]) # A simplistic version of gripper control + #@TO-DO: Add slider for the gripper if e[BUTTONS][33] & p.VR_BUTTON_WAS_TRIGGERED: # avg = 0. for i in range(p.getNumJoints(kuka_gripper)): - p.setJointMotorControl2(kuka_gripper, i, p.VELOCITY_CONTROL, targetVelocity=5, force=50) - # posTarget = 0.1 + (1 - min(0.75, e[3])) * 1.5 * math.pi * 0.29; - # maxPosTarget = 0.55 - # correction = 0. - # jointPosition = p.getJointState(kuka_gripper, i)[0] - # if avg: - # correction = jointPosition - avg - # if jointPosition < 0: - # p.resetJointState(kuka_gripper, i, 0) - # if jointPosition > maxPosTarget: - # p.resetJointState(kuka_gripper, i, maxPosTarget) - # if avg: + p.setJointMotorControl2(kuka_gripper, i, p.POSITION_CONTROL, targetPosition=KUKA_GRIPPER_CLOZ_POS[i], force=50) - # p.setJointMotorControl2(kuka_gripper, i, p.POSITION_CONTROL, - # targetPosition=avg, targetVelocity=0., - # positionGain=1, velocityGain=0.5, force=50) - # else: - # p.setJointMotorControl2(kuka_gripper, i, p.POSITION_CONTROL, - # targetPosition=posTarget, targetVelocity=0., - # positionGain=1, velocityGain=0.5, force=50) - # avg = p.getJointState(kuka_gripper, i)[0] - if e[BUTTONS][33] & p.VR_BUTTON_WAS_RELEASED: for i in range(p.getNumJoints(kuka_gripper)): - p.setJointMotorControl2(kuka_gripper, i, p.VELOCITY_CONTROL, targetVelocity=-5, force=50) + p.setJointMotorControl2(kuka_gripper, i, p.POSITION_CONTROL, targetPosition=KUKA_GRIPPER_REST_POS[i], force=50) if sq_len < THRESHOLD * THRESHOLD: eef_pos = e[POSITION] @@ -90,12 +75,18 @@ while True: _, _, z = p.getEulerFromQuaternion(targetOrn) # End effector needs protection, done by using triangular tricks - p.setJointMotorControl2(kuka, 6, p.POSITION_CONTROL, - targetPosition=np.arcsin(np.sin(z)), targetVelocity=0, positionGain=0.5, - velocityGain=1.0, force=MAX_FORCE) + + if LOWER_LIMITS[6] < z < UPPER_LIMITS[6]: + p.setJointMotorControl2(kuka, 6, p.POSITION_CONTROL, + targetPosition=z, targetVelocity=0, positionGain=0.03, velocityGain=1.0, force=MAX_FORCE) + + else: + p.setJointMotorControl2(kuka, 6, p.POSITION_CONTROL, + targetPosition=joint_pos[6], targetVelocity=0, positionGain=0.05, + velocityGain=1.0, force=MAX_FORCE) p.setJointMotorControl2(kuka, 5, p.POSITION_CONTROL, - targetPosition=-math.pi, targetVelocity=0, + targetPosition=-1.57, targetVelocity=0, positionGain=0.03, velocityGain=1.0, force=MAX_FORCE) else: From f90986d6f01a32db047dd438b454d08962abedca Mon Sep 17 00:00:00 2001 From: Jie Tan Date: Tue, 14 Mar 2017 15:04:43 -0700 Subject: [PATCH 46/66] add cartpole urdf --- data/cartpole.urdf | 74 ++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 74 insertions(+) create mode 100644 data/cartpole.urdf diff --git a/data/cartpole.urdf b/data/cartpole.urdf new file mode 100644 index 000000000..c22ca920c --- /dev/null +++ b/data/cartpole.urdf @@ -0,0 +1,74 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 6e2850e08a59aab8846e54c82a2b3e5edc9e5bfa Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 14 Mar 2017 17:03:11 -0700 Subject: [PATCH 47/66] fix names (case) for Linux for MPL/hand --- data/MPL/MPL.xml | 48 +++++++++++++++++++-------------------- examples/pybullet/hand.py | 4 ++-- 2 files changed, 26 insertions(+), 26 deletions(-) diff --git a/data/MPL/MPL.xml b/data/MPL/MPL.xml index 2b8408323..7ed5170ff 100644 --- a/data/MPL/MPL.xml +++ b/data/MPL/MPL.xml @@ -49,30 +49,30 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/hand.py b/examples/pybullet/hand.py index d0428c555..cb4b45f87 100644 --- a/examples/pybullet/hand.py +++ b/examples/pybullet/hand.py @@ -16,7 +16,7 @@ if (c<0): p.connect(p.GUI) #load the MuJoCo MJCF hand -objects = p.loadMJCF("MPL/mpl.xml") +objects = p.loadMJCF("MPL/MPL.xml") hand=objects[0] #clamp in range 400-600 @@ -75,4 +75,4 @@ if (ser.isOpen()): #print(middle) #print(pink) #print(index) - #print(thumb) \ No newline at end of file + #print(thumb) From 4db6fa9e29aa463dd8830f2fafb57d89f689d517 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 15 Mar 2017 15:38:50 -0700 Subject: [PATCH 48/66] update minitaur.py to use minitaur.urdf (instead of quadruped.urdf), also sort the legs in the same order as real hardware added test urdf files for minitaur with all fixed joints, or fixed knees. added some stiffness/damping to minitaur legs (testing) tiny_obj_loader, don't crash on invalid texture coordinates btMultiBodyConstraintSolver: sweep back and forward to reduce asymmetry --- data/quadruped/minitaur.urdf | 34 +- data/quadruped/minitaur_fixed_all.urdf | 913 +++++++++++++++++ data/quadruped/minitaur_fixed_knees.urdf | 929 ++++++++++++++++++ .../b3RobotSimulatorClientAPI.h | 2 +- .../Wavefront/tiny_obj_loader.cpp | 14 +- examples/pybullet/minitaur.py | 89 +- examples/pybullet/minitaur_evaluate.py | 2 +- examples/pybullet/minitaur_test.py | 4 + examples/pybullet/mylittleminitaur.py | 21 + examples/pybullet/quadruped.py | 141 +-- .../btMultiBodyConstraintSolver.cpp | 12 +- 11 files changed, 2043 insertions(+), 118 deletions(-) create mode 100644 data/quadruped/minitaur_fixed_all.urdf create mode 100644 data/quadruped/minitaur_fixed_knees.urdf create mode 100644 examples/pybullet/mylittleminitaur.py diff --git a/data/quadruped/minitaur.urdf b/data/quadruped/minitaur.urdf index c483bd4b4..663ff2a84 100644 --- a/data/quadruped/minitaur.urdf +++ b/data/quadruped/minitaur.urdf @@ -427,7 +427,9 @@ - + + + @@ -493,7 +495,9 @@ - + + + @@ -557,7 +561,9 @@ - + + + @@ -622,7 +628,9 @@ - + + + @@ -684,7 +692,9 @@ - + + + @@ -750,9 +760,11 @@ - + + + - + @@ -814,7 +826,9 @@ - + + + @@ -877,7 +891,9 @@ - + + + diff --git a/data/quadruped/minitaur_fixed_all.urdf b/data/quadruped/minitaur_fixed_all.urdf new file mode 100644 index 000000000..68815043a --- /dev/null +++ b/data/quadruped/minitaur_fixed_all.urdf @@ -0,0 +1,913 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/quadruped/minitaur_fixed_knees.urdf b/data/quadruped/minitaur_fixed_knees.urdf new file mode 100644 index 000000000..2c5903e1f --- /dev/null +++ b/data/quadruped/minitaur_fixed_knees.urdf @@ -0,0 +1,929 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h index f1ca5fe98..e6f658cc5 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h @@ -146,7 +146,7 @@ public: b3Vector3 getEulerFromQuaternion(const b3Quaternion& quat); int loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args=b3RobotSimulatorLoadUrdfFileArgs()); - bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results, const struct b3RobotSimulatorLoadSdfFileArgs& args=b3RobotSimulatorLoadSdfFileArgs()); + bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results=b3RobotSimulatorLoadFileResults(), const struct b3RobotSimulatorLoadSdfFileArgs& args=b3RobotSimulatorLoadSdfFileArgs()); bool loadMJCF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results); bool loadBullet(const std::string& fileName, b3RobotSimulatorLoadFileResults& results); diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp index f69fa3dda..f56de333a 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp @@ -218,8 +218,18 @@ updateVertex( } if (i.vt_idx >= 0) { - texcoords.push_back(in_texcoords[2*i.vt_idx+0]); - texcoords.push_back(in_texcoords[2*i.vt_idx+1]); + int numTexCoords = in_texcoords.size(); + int index0 = 2*i.vt_idx+0; + int index1 = 2*i.vt_idx+1; + + if (index0>=0 && (index0)=0 && (index1)m_multiBodyFrictionContactConstraints.size();j++) + for (int j1=0;j1m_multiBodyFrictionContactConstraints.size();j1++) { if (iteration < infoGlobal.m_numIterations) { - btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[j]; + int index = iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1; + + btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[index]; btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse; //adjust friction limits here if (totalImpulse>btScalar(0)) From b7b46b12d33a7d47ceaf8723a2d77cd03cc12dc3 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 15 Mar 2017 17:09:17 -0700 Subject: [PATCH 49/66] update RobotSimulator/MinitaurSetup to use data/quadruped/minitaur.urdf add b3RobotSimulatorClientAPI::getBaseVelocity and resetBaseVelocity add b3Quaternion::getEulerZYX --- examples/RobotSimulator/MinitaurSetup.cpp | 98 ++-- .../RobotSimulator/RobotSimulatorMain.cpp | 36 +- .../b3RobotSimulatorClientAPI.cpp | 522 +++++++++--------- .../b3RobotSimulatorClientAPI.h | 118 ++-- src/Bullet3Common/b3Quaternion.h | 34 +- 5 files changed, 427 insertions(+), 381 deletions(-) diff --git a/examples/RobotSimulator/MinitaurSetup.cpp b/examples/RobotSimulator/MinitaurSetup.cpp index 0d1238c87..e867d0583 100644 --- a/examples/RobotSimulator/MinitaurSetup.cpp +++ b/examples/RobotSimulator/MinitaurSetup.cpp @@ -49,57 +49,69 @@ void MinitaurSetup::resetPose(class b3RobotSimulatorClientAPI* sim) sim->setJointMotorControl(m_data->m_quadrupedUniqueId,i,controlArgs); } - //right front leg - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_rightR_joint"],1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightR_link"],-2.2); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_rightL_joint"],-1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightL_link"],2.2); + b3Scalar startAngle = B3_HALF_PI; + b3Scalar upperLegLength = 11.5; + b3Scalar lowerLegLength = 20; + b3Scalar kneeAngle = B3_PI+b3Acos(upperLegLength/lowerLegLength); + + b3Scalar motorDirs[8] = {-1,-1,-1,-1,1,1,1,1}; b3JointInfo jointInfo; jointInfo.m_jointType = ePoint2PointType; - jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.01; jointInfo.m_parentFrame[2] = 0.2; - jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = -0.015; jointInfo.m_childFrame[2] = 0.2; - sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightR_link"], - m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightL_link"],&jointInfo); - setDesiredMotorAngle(sim,"motor_front_rightR_joint",1.57); - setDesiredMotorAngle(sim,"motor_front_rightL_joint",-1.57); - - //left front leg - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_leftR_joint"],1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftR_link"],-2.2); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_leftL_joint"],-1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftL_link"],2.2); - jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = -0.01; jointInfo.m_parentFrame[2] = 0.2; - jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.015; jointInfo.m_childFrame[2] = 0.2; + //left front leg + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_leftL_joint"],motorDirs[0] * startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftL_link"],motorDirs[0]*kneeAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_leftR_joint"],motorDirs[1] * startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftR_link"],motorDirs[1]*kneeAngle); + + jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; + jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftR_link"], m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftL_link"],&jointInfo); - setDesiredMotorAngle(sim,"motor_front_leftR_joint", 1.57); - setDesiredMotorAngle(sim,"motor_front_leftL_joint", -1.57); - - //right back leg - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_rightR_joint"],1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightR_link"],-2.2); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_rightL_joint"],-1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightL_link"],2.2); - jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.01; jointInfo.m_parentFrame[2] = 0.2; - jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = -0.015; jointInfo.m_childFrame[2] = 0.2; - sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightR_link"], - m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightL_link"],&jointInfo); - setDesiredMotorAngle(sim,"motor_back_rightR_joint", 1.57); - setDesiredMotorAngle(sim,"motor_back_rightL_joint", -1.57); - + setDesiredMotorAngle(sim,"motor_front_leftL_joint", motorDirs[0] * startAngle); + setDesiredMotorAngle(sim,"motor_front_leftR_joint", motorDirs[1] * startAngle); + //left back leg - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_leftR_joint"],1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftR_link"],-2.2); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_leftL_joint"],-1.57); - sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftL_link"],2.2); - jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = -0.01; jointInfo.m_parentFrame[2] = 0.2; - jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.015; jointInfo.m_childFrame[2] = 0.2; + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_leftL_joint"],motorDirs[2] * startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftL_link"],motorDirs[2] * kneeAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_leftR_joint"],motorDirs[3] * startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftR_link"],motorDirs[3] * kneeAngle); + jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; + jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftR_link"], m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftL_link"],&jointInfo); - setDesiredMotorAngle(sim,"motor_back_leftR_joint", 1.57); - setDesiredMotorAngle(sim,"motor_back_leftL_joint", -1.57); + setDesiredMotorAngle(sim,"motor_back_leftL_joint", motorDirs[2] * startAngle); + setDesiredMotorAngle(sim,"motor_back_leftR_joint", motorDirs[3] * startAngle); + //right front leg + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_rightL_joint"],motorDirs[4] * startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightL_link"],motorDirs[4] * kneeAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_rightR_joint"],motorDirs[5]*startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightR_link"],motorDirs[5] * kneeAngle); + + + + jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; + jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; + sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightR_link"], + m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightL_link"],&jointInfo); + setDesiredMotorAngle(sim,"motor_front_rightL_joint",motorDirs[4] * startAngle); + setDesiredMotorAngle(sim,"motor_front_rightR_joint",motorDirs[5] * startAngle); + + + //right back leg + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_rightL_joint"],motorDirs[6] * startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightL_link"],motorDirs[6] * kneeAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_rightR_joint"],motorDirs[7] * startAngle); + sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightR_link"],motorDirs[7] * kneeAngle); + + jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; + jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; + sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightR_link"], + m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightL_link"],&jointInfo); + setDesiredMotorAngle(sim,"motor_back_rightL_joint", motorDirs[6] * startAngle); + setDesiredMotorAngle(sim,"motor_back_rightR_joint", motorDirs[7] * startAngle); + } int MinitaurSetup::setupMinitaur(class b3RobotSimulatorClientAPI* sim, const b3Vector3& startPos, const b3Quaternion& startOrn) @@ -109,7 +121,7 @@ int MinitaurSetup::setupMinitaur(class b3RobotSimulatorClientAPI* sim, const b3V args.m_startPosition = startPos; args.m_startOrientation = startOrn; - m_data->m_quadrupedUniqueId = sim->loadURDF("quadruped/quadruped.urdf",args); + m_data->m_quadrupedUniqueId = sim->loadURDF("quadruped/minitaur.urdf",args); int numJoints = sim->getNumJoints(m_data->m_quadrupedUniqueId); for (int i=0;isyncBodies(); - - sim->setTimeStep(1./240.); + b3Scalar fixedTimeStep = 1./240.; - sim->setGravity(b3MakeVector3(0,0,-10)); + sim->setTimeStep(fixedTimeStep); - int blockId = sim->loadURDF("cube.urdf"); - b3BodyInfo bodyInfo; - sim->getBodyInfo(blockId,&bodyInfo); + b3Quaternion q = sim->getQuaternionFromEuler(b3MakeVector3(0.1,0.2,0.3)); + b3Vector3 rpy; + rpy = sim->getEulerFromQuaternion(q); + + sim->setGravity(b3MakeVector3(0,0,-9.8)); + + //int blockId = sim->loadURDF("cube.urdf"); + //b3BodyInfo bodyInfo; + //sim->getBodyInfo(blockId,&bodyInfo); sim->loadURDF("plane.urdf"); @@ -34,15 +39,15 @@ int main(int argc, char* argv[]) int minitaurUid = minitaur.setupMinitaur(sim, b3MakeVector3(0,0,.3)); - b3RobotSimulatorLoadUrdfFileArgs args; - args.m_startPosition.setValue(2,0,1); - int r2d2 = sim->loadURDF("r2d2.urdf",args); + //b3RobotSimulatorLoadUrdfFileArgs args; + //args.m_startPosition.setValue(2,0,1); + //int r2d2 = sim->loadURDF("r2d2.urdf",args); - b3RobotSimulatorLoadFileResults sdfResults; - if (!sim->loadSDF("two_cubes.sdf",sdfResults)) - { - b3Warning("Can't load SDF!\n"); - } + //b3RobotSimulatorLoadFileResults sdfResults; + //if (!sim->loadSDF("two_cubes.sdf",sdfResults)) + //{ +// b3Warning("Can't load SDF!\n"); + //} b3Clock clock; double startTime = clock.getTimeInSeconds(); @@ -69,7 +74,8 @@ int main(int argc, char* argv[]) printf("keyEvent[%d].m_keyCode = %d, state = %d\n", i,keyEvents.m_keyboardEvents[i].m_keyCode,keyEvents.m_keyboardEvents[i].m_keyState); } } - b3Clock::usleep(1000*1000); + sim->stepSimulation(); + b3Clock::usleep(1000.*1000.*fixedTimeStep); } printf("sim->disconnect\n"); diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 224014b76..4c95006d2 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -1,17 +1,16 @@ #include "b3RobotSimulatorClientAPI.h" - //#include "SharedMemoryCommands.h" #include "SharedMemory/PhysicsClientC_API.h" #ifdef BT_ENABLE_ENET #include "SharedMemory/PhysicsClientUDP_C_API.h" -#endif//PHYSICS_UDP +#endif //PHYSICS_UDP #ifdef BT_ENABLE_CLSOCKET #include "SharedMemory/PhysicsClientTCP_C_API.h" -#endif//PHYSICS_TCP +#endif //PHYSICS_TCP #include "SharedMemory/PhysicsDirectC_API.h" @@ -25,7 +24,7 @@ struct b3RobotSimulatorClientAPI_InternalData b3PhysicsClientHandle m_physicsClientHandle; b3RobotSimulatorClientAPI_InternalData() - :m_physicsClientHandle(0) + : m_physicsClientHandle(0) { } }; @@ -35,17 +34,16 @@ b3RobotSimulatorClientAPI::b3RobotSimulatorClientAPI() m_data = new b3RobotSimulatorClientAPI_InternalData(); } - b3RobotSimulatorClientAPI::~b3RobotSimulatorClientAPI() +b3RobotSimulatorClientAPI::~b3RobotSimulatorClientAPI() { - delete m_data; + delete m_data; } - bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, int portOrKey) { if (m_data->m_physicsClientHandle) { - b3Warning ("Already connected, disconnect first."); + b3Warning("Already connected, disconnect first."); return false; } b3PhysicsClientHandle sm = 0; @@ -54,89 +52,88 @@ bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, i int tcpPort = 6667; int key = SHARED_MEMORY_KEY; bool connected = false; - - switch (mode) + switch (mode) { - case eCONNECT_GUI: + case eCONNECT_GUI: { - int argc = 0; - char* argv[1] = {0}; - #ifdef __APPLE__ - sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); - #else - sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv); - #endif - break; + int argc = 0; + char* argv[1] = {0}; +#ifdef __APPLE__ + sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); +#else + sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv); +#endif + break; } - case eCONNECT_DIRECT: { - sm = b3ConnectPhysicsDirect(); - break; + case eCONNECT_DIRECT: + { + sm = b3ConnectPhysicsDirect(); + break; } - case eCONNECT_SHARED_MEMORY: { - if (portOrKey>=0) + case eCONNECT_SHARED_MEMORY: + { + if (portOrKey >= 0) { key = portOrKey; } - sm = b3ConnectSharedMemory(key); - break; + sm = b3ConnectSharedMemory(key); + break; } - case eCONNECT_UDP: - { - if (portOrKey>=0) + case eCONNECT_UDP: + { + if (portOrKey >= 0) { udpPort = portOrKey; } - #ifdef BT_ENABLE_ENET +#ifdef BT_ENABLE_ENET sm = b3ConnectPhysicsUDP(hostName.c_str(), udpPort); - #else - b3Warning("UDP is not enabled in this build"); - #endif //BT_ENABLE_ENET +#else + b3Warning("UDP is not enabled in this build"); +#endif //BT_ENABLE_ENET break; - } - case eCONNECT_TCP: + } + case eCONNECT_TCP: { - if (portOrKey>=0) + if (portOrKey >= 0) { tcpPort = portOrKey; } - #ifdef BT_ENABLE_CLSOCKET - +#ifdef BT_ENABLE_CLSOCKET + sm = b3ConnectPhysicsTCP(hostName.c_str(), tcpPort); - #else +#else b3Warning("TCP is not enabled in this pybullet build"); - #endif //BT_ENABLE_CLSOCKET +#endif //BT_ENABLE_CLSOCKET break; } - - - default: { - b3Warning("connectPhysicsServer unexpected argument"); + default: + { + b3Warning("connectPhysicsServer unexpected argument"); } }; - if (sm) - { - m_data->m_physicsClientHandle = sm; - if (!b3CanSubmitCommand(m_data->m_physicsClientHandle)) - { - disconnect(); - return false; - } - return true; - } - return false; + if (sm) + { + m_data->m_physicsClientHandle = sm; + if (!b3CanSubmitCommand(m_data->m_physicsClientHandle)) + { + disconnect(); + return false; + } + return true; + } + return false; } bool b3RobotSimulatorClientAPI::isConnected() const { - return (m_data->m_physicsClientHandle!=0); + return (m_data->m_physicsClientHandle != 0); } - void b3RobotSimulatorClientAPI::disconnect() { if (!isConnected()) @@ -157,15 +154,13 @@ void b3RobotSimulatorClientAPI::syncBodies() return; } - - b3SharedMemoryCommandHandle command; + b3SharedMemoryCommandHandle command; b3SharedMemoryStatusHandle statusHandle; int statusType; command = b3InitSyncBodyInfoCommand(m_data->m_physicsClientHandle); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); statusType = b3GetStatusType(statusHandle); - } void b3RobotSimulatorClientAPI::resetSimulation() @@ -175,9 +170,9 @@ void b3RobotSimulatorClientAPI::resetSimulation() b3Warning("Not connected"); return; } - b3SharedMemoryStatusHandle statusHandle; - statusHandle = b3SubmitClientCommandAndWaitStatus( - m_data->m_physicsClientHandle, b3InitResetSimulationCommand(m_data->m_physicsClientHandle)); + b3SharedMemoryStatusHandle statusHandle; + statusHandle = b3SubmitClientCommandAndWaitStatus( + m_data->m_physicsClientHandle, b3InitResetSimulationCommand(m_data->m_physicsClientHandle)); } bool b3RobotSimulatorClientAPI::canSubmitCommand() const @@ -186,7 +181,7 @@ bool b3RobotSimulatorClientAPI::canSubmitCommand() const { return false; } - return (b3CanSubmitCommand(m_data->m_physicsClientHandle)); + return (b3CanSubmitCommand(m_data->m_physicsClientHandle) != 0); } void b3RobotSimulatorClientAPI::stepSimulation() @@ -200,11 +195,11 @@ void b3RobotSimulatorClientAPI::stepSimulation() b3SharedMemoryStatusHandle statusHandle; int statusType; if (b3CanSubmitCommand(m_data->m_physicsClientHandle)) - { - statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitStepSimulationCommand(m_data->m_physicsClientHandle)); - statusType = b3GetStatusType(statusHandle); - b3Assert(statusType==CMD_STEP_FORWARD_SIMULATION_COMPLETED); - } + { + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitStepSimulationCommand(m_data->m_physicsClientHandle)); + statusType = b3GetStatusType(statusHandle); + b3Assert(statusType == CMD_STEP_FORWARD_SIMULATION_COMPLETED); + } } void b3RobotSimulatorClientAPI::setGravity(const b3Vector3& gravityAcceleration) @@ -215,57 +210,26 @@ void b3RobotSimulatorClientAPI::setGravity(const b3Vector3& gravityAcceleration) return; } - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle); - b3SharedMemoryStatusHandle statusHandle; - b3PhysicsParamSetGravity(command, gravityAcceleration[0],gravityAcceleration[1],gravityAcceleration[2]); + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle); + b3SharedMemoryStatusHandle statusHandle; + b3PhysicsParamSetGravity(command, gravityAcceleration[0], gravityAcceleration[1], gravityAcceleration[2]); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - b3Assert(b3GetStatusType(statusHandle)==CMD_CLIENT_COMMAND_COMPLETED); + b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); } b3Quaternion b3RobotSimulatorClientAPI::getQuaternionFromEuler(const b3Vector3& rollPitchYaw) { - double phi, the, psi; - phi = rollPitchYaw[0] / 2.0; - the = rollPitchYaw[1] / 2.0; - psi = rollPitchYaw[2] / 2.0; - double quat[4] = { - sin(phi) * cos(the) * cos(psi) - cos(phi) * sin(the) * sin(psi), - cos(phi) * sin(the) * cos(psi) + sin(phi) * cos(the) * sin(psi), - cos(phi) * cos(the) * sin(psi) - sin(phi) * sin(the) * cos(psi), - cos(phi) * cos(the) * cos(psi) + sin(phi) * sin(the) * sin(psi)}; - - // normalize the quaternion - double len = sqrt(quat[0] * quat[0] + quat[1] * quat[1] + - quat[2] * quat[2] + quat[3] * quat[3]); - quat[0] /= len; - quat[1] /= len; - quat[2] /= len; - quat[3] /= len; - b3Quaternion q(quat[0],quat[1],quat[2],quat[3]); + b3Quaternion q; + q.setEulerZYX(rollPitchYaw[2],rollPitchYaw[1],rollPitchYaw[0]); return q; } b3Vector3 b3RobotSimulatorClientAPI::getEulerFromQuaternion(const b3Quaternion& quat) { - double squ; - double sqx; - double sqy; - double sqz; - double sarg; - - b3Vector3 rpy; - sqx = quat[0] * quat[0]; - sqy = quat[1] * quat[1]; - sqz = quat[2] * quat[2]; - squ = quat[3] * quat[3]; - rpy[0] = atan2(2 * (quat[1] * quat[2] + quat[3] * quat[0]), - squ - sqx - sqy + sqz); - sarg = -2 * (quat[0] * quat[2] - quat[3] * quat[1]); - rpy[1] = sarg <= -1.0 ? -0.5 * 3.141592538 - : (sarg >= 1.0 ? 0.5 * 3.141592538 : asin(sarg)); - rpy[2] = atan2(2 * (quat[0] * quat[1] + quat[3] * quat[2]), - squ + sqx - sqy - sqz); - return rpy; + b3Scalar roll,pitch,yaw; + quat.getEulerZYX(yaw,pitch,roll); + b3Vector3 rpy2 = b3MakeVector3(roll,pitch,yaw); + return rpy2; } int b3RobotSimulatorClientAPI::loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args) @@ -278,31 +242,26 @@ int b3RobotSimulatorClientAPI::loadURDF(const std::string& fileName, const struc return robotUniqueId; } - - b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(m_data->m_physicsClientHandle, fileName.c_str()); - + //setting the initial position, orientation and other arguments are optional - + b3LoadUrdfCommandSetStartPosition(command, args.m_startPosition[0], - args.m_startPosition[1], - args.m_startPosition[2]); - b3LoadUrdfCommandSetStartOrientation(command,args.m_startOrientation[0] - ,args.m_startOrientation[1] - ,args.m_startOrientation[2] - ,args.m_startOrientation[3]); + args.m_startPosition[1], + args.m_startPosition[2]); + b3LoadUrdfCommandSetStartOrientation(command, args.m_startOrientation[0], args.m_startOrientation[1], args.m_startOrientation[2], args.m_startOrientation[3]); if (args.m_forceOverrideFixedBase) { - b3LoadUrdfCommandSetUseFixedBase(command,true); + b3LoadUrdfCommandSetUseFixedBase(command, true); } b3LoadUrdfCommandSetUseMultiBody(command, args.m_useMultiBody); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); statusType = b3GetStatusType(statusHandle); - b3Assert(statusType==CMD_URDF_LOADING_COMPLETED); - if (statusType==CMD_URDF_LOADING_COMPLETED) + b3Assert(statusType == CMD_URDF_LOADING_COMPLETED); + if (statusType == CMD_URDF_LOADING_COMPLETED) { robotUniqueId = b3GetStatusBodyIndex(statusHandle); } @@ -329,12 +288,12 @@ bool b3RobotSimulatorClientAPI::loadMJCF(const std::string& fileName, b3RobotSim b3Warning("Couldn't load .mjcf file."); return false; } - int numBodies = b3GetStatusBodyIndices(statusHandle, 0,0); + int numBodies = b3GetStatusBodyIndices(statusHandle, 0, 0); if (numBodies) { results.m_uniqueObjectIds.resize(numBodies); int numBodies; - numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0],results.m_uniqueObjectIds.size()); + numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0], results.m_uniqueObjectIds.size()); } return true; @@ -359,12 +318,12 @@ bool b3RobotSimulatorClientAPI::loadBullet(const std::string& fileName, b3RobotS { return false; } - int numBodies = b3GetStatusBodyIndices(statusHandle, 0,0); + int numBodies = b3GetStatusBodyIndices(statusHandle, 0, 0); if (numBodies) { results.m_uniqueObjectIds.resize(numBodies); int numBodies; - numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0],results.m_uniqueObjectIds.size()); + numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0], results.m_uniqueObjectIds.size()); } return true; @@ -383,19 +342,18 @@ bool b3RobotSimulatorClientAPI::loadSDF(const std::string& fileName, b3RobotSimu b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3LoadSdfCommandInit(m_data->m_physicsClientHandle, fileName.c_str()); - b3LoadSdfCommandSetUseMultiBody(command, args.m_useMultiBody); + b3LoadSdfCommandSetUseMultiBody(command, args.m_useMultiBody); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); statusType = b3GetStatusType(statusHandle); b3Assert(statusType == CMD_SDF_LOADING_COMPLETED); if (statusType == CMD_SDF_LOADING_COMPLETED) { - int numBodies = b3GetStatusBodyIndices(statusHandle, 0,0); + int numBodies = b3GetStatusBodyIndices(statusHandle, 0, 0); if (numBodies) { results.m_uniqueObjectIds.resize(numBodies); int numBodies; - numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0],results.m_uniqueObjectIds.size()); - + numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0], results.m_uniqueObjectIds.size()); } statusOk = true; } @@ -411,7 +369,7 @@ bool b3RobotSimulatorClientAPI::getBodyInfo(int bodyUniqueId, struct b3BodyInfo* return false; } - int result = b3GetBodyInfo(m_data->m_physicsClientHandle, bodyUniqueId, bodyInfo); + int result = b3GetBodyInfo(m_data->m_physicsClientHandle, bodyUniqueId, bodyInfo); return (result != 0); } @@ -431,7 +389,8 @@ bool b3RobotSimulatorClientAPI::getBasePositionAndOrientation(int bodyUniqueId, const int status_type = b3GetStatusType(status_handle); const double* actualStateQ; - if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) { + if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { return false; } @@ -466,14 +425,72 @@ bool b3RobotSimulatorClientAPI::resetBasePositionAndOrientation(int bodyUniqueId b3CreatePoseCommandSetBasePosition(commandHandle, basePosition[0], basePosition[1], basePosition[2]); b3CreatePoseCommandSetBaseOrientation(commandHandle, baseOrientation[0], baseOrientation[1], - baseOrientation[2], baseOrientation[3]); + baseOrientation[2], baseOrientation[3]); b3SharedMemoryStatusHandle statusHandle; statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); - + return true; } +bool b3RobotSimulatorClientAPI::getBaseVelocity(int bodyUniqueId, b3Vector3& baseLinearVelocity, b3Vector3& baseAngularVelocity) const +{ + if (!isConnected()) + { + b3Warning("Not connected"); + return false; + } + + b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle, bodyUniqueId); + b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + + const int status_type = b3GetStatusType(statusHandle); + const double* actualStateQdot; + + if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { + return false; + } + + b3GetStatusActualState(statusHandle, 0 /* body_unique_id */, + 0 /* num_degree_of_freedom_q */, 0 /* num_degree_of_freedom_u */, + 0 /*root_local_inertial_frame*/, 0, + &actualStateQdot, 0 /* joint_reaction_forces */); + + baseLinearVelocity[0] = actualStateQdot[0]; + baseLinearVelocity[1] = actualStateQdot[1]; + baseLinearVelocity[2] = actualStateQdot[2]; + + baseAngularVelocity[0] = actualStateQdot[3]; + baseAngularVelocity[1] = actualStateQdot[4]; + baseAngularVelocity[2] = actualStateQdot[5]; + return true; +} + +bool b3RobotSimulatorClientAPI::resetBaseVelocity(int bodyUniqueId, const b3Vector3& linearVelocity, const b3Vector3& angularVelocity) const +{ + if (!isConnected()) + { + b3Warning("Not connected"); + return false; + } + + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + + commandHandle = b3CreatePoseCommandInit(m_data->m_physicsClientHandle, bodyUniqueId); + + b3Vector3DoubleData linVelDouble; + linearVelocity.serializeDouble(linVelDouble); + b3CreatePoseCommandSetBaseLinearVelocity(commandHandle, linVelDouble.m_floats); + + b3Vector3DoubleData angVelDouble; + angularVelocity.serializeDouble(angVelDouble); + b3CreatePoseCommandSetBaseAngularVelocity(commandHandle, angVelDouble.m_floats); + + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); + return true; +} void b3RobotSimulatorClientAPI::setRealTimeSimulation(bool enableRealTimeSimulation) { @@ -500,10 +517,9 @@ int b3RobotSimulatorClientAPI::getNumJoints(int bodyUniqueId) const b3Warning("Not connected"); return false; } - return b3GetNumJoints(m_data->m_physicsClientHandle,bodyUniqueId); + return b3GetNumJoints(m_data->m_physicsClientHandle, bodyUniqueId); } - bool b3RobotSimulatorClientAPI::getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo* jointInfo) { if (!isConnected()) @@ -511,7 +527,7 @@ bool b3RobotSimulatorClientAPI::getJointInfo(int bodyUniqueId, int jointIndex, b b3Warning("Not connected"); return false; } - return (b3GetJointInfo(m_data->m_physicsClientHandle,bodyUniqueId, jointIndex,jointInfo)!=0); + return (b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, jointInfo) != 0); } void b3RobotSimulatorClientAPI::createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo) @@ -521,55 +537,55 @@ void b3RobotSimulatorClientAPI::createConstraint(int parentBodyIndex, int parent b3Warning("Not connected"); return; } - b3SharedMemoryStatusHandle statusHandle; - b3Assert(b3CanSubmitCommand(m_data->m_physicsClientHandle)); - if (b3CanSubmitCommand(m_data->m_physicsClientHandle)) - { - statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitCreateUserConstraintCommand(m_data->m_physicsClientHandle, parentBodyIndex, parentJointIndex, childBodyIndex, childJointIndex, jointInfo)); - } + b3SharedMemoryStatusHandle statusHandle; + b3Assert(b3CanSubmitCommand(m_data->m_physicsClientHandle)); + if (b3CanSubmitCommand(m_data->m_physicsClientHandle)) + { + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitCreateUserConstraintCommand(m_data->m_physicsClientHandle, parentBodyIndex, parentJointIndex, childBodyIndex, childJointIndex, jointInfo)); + } } -bool b3RobotSimulatorClientAPI::getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState *state) +bool b3RobotSimulatorClientAPI::getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState* state) { if (!isConnected()) { b3Warning("Not connected"); return false; } - b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle,bodyUniqueId); - b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - int statusType = b3GetStatusType(statusHandle); - if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) + b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle, bodyUniqueId); + b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + int statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) { - if (b3GetJointState(m_data->m_physicsClientHandle, statusHandle, jointIndex, state)) - { - return true; - } + if (b3GetJointState(m_data->m_physicsClientHandle, statusHandle, jointIndex, state)) + { + return true; + } } - return false; + return false; } bool b3RobotSimulatorClientAPI::resetJointState(int bodyUniqueId, int jointIndex, double targetValue) { - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - int numJoints; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int numJoints; - numJoints = b3GetNumJoints(m_data->m_physicsClientHandle, bodyUniqueId); - if ((jointIndex >= numJoints) || (jointIndex < 0)) { - return false; - } + numJoints = b3GetNumJoints(m_data->m_physicsClientHandle, bodyUniqueId); + if ((jointIndex >= numJoints) || (jointIndex < 0)) + { + return false; + } - commandHandle = b3CreatePoseCommandInit(m_data->m_physicsClientHandle, bodyUniqueId); + commandHandle = b3CreatePoseCommandInit(m_data->m_physicsClientHandle, bodyUniqueId); - b3CreatePoseCommandSetJointPosition(m_data->m_physicsClientHandle, commandHandle, jointIndex, - targetValue); + b3CreatePoseCommandSetJointPosition(m_data->m_physicsClientHandle, commandHandle, jointIndex, + targetValue); - statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); return false; } - void b3RobotSimulatorClientAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const b3RobotSimulatorJointMotorArgs& args) { if (!isConnected()) @@ -582,39 +598,39 @@ void b3RobotSimulatorClientAPI::setJointMotorControl(int bodyUniqueId, int joint { case CONTROL_MODE_VELOCITY: { - b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_data->m_physicsClientHandle, bodyUniqueId, CONTROL_MODE_VELOCITY); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit2(m_data->m_physicsClientHandle, bodyUniqueId, CONTROL_MODE_VELOCITY); b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; - b3JointControlSetKd(command,uIndex,args.m_kd); - b3JointControlSetDesiredVelocity(command,uIndex,args.m_targetVelocity); - b3JointControlSetMaximumForce(command,uIndex,args.m_maxTorqueValue); + b3JointControlSetKd(command, uIndex, args.m_kd); + b3JointControlSetDesiredVelocity(command, uIndex, args.m_targetVelocity); + b3JointControlSetMaximumForce(command, uIndex, args.m_maxTorqueValue); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); break; } case CONTROL_MODE_POSITION_VELOCITY_PD: { - b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_data->m_physicsClientHandle, bodyUniqueId, CONTROL_MODE_POSITION_VELOCITY_PD); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit2(m_data->m_physicsClientHandle, bodyUniqueId, CONTROL_MODE_POSITION_VELOCITY_PD); b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; int qIndex = jointInfo.m_qIndex; - b3JointControlSetDesiredPosition(command,qIndex,args.m_targetPosition); - b3JointControlSetKp(command,uIndex,args.m_kp); - b3JointControlSetDesiredVelocity(command,uIndex,args.m_targetVelocity); - b3JointControlSetKd(command,uIndex,args.m_kd); - b3JointControlSetMaximumForce(command,uIndex,args.m_maxTorqueValue); + b3JointControlSetDesiredPosition(command, qIndex, args.m_targetPosition); + b3JointControlSetKp(command, uIndex, args.m_kp); + b3JointControlSetDesiredVelocity(command, uIndex, args.m_targetVelocity); + b3JointControlSetKd(command, uIndex, args.m_kd); + b3JointControlSetMaximumForce(command, uIndex, args.m_maxTorqueValue); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); break; } case CONTROL_MODE_TORQUE: { - b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_data->m_physicsClientHandle, bodyUniqueId, CONTROL_MODE_TORQUE); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit2(m_data->m_physicsClientHandle, bodyUniqueId, CONTROL_MODE_TORQUE); b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; - b3JointControlSetDesiredForceTorque(command,uIndex,args.m_maxTorqueValue); + b3JointControlSetDesiredForceTorque(command, uIndex, args.m_maxTorqueValue); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); break; } @@ -625,7 +641,6 @@ void b3RobotSimulatorClientAPI::setJointMotorControl(int bodyUniqueId, int joint } } - void b3RobotSimulatorClientAPI::setNumSolverIterations(int numIterations) { if (!isConnected()) @@ -633,12 +648,11 @@ void b3RobotSimulatorClientAPI::setNumSolverIterations(int numIterations) b3Warning("Not connected"); return; } - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle); - b3SharedMemoryStatusHandle statusHandle; - b3PhysicsParamSetNumSolverIterations(command, numIterations); - statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - b3Assert(b3GetStatusType(statusHandle)==CMD_CLIENT_COMMAND_COMPLETED); - + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle); + b3SharedMemoryStatusHandle statusHandle; + b3PhysicsParamSetNumSolverIterations(command, numIterations); + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); } void b3RobotSimulatorClientAPI::setTimeStep(double timeStepInSeconds) @@ -654,10 +668,8 @@ void b3RobotSimulatorClientAPI::setTimeStep(double timeStepInSeconds) int ret; ret = b3PhysicsParamSetTimeStep(command, timeStepInSeconds); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - } - void b3RobotSimulatorClientAPI::setNumSimulationSubSteps(int numSubSteps) { if (!isConnected()) @@ -665,14 +677,13 @@ void b3RobotSimulatorClientAPI::setNumSimulationSubSteps(int numSubSteps) b3Warning("Not connected"); return; } - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle); - b3SharedMemoryStatusHandle statusHandle; - b3PhysicsParamSetNumSubSteps(command, numSubSteps); - statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - b3Assert(b3GetStatusType(statusHandle)==CMD_CLIENT_COMMAND_COMPLETED); + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle); + b3SharedMemoryStatusHandle statusHandle; + b3PhysicsParamSetNumSubSteps(command, numSubSteps); + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); } - bool b3RobotSimulatorClientAPI::calculateInverseKinematics(const struct b3RobotSimulatorInverseKinematicArgs& args, struct b3RobotSimulatorInverseKinematicsResults& results) { if (!isConnected()) @@ -680,55 +691,52 @@ bool b3RobotSimulatorClientAPI::calculateInverseKinematics(const struct b3RobotS b3Warning("Not connected"); return false; } - b3Assert(args.m_endEffectorLinkIndex>=0); - b3Assert(args.m_bodyUniqueId>=0); - + b3Assert(args.m_endEffectorLinkIndex >= 0); + b3Assert(args.m_bodyUniqueId >= 0); - b3SharedMemoryCommandHandle command = b3CalculateInverseKinematicsCommandInit(m_data->m_physicsClientHandle,args.m_bodyUniqueId); + b3SharedMemoryCommandHandle command = b3CalculateInverseKinematicsCommandInit(m_data->m_physicsClientHandle, args.m_bodyUniqueId); if ((args.m_flags & B3_HAS_IK_TARGET_ORIENTATION) && (args.m_flags & B3_HAS_NULL_SPACE_VELOCITY)) - { - b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(command, args.m_numDegreeOfFreedom, args.m_endEffectorLinkIndex, args.m_endEffectorTargetPosition, args.m_endEffectorTargetOrientation, &args.m_lowerLimits[0], &args.m_upperLimits[0], &args.m_jointRanges[0], &args.m_restPoses[0]); - } else if (args.m_flags & B3_HAS_IK_TARGET_ORIENTATION) { - b3CalculateInverseKinematicsAddTargetPositionWithOrientation(command,args.m_endEffectorLinkIndex,args.m_endEffectorTargetPosition,args.m_endEffectorTargetOrientation); - } else if (args.m_flags & B3_HAS_NULL_SPACE_VELOCITY) - { - b3CalculateInverseKinematicsPosWithNullSpaceVel(command, args.m_numDegreeOfFreedom, args.m_endEffectorLinkIndex, args.m_endEffectorTargetPosition, &args.m_lowerLimits[0], &args.m_upperLimits[0], &args.m_jointRanges[0], &args.m_restPoses[0]); - } else - { - b3CalculateInverseKinematicsAddTargetPurePosition(command,args.m_endEffectorLinkIndex,args.m_endEffectorTargetPosition); + b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(command, args.m_numDegreeOfFreedom, args.m_endEffectorLinkIndex, args.m_endEffectorTargetPosition, args.m_endEffectorTargetOrientation, &args.m_lowerLimits[0], &args.m_upperLimits[0], &args.m_jointRanges[0], &args.m_restPoses[0]); + } + else if (args.m_flags & B3_HAS_IK_TARGET_ORIENTATION) + { + b3CalculateInverseKinematicsAddTargetPositionWithOrientation(command, args.m_endEffectorLinkIndex, args.m_endEffectorTargetPosition, args.m_endEffectorTargetOrientation); + } + else if (args.m_flags & B3_HAS_NULL_SPACE_VELOCITY) + { + b3CalculateInverseKinematicsPosWithNullSpaceVel(command, args.m_numDegreeOfFreedom, args.m_endEffectorLinkIndex, args.m_endEffectorTargetPosition, &args.m_lowerLimits[0], &args.m_upperLimits[0], &args.m_jointRanges[0], &args.m_restPoses[0]); + } + else + { + b3CalculateInverseKinematicsAddTargetPurePosition(command, args.m_endEffectorLinkIndex, args.m_endEffectorTargetPosition); } - - if (args.m_flags & B3_HAS_JOINT_DAMPING) - { - b3CalculateInverseKinematicsSetJointDamping(command, args.m_numDegreeOfFreedom, &args.m_jointDamping[0]); - } - b3SharedMemoryStatusHandle statusHandle; + if (args.m_flags & B3_HAS_JOINT_DAMPING) + { + b3CalculateInverseKinematicsSetJointDamping(command, args.m_numDegreeOfFreedom, &args.m_jointDamping[0]); + } + + b3SharedMemoryStatusHandle statusHandle; statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - + int numPos = 0; - int numPos=0; - bool result = b3GetStatusInverseKinematicsJointPositions(statusHandle, - &results.m_bodyUniqueId, - &numPos, - 0)!=0; - if (result && numPos) - { - results.m_calculatedJointPositions.resize(numPos); - result = b3GetStatusInverseKinematicsJointPositions(statusHandle, - &results.m_bodyUniqueId, - &numPos, - &results.m_calculatedJointPositions[0])!=0; - - } + &results.m_bodyUniqueId, + &numPos, + 0) != 0; + if (result && numPos) + { + results.m_calculatedJointPositions.resize(numPos); + result = b3GetStatusInverseKinematicsJointPositions(statusHandle, + &results.m_bodyUniqueId, + &numPos, + &results.m_calculatedJointPositions[0]) != 0; + } return result; } - - bool b3RobotSimulatorClientAPI::getBodyJacobian(int bodyUniqueId, int linkIndex, const double* localPosition, const double* jointPositions, const double* jointVelocities, const double* jointAccelerations, double* linearJacobian, double* angularJacobian) { if (!isConnected()) @@ -736,12 +744,12 @@ bool b3RobotSimulatorClientAPI::getBodyJacobian(int bodyUniqueId, int linkIndex, b3Warning("Not connected"); return false; } - b3SharedMemoryCommandHandle command = b3CalculateJacobianCommandInit(m_data->m_physicsClientHandle, bodyUniqueId, linkIndex, localPosition, jointPositions, jointVelocities, jointAccelerations); - b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - - if (b3GetStatusType(statusHandle) == CMD_CALCULATED_JACOBIAN_COMPLETED) - { - b3GetStatusJacobian(statusHandle, linearJacobian, angularJacobian); + b3SharedMemoryCommandHandle command = b3CalculateJacobianCommandInit(m_data->m_physicsClientHandle, bodyUniqueId, linkIndex, localPosition, jointPositions, jointVelocities, jointAccelerations); + b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + + if (b3GetStatusType(statusHandle) == CMD_CALCULATED_JACOBIAN_COMPLETED) + { + b3GetStatusJacobian(statusHandle, linearJacobian, angularJacobian); return true; } return false; @@ -754,14 +762,14 @@ bool b3RobotSimulatorClientAPI::getLinkState(int bodyUniqueId, int linkIndex, b3 b3Warning("Not connected"); return false; } - b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle,bodyUniqueId); - b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - - if (b3GetStatusType(statusHandle) == CMD_ACTUAL_STATE_UPDATE_COMPLETED) - { - b3GetLinkState(m_data->m_physicsClientHandle, statusHandle, linkIndex, linkState); + b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle, bodyUniqueId); + b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + + if (b3GetStatusType(statusHandle) == CMD_ACTUAL_STATE_UPDATE_COMPLETED) + { + b3GetLinkState(m_data->m_physicsClientHandle, statusHandle, linkIndex, linkState); return true; - } + } return false; } @@ -787,9 +795,9 @@ void b3RobotSimulatorClientAPI::getVREvents(b3VREventsData* vrEventsData) return; } - b3SharedMemoryCommandHandle commandHandle = b3RequestVREventsCommandInit(m_data->m_physicsClientHandle); + b3SharedMemoryCommandHandle commandHandle = b3RequestVREventsCommandInit(m_data->m_physicsClientHandle); b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); - b3GetVREventsData(m_data->m_physicsClientHandle, vrEventsData); + b3GetVREventsData(m_data->m_physicsClientHandle, vrEventsData); } void b3RobotSimulatorClientAPI::getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData) @@ -802,32 +810,35 @@ void b3RobotSimulatorClientAPI::getKeyboardEvents(b3KeyboardEventsData* keyboard return; } - b3SharedMemoryCommandHandle commandHandle = b3RequestKeyboardEventsCommandInit(m_data->m_physicsClientHandle); + b3SharedMemoryCommandHandle commandHandle = b3RequestKeyboardEventsCommandInit(m_data->m_physicsClientHandle); b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); - b3GetKeyboardEventsData(m_data->m_physicsClientHandle,keyboardEventsData); - + b3GetKeyboardEventsData(m_data->m_physicsClientHandle, keyboardEventsData); } - -int b3RobotSimulatorClientAPI::startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray& objectUniqueIds) +int b3RobotSimulatorClientAPI::startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray& objectUniqueIds, int maxLogDof) { int loggingUniqueId = -1; b3SharedMemoryCommandHandle commandHandle; commandHandle = b3StateLoggingCommandInit(m_data->m_physicsClientHandle); - - b3StateLoggingStart(commandHandle,loggingType,fileName.c_str()); - for ( int i=0;i 0) + { + b3StateLoggingSetMaxLogDof(commandHandle, maxLogDof); } b3SharedMemoryStatusHandle statusHandle; int statusType; statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); statusType = b3GetStatusType(statusHandle); - if (statusType==CMD_STATE_LOGGING_START_COMPLETED) + if (statusType == CMD_STATE_LOGGING_START_COMPLETED) { loggingUniqueId = b3GetStatusLoggingUniqueId(statusHandle); } @@ -842,4 +853,3 @@ void b3RobotSimulatorClientAPI::stopStateLogging(int stateLoggerUniqueId) b3StateLoggingStop(commandHandle, stateLoggerUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); } - diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h index e6f658cc5..9fe1b8c50 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h @@ -9,23 +9,18 @@ #include - - - - struct b3RobotSimulatorLoadUrdfFileArgs { b3Vector3 m_startPosition; b3Quaternion m_startOrientation; bool m_forceOverrideFixedBase; - bool m_useMultiBody; + bool m_useMultiBody; b3RobotSimulatorLoadUrdfFileArgs() - : - m_startPosition(b3MakeVector3(0,0,0)), - m_startOrientation(b3Quaternion(0,0,0,1)), - m_forceOverrideFixedBase(false), - m_useMultiBody(true) + : m_startPosition(b3MakeVector3(0, 0, 0)), + m_startOrientation(b3Quaternion(0, 0, 0, 1)), + m_forceOverrideFixedBase(false), + m_useMultiBody(true) { } }; @@ -33,17 +28,15 @@ struct b3RobotSimulatorLoadUrdfFileArgs struct b3RobotSimulatorLoadSdfFileArgs { bool m_forceOverrideFixedBase; - bool m_useMultiBody; + bool m_useMultiBody; b3RobotSimulatorLoadSdfFileArgs() - : - m_forceOverrideFixedBase(false), - m_useMultiBody(true) + : m_forceOverrideFixedBase(false), + m_useMultiBody(true) { } }; - struct b3RobotSimulatorLoadFileResults { b3AlignedObjectArray m_uniqueObjectIds; @@ -55,7 +48,7 @@ struct b3RobotSimulatorLoadFileResults struct b3RobotSimulatorJointMotorArgs { int m_controlMode; - + double m_targetPosition; double m_kp; @@ -65,52 +58,52 @@ struct b3RobotSimulatorJointMotorArgs double m_maxTorqueValue; b3RobotSimulatorJointMotorArgs(int controlMode) - :m_controlMode(controlMode), - m_targetPosition(0), - m_kp(0.1), - m_targetVelocity(0), - m_kd(0.9), - m_maxTorqueValue(1000) + : m_controlMode(controlMode), + m_targetPosition(0), + m_kp(0.1), + m_targetVelocity(0), + m_kd(0.9), + m_maxTorqueValue(1000) { } }; enum b3RobotSimulatorInverseKinematicsFlags { - B3_HAS_IK_TARGET_ORIENTATION=1, - B3_HAS_NULL_SPACE_VELOCITY=2, - B3_HAS_JOINT_DAMPING=4, + B3_HAS_IK_TARGET_ORIENTATION = 1, + B3_HAS_NULL_SPACE_VELOCITY = 2, + B3_HAS_JOINT_DAMPING = 4, }; struct b3RobotSimulatorInverseKinematicArgs { int m_bodyUniqueId; -// double* m_currentJointPositions; -// int m_numPositions; + // double* m_currentJointPositions; + // int m_numPositions; double m_endEffectorTargetPosition[3]; double m_endEffectorTargetOrientation[4]; - int m_endEffectorLinkIndex; + int m_endEffectorLinkIndex; int m_flags; - int m_numDegreeOfFreedom; - b3AlignedObjectArray m_lowerLimits; - b3AlignedObjectArray m_upperLimits; - b3AlignedObjectArray m_jointRanges; - b3AlignedObjectArray m_restPoses; - b3AlignedObjectArray m_jointDamping; + int m_numDegreeOfFreedom; + b3AlignedObjectArray m_lowerLimits; + b3AlignedObjectArray m_upperLimits; + b3AlignedObjectArray m_jointRanges; + b3AlignedObjectArray m_restPoses; + b3AlignedObjectArray m_jointDamping; b3RobotSimulatorInverseKinematicArgs() - :m_bodyUniqueId(-1), - m_endEffectorLinkIndex(-1), - m_flags(0) + : m_bodyUniqueId(-1), + m_endEffectorLinkIndex(-1), + m_flags(0) { - m_endEffectorTargetPosition[0]=0; - m_endEffectorTargetPosition[1]=0; - m_endEffectorTargetPosition[2]=0; + m_endEffectorTargetPosition[0] = 0; + m_endEffectorTargetPosition[1] = 0; + m_endEffectorTargetPosition[2] = 0; - m_endEffectorTargetOrientation[0]=0; - m_endEffectorTargetOrientation[1]=0; - m_endEffectorTargetOrientation[2]=0; - m_endEffectorTargetOrientation[3]=1; + m_endEffectorTargetOrientation[0] = 0; + m_endEffectorTargetOrientation[1] = 0; + m_endEffectorTargetOrientation[2] = 0; + m_endEffectorTargetOrientation[3] = 1; } }; @@ -120,20 +113,19 @@ struct b3RobotSimulatorInverseKinematicsResults b3AlignedObjectArray m_calculatedJointPositions; }; - ///The b3RobotSimulatorClientAPI is pretty much the C++ version of pybullet ///as documented in the pybullet Quickstart Guide ///https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA class b3RobotSimulatorClientAPI { struct b3RobotSimulatorClientAPI_InternalData* m_data; - + public: b3RobotSimulatorClientAPI(); virtual ~b3RobotSimulatorClientAPI(); - bool connect(int mode, const std::string& hostName="localhost", int portOrKey=-1); - + bool connect(int mode, const std::string& hostName = "localhost", int portOrKey = -1); + void disconnect(); bool isConnected() const; @@ -145,8 +137,8 @@ public: b3Quaternion getQuaternionFromEuler(const b3Vector3& rollPitchYaw); b3Vector3 getEulerFromQuaternion(const b3Quaternion& quat); - int loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args=b3RobotSimulatorLoadUrdfFileArgs()); - bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results=b3RobotSimulatorLoadFileResults(), const struct b3RobotSimulatorLoadSdfFileArgs& args=b3RobotSimulatorLoadSdfFileArgs()); + int loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args = b3RobotSimulatorLoadUrdfFileArgs()); + bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results = b3RobotSimulatorLoadFileResults(), const struct b3RobotSimulatorLoadSdfFileArgs& args = b3RobotSimulatorLoadSdfFileArgs()); bool loadMJCF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results); bool loadBullet(const std::string& fileName, b3RobotSimulatorLoadFileResults& results); @@ -155,14 +147,17 @@ public: bool getBasePositionAndOrientation(int bodyUniqueId, b3Vector3& basePosition, b3Quaternion& baseOrientation) const; bool resetBasePositionAndOrientation(int bodyUniqueId, b3Vector3& basePosition, b3Quaternion& baseOrientation); + bool getBaseVelocity(int bodyUniqueId, b3Vector3& baseLinearVelocity, b3Vector3& baseAngularVelocity) const; + bool resetBaseVelocity(int bodyUniqueId, const b3Vector3& linearVelocity, const b3Vector3& angularVelocity) const; + int getNumJoints(int bodyUniqueId) const; bool getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo* jointInfo); - - void createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo); - bool getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState *state); - + void createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo); + + bool getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState* state); + bool resetJointState(int bodyUniqueId, int jointIndex, double targetValue); void setJointMotorControl(int bodyUniqueId, int jointIndex, const struct b3RobotSimulatorJointMotorArgs& args); @@ -170,29 +165,28 @@ public: void stepSimulation(); bool canSubmitCommand() const; - + void setRealTimeSimulation(bool enableRealTimeSimulation); void setGravity(const b3Vector3& gravityAcceleration); - + void setTimeStep(double timeStepInSeconds); - void setNumSimulationSubSteps(int numSubSteps); + void setNumSimulationSubSteps(int numSubSteps); void setNumSolverIterations(int numIterations); bool calculateInverseKinematics(const struct b3RobotSimulatorInverseKinematicArgs& args, struct b3RobotSimulatorInverseKinematicsResults& results); - bool getBodyJacobian(int bodyUniqueId, int linkIndex, const double* localPosition, const double* jointPositions, const double* jointVelocities, const double* jointAccelerations, double* linearJacobian, double* angularJacobian); - + bool getBodyJacobian(int bodyUniqueId, int linkIndex, const double* localPosition, const double* jointPositions, const double* jointVelocities, const double* jointAccelerations, double* linearJacobian, double* angularJacobian); + bool getLinkState(int bodyUniqueId, int linkIndex, b3LinkState* linkState); void configureDebugVisualizer(enum b3ConfigureDebugVisualizerEnum flag, int enable); - int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray& objectUniqueIds); + int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray& objectUniqueIds, int maxLogDof = -1); void stopStateLogging(int stateLoggerUniqueId); void getVREvents(b3VREventsData* vrEventsData); void getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData); - }; -#endif //B3_ROBOT_SIMULATOR_CLIENT_API_H +#endif //B3_ROBOT_SIMULATOR_CLIENT_API_H diff --git a/src/Bullet3Common/b3Quaternion.h b/src/Bullet3Common/b3Quaternion.h index c89f2cf39..0b7564dcd 100644 --- a/src/Bullet3Common/b3Quaternion.h +++ b/src/Bullet3Common/b3Quaternion.h @@ -126,15 +126,16 @@ public: sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw, cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw); } - /**@brief Set the quaternion using euler angles + + /**@brief Set the quaternion using euler angles * @param yaw Angle around Z * @param pitch Angle around Y * @param roll Angle around X */ - void setEulerZYX(const b3Scalar& yaw, const b3Scalar& pitch, const b3Scalar& roll) + void setEulerZYX(const b3Scalar& yawZ, const b3Scalar& pitchY, const b3Scalar& rollX) { - b3Scalar halfYaw = b3Scalar(yaw) * b3Scalar(0.5); - b3Scalar halfPitch = b3Scalar(pitch) * b3Scalar(0.5); - b3Scalar halfRoll = b3Scalar(roll) * b3Scalar(0.5); + b3Scalar halfYaw = b3Scalar(yawZ) * b3Scalar(0.5); + b3Scalar halfPitch = b3Scalar(pitchY) * b3Scalar(0.5); + b3Scalar halfRoll = b3Scalar(rollX) * b3Scalar(0.5); b3Scalar cosYaw = b3Cos(halfYaw); b3Scalar sinYaw = b3Sin(halfYaw); b3Scalar cosPitch = b3Cos(halfPitch); @@ -145,7 +146,30 @@ public: cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw, //y cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw, //z cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw); //formerly yzx + normalize(); } + + /**@brief Get the euler angles from this quaternion + * @param yaw Angle around Z + * @param pitch Angle around Y + * @param roll Angle around X */ + void getEulerZYX(b3Scalar& yawZ, b3Scalar& pitchY, b3Scalar& rollX) const + { + b3Scalar squ; + b3Scalar sqx; + b3Scalar sqy; + b3Scalar sqz; + b3Scalar sarg; + sqx = m_floats[0] * m_floats[0]; + sqy = m_floats[1] * m_floats[1]; + sqz = m_floats[2] * m_floats[2]; + squ = m_floats[3] * m_floats[3]; + rollX = b3Atan2(2 * (m_floats[1] * m_floats[2] + m_floats[3] * m_floats[0]), squ - sqx - sqy + sqz); + sarg = b3Scalar(-2.) * (m_floats[0] * m_floats[2] - m_floats[3] * m_floats[1]); + pitchY = sarg <= b3Scalar(-1.0) ? b3Scalar(-0.5) * B3_PI: (sarg >= b3Scalar(1.0) ? b3Scalar(0.5) * B3_PI : b3Asin(sarg)); + yawZ = b3Atan2(2 * (m_floats[0] * m_floats[1] + m_floats[3] * m_floats[2]), squ + sqx - sqy - sqz); + } + /**@brief Add two quaternions * @param q The quaternion to add to this one */ B3_FORCE_INLINE b3Quaternion& operator+=(const b3Quaternion& q) From e0a4393bd21ed95f2fac180b8fbeb26ed709301a Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 15 Mar 2017 17:35:10 -0700 Subject: [PATCH 50/66] fix compile issue --- examples/RobotSimulator/b3RobotSimulatorClientAPI.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h index 9fe1b8c50..a6f6ef1f9 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h @@ -138,7 +138,7 @@ public: b3Vector3 getEulerFromQuaternion(const b3Quaternion& quat); int loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args = b3RobotSimulatorLoadUrdfFileArgs()); - bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results = b3RobotSimulatorLoadFileResults(), const struct b3RobotSimulatorLoadSdfFileArgs& args = b3RobotSimulatorLoadSdfFileArgs()); + bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results, const struct b3RobotSimulatorLoadSdfFileArgs& args = b3RobotSimulatorLoadSdfFileArgs()); bool loadMJCF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results); bool loadBullet(const std::string& fileName, b3RobotSimulatorLoadFileResults& results); From 59d16b2c427196e07eca884e5a4ea4af7ea1bb5b Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 16 Mar 2017 09:13:33 -0700 Subject: [PATCH 51/66] expose video capture as logging command in b3RobotSimulatorClientAPI (C++) and pybullet (use STATE_LOGGING_VIDEO_MP4) --- .../CommonGUIHelperInterface.h | 3 ++ examples/ExampleBrowser/CMakeLists.txt | 2 + .../ExampleBrowser/OpenGLExampleBrowser.cpp | 5 ++- examples/ExampleBrowser/OpenGLGuiHelper.cpp | 7 +++ examples/ExampleBrowser/OpenGLGuiHelper.h | 2 + examples/ExampleBrowser/premake4.lua | 2 + examples/OpenGLWindow/SimpleOpenGL3App.cpp | 38 ++++++++++------ .../RobotSimulator/RobotSimulatorMain.cpp | 44 +++++++++++++++++-- .../b3RobotSimulatorClientAPI.cpp | 27 ++++++++++++ .../b3RobotSimulatorClientAPI.h | 5 ++- examples/SharedMemory/CMakeLists.txt | 2 + .../PhysicsServerCommandProcessor.cpp | 36 +++++++++++++++ .../SharedMemory/PhysicsServerExample.cpp | 22 +++++++++- .../PhysicsServerSharedMemory.cpp | 2 + examples/SharedMemory/SharedMemoryPublic.h | 3 +- examples/pybullet/premake4.lua | 2 + 16 files changed, 180 insertions(+), 22 deletions(-) diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index 8e220faef..493b9e123 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -85,6 +85,9 @@ struct GUIHelperInterface virtual void removeAllUserDebugItems( ){}; virtual void setVisualizerFlagCallback(VisualizerFlagCallback callback){} + //empty name stops dumping video + virtual void dumpFramesToVideo(const char* mp4FileName) {}; + }; diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index b7cf1fd06..127ab11f5 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -191,6 +191,8 @@ SET(BulletExampleBrowser_SRCS ../SharedMemory/PhysicsLoopBackC_API.h ../SharedMemory/PhysicsServerCommandProcessor.cpp ../SharedMemory/PhysicsServerCommandProcessor.h + ../SharedMemory/SharedMemoryCommands.h + ../SharedMemory/SharedMemoryPublic.h ../BasicDemo/BasicExample.cpp ../BasicDemo/BasicExample.h ../InverseDynamics/InverseDynamicsExample.cpp diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 368cd67cc..df2a83021 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -371,6 +371,7 @@ void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable) if (flag == COV_ENABLE_GUI) { renderGui = enable; + renderGrid = enable; } if (flag == COV_ENABLE_WIREFRAME) @@ -868,8 +869,8 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[]) } - int width = 1024; - int height=768; + int width = 1280; + int height=640; #ifndef NO_OPENGL3 SimpleOpenGL3App* simpleApp=0; sUseOpenGL2 =args.CheckCmdLineFlag("opengl2"); diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 2107c8bb3..b65eaea44 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -568,3 +568,10 @@ struct CommonGraphicsApp* OpenGLGuiHelper::getAppInterface() return m_data->m_glApp; } +void OpenGLGuiHelper::dumpFramesToVideo(const char* mp4FileName) +{ + if (m_data->m_glApp) + { + m_data->m_glApp->dumpFramesToVideo(mp4FileName); + } +} \ No newline at end of file diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index 9448b5eef..0e91f0f3b 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -85,6 +85,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface virtual void setVisualizerFlagCallback(VisualizerFlagCallback callback); + virtual void dumpFramesToVideo(const char* mp4FileName); + }; #endif //OPENGL_GUI_HELPER_H diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index 0c44e93bb..f6a7df31f 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -88,6 +88,8 @@ project "App_BulletExampleBrowser" "../SharedMemory/PhysicsServerCommandProcessor.h", "../SharedMemory/TinyRendererVisualShapeConverter.cpp", "../SharedMemory/TinyRendererVisualShapeConverter.h", + "../SharedMemory/SharedMemoryCommands.h", + "../SharedMemory/SharedMemoryPublic.h", "../MultiThreading/MultiThreadingExample.cpp", "../MultiThreading/b3PosixThreadSupport.cpp", "../MultiThreading/b3Win32ThreadSupport.cpp", diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index 212d80a6f..f7e37688a 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -774,16 +774,18 @@ void SimpleOpenGL3App::swapBuffer() m_data->m_frameDumpPngFileName = 0; } } - m_window->endRendering(); - m_window->startRendering(); + m_window->endRendering(); + m_window->startRendering(); } // see also http://blog.mmacklin.com/2013/06/11/real-time-video-capture-with-ffmpeg/ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName) { - int width = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth(); - int height = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenHeight(); - char cmd[8192]; + if (mp4FileName) + { + int width = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth(); + int height = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenHeight(); + char cmd[8192]; #ifdef _WIN32 sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " @@ -803,15 +805,25 @@ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName) // sprintf(cmd,"ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " // "-threads 0 -preset fast -y -crf 21 -vf vflip %s",width,height,mp4FileName); - if (m_data->m_ffmpegFile) - { - pclose(m_data->m_ffmpegFile); - } - if (mp4FileName) - { - m_data->m_ffmpegFile = popen(cmd, "w"); + if (m_data->m_ffmpegFile) + { + pclose(m_data->m_ffmpegFile); + } + if (mp4FileName) + { + m_data->m_ffmpegFile = popen(cmd, "w"); - m_data->m_frameDumpPngFileName = mp4FileName; + m_data->m_frameDumpPngFileName = mp4FileName; + } + } else + { + if (m_data->m_ffmpegFile) + { + fflush(m_data->m_ffmpegFile); + pclose(m_data->m_ffmpegFile); + m_data->m_frameDumpPngFileName = 0; + } + m_data->m_ffmpegFile = 0; } } void SimpleOpenGL3App::dumpNextFrameToPng(const char* filename) diff --git a/examples/RobotSimulator/RobotSimulatorMain.cpp b/examples/RobotSimulator/RobotSimulatorMain.cpp index 77b6bf583..7ab3f3e70 100644 --- a/examples/RobotSimulator/RobotSimulatorMain.cpp +++ b/examples/RobotSimulator/RobotSimulatorMain.cpp @@ -16,7 +16,7 @@ int main(int argc, char* argv[]) //sim->connect(eCONNECT_UDP, "localhost", 1234); sim->configureDebugVisualizer( COV_ENABLE_GUI, 0); // sim->configureDebugVisualizer( COV_ENABLE_SHADOWS, 0);//COV_ENABLE_WIREFRAME - + sim->setTimeOut(10); //syncBodies is only needed when connecting to an existing physics server that has already some bodies sim->syncBodies(); b3Scalar fixedTimeStep = 1./240.; @@ -59,7 +59,9 @@ int main(int argc, char* argv[]) } #endif sim->setRealTimeSimulation(false); - + int vidLogId = -1; + int minitaurLogId = -1; + while (sim->canSubmitCommand()) { b3KeyboardEventsData keyEvents; @@ -67,14 +69,48 @@ int main(int argc, char* argv[]) if (keyEvents.m_numKeyboardEvents) { - printf("num key events = %d]\n", keyEvents.m_numKeyboardEvents); + //printf("num key events = %d]\n", keyEvents.m_numKeyboardEvents); //m_keyState is a flag combination of eButtonIsDown,eButtonTriggered, eButtonReleased for (int i=0;istartStateLogging(STATE_LOGGING_VIDEO_MP4,"video.mp4"); + } + else + { + sim->stopStateLogging(vidLogId); + vidLogId=-1; + } + } + } + + if (keyEvents.m_keyboardEvents[i].m_keyCode=='m') + { + if ( minitaurLogId<0 && keyEvents.m_keyboardEvents[i].m_keyState&eButtonTriggered) + { + minitaurLogId = sim->startStateLogging(STATE_LOGGING_MINITAUR,"simlog.bin"); + } + if (minitaurLogId>=0 && keyEvents.m_keyboardEvents[i].m_keyState&eButtonReleased) + { + sim->stopStateLogging(minitaurLogId); + minitaurLogId=-1; + } + } + + + //printf("keyEvent[%d].m_keyCode = %d, state = %d\n", i,keyEvents.m_keyboardEvents[i].m_keyCode,keyEvents.m_keyboardEvents[i].m_keyState); } } sim->stepSimulation(); + static double yaw=0; + double distance = 10.5+9 * b3Sin(yaw); + yaw+=0.008; + sim->resetDebugVisualizerCamera(distance,yaw,20,b3MakeVector3(0,0,0.1)); b3Clock::usleep(1000.*1000.*fixedTimeStep); } diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 4c95006d2..8b2834a2f 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -134,6 +134,18 @@ bool b3RobotSimulatorClientAPI::isConnected() const return (m_data->m_physicsClientHandle != 0); } +void b3RobotSimulatorClientAPI::setTimeOut(double timeOutInSec) +{ + if (!isConnected()) + { + b3Warning("Not connected"); + return; + } + b3SetTimeOut(m_data->m_physicsClientHandle,timeOutInSec); + +} + + void b3RobotSimulatorClientAPI::disconnect() { if (!isConnected()) @@ -853,3 +865,18 @@ void b3RobotSimulatorClientAPI::stopStateLogging(int stateLoggerUniqueId) b3StateLoggingStop(commandHandle, stateLoggerUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); } + +void b3RobotSimulatorClientAPI::resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const b3Vector3& targetPos) +{ + b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(m_data->m_physicsClientHandle); + if (commandHandle) + { + if ((cameraDistance >= 0)) + { + b3Vector3FloatData camTargetPos; + targetPos.serializeFloat(camTargetPos); + b3ConfigureOpenGLVisualizerSetViewMatrix(commandHandle, cameraDistance, cameraPitch, cameraYaw, camTargetPos.m_floats); + } + b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); + } +} diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h index 9fe1b8c50..659d84502 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h @@ -130,6 +130,8 @@ public: bool isConnected() const; + void setTimeOut(double timeOutInSec); + void syncBodies(); void resetSimulation(); @@ -181,8 +183,9 @@ public: bool getLinkState(int bodyUniqueId, int linkIndex, b3LinkState* linkState); void configureDebugVisualizer(enum b3ConfigureDebugVisualizerEnum flag, int enable); + void resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const b3Vector3& targetPos); - int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray& objectUniqueIds, int maxLogDof = -1); + int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray& objectUniqueIds=b3AlignedObjectArray(), int maxLogDof = -1); void stopStateLogging(int stateLoggerUniqueId); void getVREvents(b3VREventsData* vrEventsData); diff --git a/examples/SharedMemory/CMakeLists.txt b/examples/SharedMemory/CMakeLists.txt index b282c09cb..d2754f8c5 100644 --- a/examples/SharedMemory/CMakeLists.txt +++ b/examples/SharedMemory/CMakeLists.txt @@ -38,6 +38,8 @@ SET(SharedMemory_SRCS PhysicsServerCommandProcessor.h TinyRendererVisualShapeConverter.cpp TinyRendererVisualShapeConverter.h + SharedMemoryCommands.h + SharedMemoryPublic.h ../TinyRenderer/geometry.cpp ../TinyRenderer/model.cpp ../TinyRenderer/tgaimage.cpp diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 85fb1dd7a..c5a48efaa 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -438,6 +438,31 @@ struct InternalStateLogger }; +struct VideoMP4Loggger : public InternalStateLogger +{ + + struct GUIHelperInterface* m_guiHelper; + std::string m_fileName; + VideoMP4Loggger(int loggerUid,const char* fileName,GUIHelperInterface* guiHelper) + :m_guiHelper(guiHelper) + { + m_fileName = fileName; + m_loggingUniqueId = loggerUid; + m_loggingType = STATE_LOGGING_VIDEO_MP4; + m_guiHelper->dumpFramesToVideo(fileName); + } + + virtual void stop() + { + m_guiHelper->dumpFramesToVideo(0); + } + virtual void logState(btScalar timeStamp) + { + //dumping video frames happens in another thread + //we could add some overlay of timestamp here, if needed/wanted + } +}; + struct MinitaurStateLogger : public InternalStateLogger { int m_loggingTimeStamp; @@ -1797,6 +1822,17 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (clientCmd.m_updateFlags & STATE_LOGGING_START_LOG) { + if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_VIDEO_MP4) + { + if (clientCmd.m_stateLoggingArguments.m_fileName) + { + int loggerUid = m_data->m_stateLoggersUniqueId++; + VideoMP4Loggger* logger = new VideoMP4Loggger(loggerUid,clientCmd.m_stateLoggingArguments.m_fileName,this->m_data->m_guiHelper); + m_data->m_stateLoggers.push_back(logger); + serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED; + serverStatusOut.m_stateLoggingResultArgs.m_loggingUniqueId = loggerUid; + } + } if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_MINITAUR) { diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index dc3390c4e..970b209d3 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -179,8 +179,10 @@ enum MultiThreadedGUIHelperCommunicationEnums eGUIUserDebugAddParameter, eGUIUserDebugRemoveItem, eGUIUserDebugRemoveAllItems, + eGUIDumpFramesToVideo, }; + #include //#include "BulletMultiThreaded/PlatformDefinitions.h" @@ -489,7 +491,7 @@ void MotionThreadFunc(void* userPtr,void* lsMemory) args->m_cs->unlock(); } - + args->m_physicsServerPtr->disconnectSharedMemory(true); //do nothing } @@ -959,6 +961,16 @@ public: } + const char* m_mp4FileName; + virtual void dumpFramesToVideo(const char* mp4FileName) + { + m_cs->lock(); + m_mp4FileName = mp4FileName; + m_cs->setSharedParam(1, eGUIDumpFramesToVideo); + workerThreadWait(); + m_mp4FileName = 0; + } + }; @@ -1614,6 +1626,14 @@ void PhysicsServerExample::updateGraphics() m_multiThreadedHelper->mainThreadRelease(); break; } + + case eGUIDumpFramesToVideo: + { + m_multiThreadedHelper->m_childGuiHelper->dumpFramesToVideo(m_multiThreadedHelper->m_mp4FileName); + m_multiThreadedHelper->mainThreadRelease(); + break; + } + case eGUIHelperIdle: { break; diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.cpp b/examples/SharedMemory/PhysicsServerSharedMemory.cpp index 182187885..70d173784 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsServerSharedMemory.cpp @@ -188,6 +188,8 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface* void PhysicsServerSharedMemory::disconnectSharedMemory(bool deInitializeSharedMemory) { + m_data->m_commandProcessor->deleteDynamicsWorld(); + m_data->m_commandProcessor->setGuiHelper(0); if (m_data->m_verboseOutput) diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 73760a130..6421a37e0 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -330,7 +330,8 @@ enum b3StateLoggingType STATE_LOGGING_MINITAUR = 0, STATE_LOGGING_GENERIC_ROBOT = 1, STATE_LOGGING_VR_CONTROLLERS = 2, - STATE_LOGGING_COMMANDS = 3, + STATE_LOGGING_VIDEO_MP4 = 3, + STATE_LOGGING_COMMANDS = 4, }; diff --git a/examples/pybullet/premake4.lua b/examples/pybullet/premake4.lua index d424ef209..7892d3da2 100644 --- a/examples/pybullet/premake4.lua +++ b/examples/pybullet/premake4.lua @@ -125,6 +125,8 @@ if not _OPTIONS["no-enet"] then "../../examples/SharedMemory/Win32SharedMemory.h", "../../examples/SharedMemory/PosixSharedMemory.cpp", "../../examples/SharedMemory/PosixSharedMemory.h", + "../../examples/SharedMemory/SharedMemoryCommands.h", + "../../examples/SharedMemory/SharedMemoryPublic.h", "../../examples/Utils/b3ResourcePath.cpp", "../../examples/Utils/b3ResourcePath.h", "../../examples/Utils/RobotLoggingUtil.cpp", From 32b9eacb3434c09c5cb1bc55c5beecc7eb2ac84c Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 16 Mar 2017 13:26:44 -0700 Subject: [PATCH 52/66] fix compile issue --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index c5a48efaa..9fd045f9b 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1824,7 +1824,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_VIDEO_MP4) { - if (clientCmd.m_stateLoggingArguments.m_fileName) + //if (clientCmd.m_stateLoggingArguments.m_fileName) { int loggerUid = m_data->m_stateLoggersUniqueId++; VideoMP4Loggger* logger = new VideoMP4Loggger(loggerUid,clientCmd.m_stateLoggingArguments.m_fileName,this->m_data->m_guiHelper); From e8da7bb6f8de7ac464548f69b918b2cbf2ed2aaa Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Fri, 17 Mar 2017 02:09:55 +0300 Subject: [PATCH 53/66] URDF loader: fix MuJoCo xml load, also closes #993 --- .../ImportMJCFDemo/BulletMJCFImporter.cpp | 229 ++++++++---------- .../ImportMJCFDemo/BulletMJCFImporter.h | 5 +- .../ImportMJCFDemo/ImportMJCFSetup.cpp | 51 ++-- .../ImportURDFDemo/BulletUrdfImporter.cpp | 32 +-- .../ImportURDFDemo/BulletUrdfImporter.h | 2 +- .../LinkVisualShapesConverter.h | 7 +- .../Importers/ImportURDFDemo/URDF2Bullet.cpp | 8 +- .../ImportURDFDemo/URDFImporterInterface.h | 2 +- .../Importers/ImportURDFDemo/UrdfParser.h | 15 +- examples/SharedMemory/PhysicsDirect.cpp | 2 +- .../PhysicsServerCommandProcessor.cpp | 25 +- .../TinyRendererVisualShapeConverter.cpp | 129 ++++++---- .../TinyRendererVisualShapeConverter.h | 2 +- 13 files changed, 259 insertions(+), 250 deletions(-) diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index 4d225c05b..d1a051fc8 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -30,12 +30,6 @@ #include -enum eMJCF_FILE_TYPE_ENUMS -{ - MJCF_FILE_STL = 1, - MJCF_FILE_OBJ = 2 -}; - enum ePARENT_LINK_ENUMS { BASE_LINK_INDEX=-1, @@ -137,9 +131,11 @@ struct MyMJCFAsset struct BulletMJCFImporterInternalData { GUIHelperInterface* m_guiHelper; + struct LinkVisualShapesConverter* m_customVisualShapesConverter; char m_pathPrefix[1024]; - std::string m_fileModelName; + std::string m_sourceFileName; // with path + std::string m_fileModelName; // without path btHashMap m_assets; btAlignedObjectArray m_models; @@ -150,6 +146,7 @@ struct BulletMJCFImporterInternalData int m_activeModel; + int m_activeBodyUniqueId; //todo: for full MJCF compatibility, we would need a stack of default values int m_defaultCollisionGroup; int m_defaultCollisionMask; @@ -160,12 +157,20 @@ struct BulletMJCFImporterInternalData BulletMJCFImporterInternalData() :m_activeModel(-1), + m_activeBodyUniqueId(-1), m_defaultCollisionGroup(1), m_defaultCollisionMask(1), m_defaultCollisionMargin(0.001)//assume unit meters, margin is 1mm { m_pathPrefix[0] = 0; } + + std::string sourceFileLocation(TiXmlElement* e) + { + char buf[1024]; + snprintf(buf, sizeof(buf), "%s:%i", m_sourceFileName.c_str(), e->Row()); + return buf; + } const UrdfLink* getLink(int modelIndex, int linkIndex) const { @@ -621,9 +626,14 @@ struct BulletMJCFImporterInternalData MyMJCFAsset* assetPtr = m_assets[meshStr]; if (assetPtr) { - handledGeomType = true; geom.m_type = URDF_GEOM_MESH; geom.m_meshFileName = assetPtr->m_fileName; + bool exists = findExistingMeshFile( + m_sourceFileName, assetPtr->m_fileName, sourceFileLocation(link_xml), + &geom.m_meshFileName, + &geom.m_meshFileType); + handledGeomType = exists; + geom.m_meshScale.setValue(1,1,1); //todo: parse mesh scale if (sz) @@ -1113,10 +1123,11 @@ struct BulletMJCFImporterInternalData }; -BulletMJCFImporter::BulletMJCFImporter(struct GUIHelperInterface* helper) +BulletMJCFImporter::BulletMJCFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter) { m_data = new BulletMJCFImporterInternalData(); m_data->m_guiHelper = helper; + m_data->m_customVisualShapesConverter = customConverter; } BulletMJCFImporter::~BulletMJCFImporter() @@ -1135,7 +1146,8 @@ bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger, b3FileUtils fu; //bool fileFound = fu.findFile(fileName, relativeFileName, 1024); - bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024)>0); + bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024)>0); + m_data->m_sourceFileName = relativeFileName; std::string xml_string; m_data->m_pathPrefix[0] = 0; @@ -1399,21 +1411,26 @@ bool BulletMJCFImporter::getLinkContactInfo(int linkIndex, URDFLinkContactInfo& return false; } - -void BulletMJCFImporter::convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const +void BulletMJCFImporter::convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const { + if (m_data->m_customVisualShapesConverter) + { + const UrdfLink* link = m_data->getLink(m_data->m_activeModel, urdfIndex); + m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,inertialFrame, link, 0, colObj, objectIndex); + } } + void BulletMJCFImporter::setBodyUniqueId(int bodyId) { - + m_data->m_activeBodyUniqueId = bodyId; } int BulletMJCFImporter::getBodyUniqueId() const { - return 0; + b3Assert(m_data->m_activeBodyUniqueId != -1); + return m_data->m_activeBodyUniqueId; } - static btCollisionShape* MjcfCreateConvexHullFromShapes(std::vector& shapes, const btVector3& geomScale, btScalar collisionMargin) { btCompoundShape* compound = new btCompoundShape(); @@ -1496,132 +1513,87 @@ class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIn } case URDF_GEOM_MESH: { - ////////////////////// - if (1) - { - if (col->m_geometry.m_meshFileName.length()) + GLInstanceGraphicsShape* glmesh = 0; + switch (col->m_geometry.m_meshFileType) { - const char* filename = col->m_geometry.m_meshFileName.c_str(); - //b3Printf("mesh->filename=%s\n",filename); - char fullPath[1024]; - int fileType = 0; - sprintf(fullPath,"%s%s",pathPrefix,filename); - b3FileUtils::toLower(fullPath); - char tmpPathPrefix[1024]; - int maxPathLen = 1024; - b3FileUtils::extractPath(filename,tmpPathPrefix,maxPathLen); - - char collisionPathPrefix[1024]; - sprintf(collisionPathPrefix,"%s%s",pathPrefix,tmpPathPrefix); - - if (strstr(fullPath,".stl")) + case UrdfGeometry::FILE_OBJ: { - fileType = MJCF_FILE_STL; + if (col->m_flags & URDF_FORCE_CONCAVE_TRIMESH) + { + glmesh = LoadMeshFromObj(col->m_geometry.m_meshFileName.c_str(), 0); + } + else + { + std::vector shapes; + std::string err = tinyobj::LoadObj(shapes, col->m_geometry.m_meshFileName.c_str()); + //create a convex hull for each shape, and store it in a btCompoundShape + + childShape = MjcfCreateConvexHullFromShapes(shapes, col->m_geometry.m_meshScale, m_data->m_defaultCollisionMargin); + + } + break; } - if (strstr(fullPath,".obj")) - { - fileType = MJCF_FILE_OBJ; - } - - sprintf(fullPath,"%s%s",pathPrefix,filename); - FILE* f = fopen(fullPath,"rb"); - if (f) + case UrdfGeometry::FILE_STL: { - fclose(f); - GLInstanceGraphicsShape* glmesh = 0; - - - switch (fileType) - { - case MJCF_FILE_OBJ: - { - if (col->m_flags & URDF_FORCE_CONCAVE_TRIMESH) - { - glmesh = LoadMeshFromObj(fullPath, collisionPathPrefix); - } - else - { - std::vector shapes; - std::string err = tinyobj::LoadObj(shapes, fullPath, collisionPathPrefix); - //create a convex hull for each shape, and store it in a btCompoundShape + glmesh = LoadMeshFromSTL(col->m_geometry.m_meshFileName.c_str()); + break; + } + default: + b3Warning("%s: Unsupported file type in Collision: %s (maybe .dae?)\n", col->m_sourceFileLocation.c_str(), col->m_geometry.m_meshFileType); + } - childShape = MjcfCreateConvexHullFromShapes(shapes, col->m_geometry.m_meshScale, m_data->m_defaultCollisionMargin); - - } - break; - } - case MJCF_FILE_STL: - { - glmesh = LoadMeshFromSTL(fullPath); - break; - } - - default: - { - b3Warning("Unsupported file type in Collision: %s\n",fullPath); - - } - } - + if (childShape) + { + // okay! + } + else if (!glmesh || glmesh->m_numvertices<=0) + { + b3Warning("%s: cannot extract anything useful from mesh '%s'\n", col->m_sourceFileLocation.c_str(), col->m_geometry.m_meshFileName.c_str()); + } + else + { + //b3Printf("extracted %d verticed from STL file %s\n", glmesh->m_numvertices,fullPath); + //int shapeId = m_glApp->m_instancingRenderer->registerShape(&gvertices[0].pos[0],gvertices.size(),&indices[0],indices.size()); + //convex->setUserIndex(shapeId); + btAlignedObjectArray convertedVerts; + convertedVerts.reserve(glmesh->m_numvertices); + for (int i=0;im_numvertices;i++) + { + convertedVerts.push_back(btVector3( + glmesh->m_vertices->at(i).xyzw[0]*col->m_geometry.m_meshScale[0], + glmesh->m_vertices->at(i).xyzw[1]*col->m_geometry.m_meshScale[1], + glmesh->m_vertices->at(i).xyzw[2]*col->m_geometry.m_meshScale[2])); + } - if (!childShape && glmesh && (glmesh->m_numvertices>0)) + if (col->m_flags & URDF_FORCE_CONCAVE_TRIMESH) + { + + btTriangleMesh* meshInterface = new btTriangleMesh(); + for (int i=0;im_numIndices/3;i++) { - //b3Printf("extracted %d verticed from STL file %s\n", glmesh->m_numvertices,fullPath); - //int shapeId = m_glApp->m_instancingRenderer->registerShape(&gvertices[0].pos[0],gvertices.size(),&indices[0],indices.size()); - //convex->setUserIndex(shapeId); - btAlignedObjectArray convertedVerts; - convertedVerts.reserve(glmesh->m_numvertices); - for (int i=0;im_numvertices;i++) - { - convertedVerts.push_back(btVector3( - glmesh->m_vertices->at(i).xyzw[0]*col->m_geometry.m_meshScale[0], - glmesh->m_vertices->at(i).xyzw[1]*col->m_geometry.m_meshScale[1], - glmesh->m_vertices->at(i).xyzw[2]*col->m_geometry.m_meshScale[2])); - } - - if (col->m_flags & URDF_FORCE_CONCAVE_TRIMESH) - { - - btTriangleMesh* meshInterface = new btTriangleMesh(); - for (int i=0;im_numIndices/3;i++) - { - float* v0 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3)).xyzw; - float* v1 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+1)).xyzw; - float* v2 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+2)).xyzw; - meshInterface->addTriangle(btVector3(v0[0],v0[1],v0[2]), - btVector3(v1[0],v1[1],v1[2]), - btVector3(v2[0],v2[1],v2[2])); - } - - btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface,true,true); - childShape = trimesh; - } else - { - btConvexHullShape* convexHull = new btConvexHullShape(&convertedVerts[0].getX(), convertedVerts.size(), sizeof(btVector3)); - convexHull->optimizeConvexHull(); - //convexHull->initializePolyhedralFeatures(); - convexHull->setMargin(m_data->m_defaultCollisionMargin); - childShape = convexHull; - } - } else - { - b3Warning("issue extracting mesh from STL file %s\n", fullPath); + float* v0 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3)).xyzw; + float* v1 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+1)).xyzw; + float* v2 = glmesh->m_vertices->at(glmesh->m_indices->at(i*3+2)).xyzw; + meshInterface->addTriangle(btVector3(v0[0],v0[1],v0[2]), + btVector3(v1[0],v1[1],v1[2]), + btVector3(v2[0],v2[1],v2[2])); } - delete glmesh; - + btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface,true,true); + childShape = trimesh; } else { - b3Warning("mesh geometry not found %s\n",fullPath); + btConvexHullShape* convexHull = new btConvexHullShape(&convertedVerts[0].getX(), convertedVerts.size(), sizeof(btVector3)); + convexHull->optimizeConvexHull(); + //convexHull->initializePolyhedralFeatures(); + convexHull->setMargin(m_data->m_defaultCollisionMargin); + childShape = convexHull; } - } - } - ////////////////////// + delete glmesh; break; } - case URDF_GEOM_CAPSULE: { //todo: convert fromto to btCapsuleShape + local btTransform @@ -1636,7 +1608,7 @@ class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIn btVector3 fromto[2] = {f,t}; btScalar radii[2] = {btScalar(col->m_geometry.m_capsuleRadius) ,btScalar(col->m_geometry.m_capsuleRadius)}; - + btMultiSphereShape* ms = new btMultiSphereShape(fromto,radii,2); childShape = ms; } else @@ -1647,11 +1619,8 @@ class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIn } break; } - default: - { + } // switch geom - } - } if (childShape) { m_data->m_allocatedCollisionShapes.push_back(childShape); diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h index f1b439690..a719c984e 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h @@ -18,9 +18,8 @@ class BulletMJCFImporter : public URDFImporterInterface { struct BulletMJCFImporterInternalData* m_data; - public: - BulletMJCFImporter(struct GUIHelperInterface* helper); + BulletMJCFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter); virtual ~BulletMJCFImporter(); virtual bool parseMJCFString(const char* xmlString, MJCFErrorLogger* logger); @@ -66,7 +65,7 @@ public: virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const; - virtual void convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const; + virtual void convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const; virtual void setBodyUniqueId(int bodyId); virtual int getBodyUniqueId() const; diff --git a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp index 79fff963f..b5e8cda6c 100644 --- a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp +++ b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp @@ -188,12 +188,12 @@ void ImportMJCFSetup::initPhysics() m_filterCallback->m_filterMode = FILTER_GROUPAMASKB_OR_GROUPBMASKA2; //m_dynamicsWorld->getSolverInfo().m_numIterations = 100; - m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); - m_dynamicsWorld->getDebugDrawer()->setDebugMode( - btIDebugDraw::DBG_DrawConstraints - +btIDebugDraw::DBG_DrawContactPoints - +btIDebugDraw::DBG_DrawAabb - );//+btIDebugDraw::DBG_DrawConstraintLimits); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + m_dynamicsWorld->getDebugDrawer()->setDebugMode( + btIDebugDraw::DBG_DrawConstraints + +btIDebugDraw::DBG_DrawContactPoints + +btIDebugDraw::DBG_DrawAabb + );//+btIDebugDraw::DBG_DrawConstraintLimits); if (m_guiHelper->getParameterInterface()) @@ -203,20 +203,23 @@ void ImportMJCFSetup::initPhysics() slider.m_maxVal = 10; m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); } - - BulletMJCFImporter importer(m_guiHelper); + + BulletMJCFImporter importer(m_guiHelper, 0); MyMJCFLogger logger; bool result = importer.loadMJCF(m_fileName,&logger); if (result) { - btTransform rootTrans; - rootTrans.setIdentity(); - - for (int m =0; mregisterNameForPointer(name->c_str(),name->c_str()); #endif//TEST_MULTIBODY_SERIALIZATION @@ -287,10 +289,11 @@ void ImportMJCFSetup::initPhysics() m_data->m_numMotors++; } } - } + } else { + // not multibody if (1) { //create motors for each generic joint diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index ae3364334..2a60cb197 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -75,16 +75,6 @@ void BulletURDFImporter::printTree() // btAssert(0); } - -enum MyFileType -{ - FILE_STL=1, - FILE_COLLADA=2, - FILE_OBJ=3, -}; - - - BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter) { m_data = new BulletURDFInternalData; @@ -624,7 +614,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co GLInstanceGraphicsShape* glmesh = 0; switch (collision->m_geometry.m_meshFileType) { - case FILE_OBJ: + case UrdfGeometry::FILE_OBJ: if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH) { glmesh = LoadMeshFromObj(collision->m_geometry.m_meshFileName.c_str(), 0); @@ -640,11 +630,11 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co } break; - case FILE_STL: + case UrdfGeometry::FILE_STL: glmesh = LoadMeshFromSTL(collision->m_geometry.m_meshFileName.c_str()); break; - case FILE_COLLADA: + case UrdfGeometry::FILE_COLLADA: { btAlignedObjectArray visualShapes; btAlignedObjectArray visualShapeInstances; @@ -833,7 +823,7 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha { switch (visual->m_geometry.m_meshFileType) { - case FILE_OBJ: + case UrdfGeometry::FILE_OBJ: { b3ImportMeshData meshData; if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData)) @@ -852,13 +842,13 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha break; } - case FILE_STL: + case UrdfGeometry::FILE_STL: { glmesh = LoadMeshFromSTL(visual->m_geometry.m_meshFileName.c_str()); break; } - case FILE_COLLADA: + case UrdfGeometry::FILE_COLLADA: { btAlignedObjectArray visualShapes; btAlignedObjectArray visualShapeInstances; @@ -1128,15 +1118,17 @@ bool BulletURDFImporter::getLinkContactInfo(int linkIndex, URDFLinkContactInfo& return false; } -void BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionObject* colObj, int bodyUniqueId) const +void BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionObject* colObj, int bodyUniqueId) const { - if (m_data->m_customVisualShapesConverter) { const UrdfModel& model = m_data->m_urdfParser.getModel(); - m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, model, colObj, bodyUniqueId); + UrdfLink*const* linkPtr = model.m_links.getAtIndex(urdfIndex); + if (linkPtr) + { + m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, *linkPtr, &model, colObj, bodyUniqueId); + } } - } int BulletURDFImporter::getNumAllocatedCollisionShapes() const diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h index 26b5a66e2..2ceb8e0d7 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.h @@ -51,7 +51,7 @@ public: virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const; - virtual void convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int bodyUniqueId) const; + virtual void convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int bodyUniqueId) const; ///todo(erwincoumans) refactor this convertLinkCollisionShapes/memory allocation diff --git a/examples/Importers/ImportURDFDemo/LinkVisualShapesConverter.h b/examples/Importers/ImportURDFDemo/LinkVisualShapesConverter.h index 814838ced..8f3d3c411 100644 --- a/examples/Importers/ImportURDFDemo/LinkVisualShapesConverter.h +++ b/examples/Importers/ImportURDFDemo/LinkVisualShapesConverter.h @@ -1,9 +1,14 @@ #ifndef LINK_VISUAL_SHAPES_CONVERTER_H #define LINK_VISUAL_SHAPES_CONVERTER_H +struct UrdfLink; +struct UrdfModel; +class btTransform; +class btCollisionObject; + struct LinkVisualShapesConverter { - virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const class btTransform& localInertiaFrame, const struct UrdfModel& model, class btCollisionObject* colObj, int objectIndex)=0; + virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, class btCollisionObject* colShape, int objectIndex) =0; }; #endif //LINK_VISUAL_SHAPES_CONVERTER_H diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index 30f35963a..a99477d93 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -311,7 +311,7 @@ void ConvertURDF2BulletInternal( - //untested: u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,body); + //untested: u2b.convertLinkVisualShapes2(linkIndex,urdfLinkIndex,pathPrefix,localInertialFrame,body); } else { if (cache.m_bulletMultiBody==0) @@ -469,8 +469,8 @@ void ConvertURDF2BulletInternal( btVector4 color = selectColor2();//(0.0,0.0,0.5); u2b.getLinkColor(urdfLinkIndex,color); creation.createCollisionObjectGraphicsInstance(urdfLinkIndex,col,color); - - u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,col, u2b.getBodyUniqueId()); + + u2b.convertLinkVisualShapes2(mbLinkIndex, urdfLinkIndex, pathPrefix, localInertialFrame,col, u2b.getBodyUniqueId()); URDFLinkContactInfo contactInfo; u2b.getLinkContactInfo(urdfLinkIndex,contactInfo); @@ -487,7 +487,7 @@ void ConvertURDF2BulletInternal( } } else { - //u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,compoundShape); + //u2b.convertLinkVisualShapes2(urdfLinkIndex,urdfIndex,pathPrefix,localInertialFrame,compoundShape); } } diff --git a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h index 6d4c98e57..427f98b3b 100644 --- a/examples/Importers/ImportURDFDemo/URDFImporterInterface.h +++ b/examples/Importers/ImportURDFDemo/URDFImporterInterface.h @@ -49,7 +49,7 @@ public: ///quick hack: need to rethink the API/dependencies of this virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const { return -1;} - virtual void convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const { } + virtual void convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const { } virtual void setBodyUniqueId(int bodyId) {} virtual int getBodyUniqueId() const { return 0;} diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 505e2658f..6c2e0e090 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -85,26 +85,23 @@ bool findExistingMeshFile(const std::string& urdf_path, std::string fn, const std::string& error_message_prefix, std::string* out_found_filename, int* out_type); // intended to fill UrdfGeometry::m_meshFileName and Type, but can be used elsewhere -struct UrdfVisual +struct UrdfShape { std::string m_sourceFileLocation; btTransform m_linkLocalFrame; UrdfGeometry m_geometry; std::string m_name; +}; + +struct UrdfVisual: UrdfShape +{ std::string m_materialName; bool m_hasLocalMaterial; UrdfMaterial m_localMaterial; }; - - - -struct UrdfCollision +struct UrdfCollision: UrdfShape { - std::string m_sourceFileLocation; - btTransform m_linkLocalFrame; - UrdfGeometry m_geometry; - std::string m_name; int m_flags; int m_collisionGroup; int m_collisionMask; diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 0989a4962..5ca0f35a2 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -1067,4 +1067,4 @@ void PhysicsDirect::setTimeOut(double timeOutInSeconds) double PhysicsDirect::getTimeOut() const { return m_data->m_timeOutInSeconds; -} \ No newline at end of file +} diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index c5a48efaa..077dba179 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1497,7 +1497,7 @@ bool PhysicsServerCommandProcessor::loadMjcf(const char* fileName, char* bufferS m_data->m_sdfRecentLoadedBodies.clear(); - BulletMJCFImporter u2b(m_data->m_guiHelper); //, &m_data->m_visualConverter + BulletMJCFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter); bool useFixedBase = false; MyMJCFLogger2 logger; @@ -4610,20 +4610,19 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm int remain = totalNumVisualShapes - clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex; int shapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex; - m_data->m_visualConverter.getVisualShapesData(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId, + int success = m_data->m_visualConverter.getVisualShapesData(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId, shapeIndex, visualShapeStoragePtr); - - - //m_visualConverter - serverCmd.m_sendVisualShapeArgs.m_numRemainingVisualShapes = remain-1; - serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied = 1; - serverCmd.m_sendVisualShapeArgs.m_startingVisualShapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex; - serverCmd.m_sendVisualShapeArgs.m_bodyUniqueId = clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId; - serverCmd.m_numDataStreamBytes = sizeof(b3VisualShapeData)*serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied; - serverCmd.m_type =CMD_VISUAL_SHAPE_INFO_COMPLETED; - hasStatus = true; - break; + if (success) { + serverCmd.m_sendVisualShapeArgs.m_numRemainingVisualShapes = remain-1; + serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied = 1; + serverCmd.m_sendVisualShapeArgs.m_startingVisualShapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex; + serverCmd.m_sendVisualShapeArgs.m_bodyUniqueId = clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId; + serverCmd.m_numDataStreamBytes = sizeof(b3VisualShapeData)*serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied; + serverCmd.m_type = CMD_VISUAL_SHAPE_INFO_COMPLETED; + } + hasStatus = true; + break; } case CMD_UPDATE_VISUAL_SHAPE: { diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index d2c3b79bd..58fd7f13e 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -170,7 +170,7 @@ void TinyRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff m_data->m_hasLightSpecularCoeff = true; } -void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut) +void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut) { visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type; @@ -211,6 +211,38 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref convexColShape = cylZShape; break; } + case URDF_GEOM_CAPSULE: + { + btVector3 p1 = visual->m_geometry.m_capsuleFrom; + btVector3 p2 = visual->m_geometry.m_capsuleTo; + btVector3 v = p2 - p1; + btVector3 center = (p2 + p1) * 0.5; + btScalar rad = visual->m_geometry.m_capsuleRadius; + btVector3 up_vector(0,0,1); + btVector3 dir = v.normalized(); + btVector3 axis = dir.cross(up_vector); + if (axis.fuzzyZero()) + { + axis = btVector3(0,0,1); + } + else + { + axis.normalize(); + } + btQuaternion q(axis, -acos(dir.dot(up_vector))); + btTransform capsule_orient(q, center); + btTransform tr = visual->m_linkLocalFrame * capsule_orient; + visualShapeOut.m_localVisualFrame[0] = tr.getOrigin()[0]; + visualShapeOut.m_localVisualFrame[1] = tr.getOrigin()[1]; + visualShapeOut.m_localVisualFrame[2] = tr.getOrigin()[2]; + visualShapeOut.m_localVisualFrame[3] = tr.getRotation()[0]; + visualShapeOut.m_localVisualFrame[4] = tr.getRotation()[1]; + visualShapeOut.m_localVisualFrame[5] = tr.getRotation()[2]; + visualShapeOut.m_localVisualFrame[6] = tr.getRotation()[3]; + visualShapeOut.m_dimensions[0] = v.length(); + visualShapeOut.m_dimensions[1] = rad; + break; + } case URDF_GEOM_BOX: { visualShapeOut.m_dimensions[0] = visual->m_geometry.m_boxSize[0]; @@ -228,7 +260,7 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref case URDF_GEOM_SPHERE: { visualShapeOut.m_dimensions[0] = visual->m_geometry.m_sphereRadius; - + btScalar radius = visual->m_geometry.m_sphereRadius; btSphereShape* sphereShape = new btSphereShape(radius); convexColShape = sphereShape; @@ -244,14 +276,6 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref visualShapeOut.m_dimensions[1] = visual->m_geometry.m_meshScale[1]; visualShapeOut.m_dimensions[2] = visual->m_geometry.m_meshScale[2]; - visualShapeOut.m_localVisualFrame[0] = visual->m_linkLocalFrame.getOrigin()[0]; - visualShapeOut.m_localVisualFrame[1] = visual->m_linkLocalFrame.getOrigin()[1]; - visualShapeOut.m_localVisualFrame[2] = visual->m_linkLocalFrame.getOrigin()[2]; - visualShapeOut.m_localVisualFrame[3] = visual->m_linkLocalFrame.getRotation()[0]; - visualShapeOut.m_localVisualFrame[4] = visual->m_linkLocalFrame.getRotation()[1]; - visualShapeOut.m_localVisualFrame[5] = visual->m_linkLocalFrame.getRotation()[2]; - visualShapeOut.m_localVisualFrame[6] = visual->m_linkLocalFrame.getRotation()[3]; - switch (visual->m_geometry.m_meshFileType) { case UrdfGeometry::FILE_OBJ: @@ -467,17 +491,30 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref -void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionObject* colObj, int bodyUniqueId) +void TinyRendererVisualShapeConverter::convertVisualShapes( + int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, + const UrdfLink* linkPtr, const UrdfModel* model, + class btCollisionObject* colObj, int bodyUniqueId) { - - - UrdfLink* const* linkPtr = model.m_links.getAtIndex(linkIndex); + btAssert(linkPtr); // TODO: remove if (not doing it now, because diff will be 50+ lines) if (linkPtr) { + const btArray* shapeArray; + bool useVisual; + int cnt = 0; + if (linkPtr->m_visualArray.size() > 0) + { + useVisual = true; + cnt = linkPtr->m_visualArray.size(); + } + else + { + // We have to see something, take collision shape. Useful for MuJoCo xml, where there is not visual shape. + useVisual = false; + cnt = linkPtr->m_collisionArray.size(); + } - const UrdfLink* link = *linkPtr; - - for (int v1 = 0; v1 < link->m_visualArray.size();v1++) + for (int v1=0; v1 textures; btAlignedObjectArray vertices; @@ -485,20 +522,28 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const btTransform startTrans; startTrans.setIdentity(); //int graphicsIndex = -1; - const UrdfVisual& vis = link->m_visualArray[v1]; - btTransform childTrans = vis.m_linkLocalFrame; - btHashString matName(vis.m_materialName.c_str()); - UrdfMaterial *const * matPtr = model.m_materials[matName]; - - float rgbaColor[4] = {1,1,1,1}; - - if (matPtr) + const UrdfShape* vis; + if (useVisual) { + vis = &linkPtr->m_visualArray[v1]; + } else { + vis = &linkPtr->m_collisionArray[v1]; + } + btTransform childTrans = vis->m_linkLocalFrame; + + float rgbaColor[4] = {1,1,1,1}; + if (model && useVisual) { - UrdfMaterial *const mat = *matPtr; - for (int i=0;i<4;i++) - rgbaColor[i] = mat->m_rgbaColor[i]; - //printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]); - //m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor); + btHashString matName(linkPtr->m_visualArray[v1].m_materialName.c_str()); + UrdfMaterial*const* matPtr = model->m_materials[matName]; + if (matPtr) + { + for (int i=0; i<4; i++) + { + rgbaColor[i] = (*matPtr)->m_rgbaColor[i]; + } + //printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]); + //m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor); + } } TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[colObj]; @@ -513,19 +558,19 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const b3VisualShapeData visualShape; visualShape.m_objectUniqueId = bodyUniqueId; visualShape.m_linkIndex = linkIndex; - visualShape.m_localVisualFrame[0] = vis.m_linkLocalFrame.getOrigin()[0]; - visualShape.m_localVisualFrame[1] = vis.m_linkLocalFrame.getOrigin()[1]; - visualShape.m_localVisualFrame[2] = vis.m_linkLocalFrame.getOrigin()[2]; - visualShape.m_localVisualFrame[3] = vis.m_linkLocalFrame.getRotation()[0]; - visualShape.m_localVisualFrame[4] = vis.m_linkLocalFrame.getRotation()[1]; - visualShape.m_localVisualFrame[5] = vis.m_linkLocalFrame.getRotation()[2]; - visualShape.m_localVisualFrame[6] = vis.m_linkLocalFrame.getRotation()[3]; - visualShape.m_rgbaColor[0] = rgbaColor[0]; - visualShape.m_rgbaColor[1] = rgbaColor[1]; - visualShape.m_rgbaColor[2] = rgbaColor[2]; - visualShape.m_rgbaColor[3] = rgbaColor[3]; + visualShape.m_localVisualFrame[0] = vis->m_linkLocalFrame.getOrigin()[0]; + visualShape.m_localVisualFrame[1] = vis->m_linkLocalFrame.getOrigin()[1]; + visualShape.m_localVisualFrame[2] = vis->m_linkLocalFrame.getOrigin()[2]; + visualShape.m_localVisualFrame[3] = vis->m_linkLocalFrame.getRotation()[0]; + visualShape.m_localVisualFrame[4] = vis->m_linkLocalFrame.getRotation()[1]; + visualShape.m_localVisualFrame[5] = vis->m_linkLocalFrame.getRotation()[2]; + visualShape.m_localVisualFrame[6] = vis->m_linkLocalFrame.getRotation()[3]; + visualShape.m_rgbaColor[0] = rgbaColor[0]; + visualShape.m_rgbaColor[1] = rgbaColor[1]; + visualShape.m_rgbaColor[2] = rgbaColor[2]; + visualShape.m_rgbaColor[3] = rgbaColor[3]; - convertURDFToVisualShape(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices,textures, visualShape); + convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices,textures, visualShape); m_data->m_visualShapes.push_back(visualShape); if (vertices.size() && indices.size()) diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index 78b4c62d6..e9e60948f 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -16,7 +16,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter virtual ~TinyRendererVisualShapeConverter(); - virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionObject* colShape, int objectIndex); + virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, class btCollisionObject* colShape, int objectIndex); virtual int getNumVisualShapes(int bodyUniqueId); From fa7397cc922e3901fe3163333abcb77474cab237 Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Fri, 17 Mar 2017 02:10:27 +0300 Subject: [PATCH 54/66] Rename *.STL to *.stl for case-sensitive filesystems --- data/MPL/mesh/{index0.STL => index0.stl} | Bin .../{index0_collision.STL => index0_collision.stl} | Bin data/MPL/mesh/{index1.STL => index1.stl} | Bin .../{index1_collision.STL => index1_collision.stl} | Bin data/MPL/mesh/{index2.STL => index2.stl} | Bin .../{index2_collision.STL => index2_collision.stl} | Bin data/MPL/mesh/{index3.STL => index3.stl} | Bin .../{index3_collision.STL => index3_collision.stl} | Bin data/MPL/mesh/{middle0.STL => middle0.stl} | Bin ...{middle0_collision.STL => middle0_collision.stl} | Bin data/MPL/mesh/{middle1.STL => middle1.stl} | Bin ...{middle1_collision.STL => middle1_collision.stl} | Bin data/MPL/mesh/{middle2.STL => middle2.stl} | Bin ...{middle2_collision.STL => middle2_collision.stl} | Bin data/MPL/mesh/{middle3.STL => middle3.stl} | Bin ...{middle3_collision.STL => middle3_collision.stl} | Bin data/MPL/mesh/{palm.STL => palm.stl} | Bin .../mesh/{palm_collision.STL => palm_collision.stl} | Bin data/MPL/mesh/{pinky0.STL => pinky0.stl} | Bin .../{pinky0_collision.STL => pinky0_collision.stl} | Bin data/MPL/mesh/{pinky1.STL => pinky1.stl} | Bin .../{pinky1_collision.STL => pinky1_collision.stl} | Bin data/MPL/mesh/{pinky2.STL => pinky2.stl} | Bin .../{pinky2_collision.STL => pinky2_collision.stl} | Bin data/MPL/mesh/{pinky3.STL => pinky3.stl} | Bin .../{pinky3_collision.STL => pinky3_collision.stl} | Bin data/MPL/mesh/{ring0.STL => ring0.stl} | Bin .../{ring0_collision.STL => ring0_collision.stl} | Bin data/MPL/mesh/{ring1.STL => ring1.stl} | Bin .../{ring1_collision.STL => ring1_collision.stl} | Bin data/MPL/mesh/{ring2.STL => ring2.stl} | Bin .../{ring2_collision.STL => ring2_collision.stl} | Bin data/MPL/mesh/{ring3.STL => ring3.stl} | Bin .../{ring3_collision.STL => ring3_collision.stl} | Bin data/MPL/mesh/{thumb0.STL => thumb0.stl} | Bin .../{thumb0_collision.STL => thumb0_collision.stl} | Bin data/MPL/mesh/{thumb1.STL => thumb1.stl} | Bin .../{thumb1_collision.STL => thumb1_collision.stl} | Bin data/MPL/mesh/{thumb2.STL => thumb2.stl} | Bin .../{thumb2_collision.STL => thumb2_collision.stl} | Bin data/MPL/mesh/{thumb3.STL => thumb3.stl} | Bin .../{thumb3_collision.STL => thumb3_collision.stl} | Bin data/MPL/mesh/{wristx.STL => wristx.stl} | Bin .../{wristx_collision.STL => wristx_collision.stl} | Bin data/MPL/mesh/{wristy.STL => wristy.stl} | Bin .../{wristy_collision.STL => wristy_collision.stl} | Bin data/MPL/mesh/{wristz.STL => wristz.stl} | Bin .../{wristz_collision.STL => wristz_collision.stl} | Bin 48 files changed, 0 insertions(+), 0 deletions(-) rename data/MPL/mesh/{index0.STL => index0.stl} (100%) rename data/MPL/mesh/{index0_collision.STL => index0_collision.stl} (100%) rename data/MPL/mesh/{index1.STL => index1.stl} (100%) rename data/MPL/mesh/{index1_collision.STL => index1_collision.stl} (100%) rename data/MPL/mesh/{index2.STL => index2.stl} (100%) rename data/MPL/mesh/{index2_collision.STL => index2_collision.stl} (100%) rename data/MPL/mesh/{index3.STL => index3.stl} (100%) rename data/MPL/mesh/{index3_collision.STL => index3_collision.stl} (100%) rename data/MPL/mesh/{middle0.STL => middle0.stl} (100%) rename data/MPL/mesh/{middle0_collision.STL => middle0_collision.stl} (100%) rename data/MPL/mesh/{middle1.STL => middle1.stl} (100%) rename data/MPL/mesh/{middle1_collision.STL => middle1_collision.stl} (100%) rename data/MPL/mesh/{middle2.STL => middle2.stl} (100%) rename data/MPL/mesh/{middle2_collision.STL => middle2_collision.stl} (100%) rename data/MPL/mesh/{middle3.STL => middle3.stl} (100%) rename data/MPL/mesh/{middle3_collision.STL => middle3_collision.stl} (100%) rename data/MPL/mesh/{palm.STL => palm.stl} (100%) rename data/MPL/mesh/{palm_collision.STL => palm_collision.stl} (100%) rename data/MPL/mesh/{pinky0.STL => pinky0.stl} (100%) rename data/MPL/mesh/{pinky0_collision.STL => pinky0_collision.stl} (100%) rename data/MPL/mesh/{pinky1.STL => pinky1.stl} (100%) rename data/MPL/mesh/{pinky1_collision.STL => pinky1_collision.stl} (100%) rename data/MPL/mesh/{pinky2.STL => pinky2.stl} (100%) rename data/MPL/mesh/{pinky2_collision.STL => pinky2_collision.stl} (100%) rename data/MPL/mesh/{pinky3.STL => pinky3.stl} (100%) rename data/MPL/mesh/{pinky3_collision.STL => pinky3_collision.stl} (100%) rename data/MPL/mesh/{ring0.STL => ring0.stl} (100%) rename data/MPL/mesh/{ring0_collision.STL => ring0_collision.stl} (100%) rename data/MPL/mesh/{ring1.STL => ring1.stl} (100%) rename data/MPL/mesh/{ring1_collision.STL => ring1_collision.stl} (100%) rename data/MPL/mesh/{ring2.STL => ring2.stl} (100%) rename data/MPL/mesh/{ring2_collision.STL => ring2_collision.stl} (100%) rename data/MPL/mesh/{ring3.STL => ring3.stl} (100%) rename data/MPL/mesh/{ring3_collision.STL => ring3_collision.stl} (100%) rename data/MPL/mesh/{thumb0.STL => thumb0.stl} (100%) rename data/MPL/mesh/{thumb0_collision.STL => thumb0_collision.stl} (100%) rename data/MPL/mesh/{thumb1.STL => thumb1.stl} (100%) rename data/MPL/mesh/{thumb1_collision.STL => thumb1_collision.stl} (100%) rename data/MPL/mesh/{thumb2.STL => thumb2.stl} (100%) rename data/MPL/mesh/{thumb2_collision.STL => thumb2_collision.stl} (100%) rename data/MPL/mesh/{thumb3.STL => thumb3.stl} (100%) rename data/MPL/mesh/{thumb3_collision.STL => thumb3_collision.stl} (100%) rename data/MPL/mesh/{wristx.STL => wristx.stl} (100%) rename data/MPL/mesh/{wristx_collision.STL => wristx_collision.stl} (100%) rename data/MPL/mesh/{wristy.STL => wristy.stl} (100%) rename data/MPL/mesh/{wristy_collision.STL => wristy_collision.stl} (100%) rename data/MPL/mesh/{wristz.STL => wristz.stl} (100%) rename data/MPL/mesh/{wristz_collision.STL => wristz_collision.stl} (100%) diff --git a/data/MPL/mesh/index0.STL b/data/MPL/mesh/index0.stl similarity index 100% rename from data/MPL/mesh/index0.STL rename to data/MPL/mesh/index0.stl diff --git a/data/MPL/mesh/index0_collision.STL b/data/MPL/mesh/index0_collision.stl similarity index 100% rename from data/MPL/mesh/index0_collision.STL rename to data/MPL/mesh/index0_collision.stl diff --git a/data/MPL/mesh/index1.STL b/data/MPL/mesh/index1.stl similarity index 100% rename from data/MPL/mesh/index1.STL rename to data/MPL/mesh/index1.stl diff --git a/data/MPL/mesh/index1_collision.STL b/data/MPL/mesh/index1_collision.stl similarity index 100% rename from data/MPL/mesh/index1_collision.STL rename to data/MPL/mesh/index1_collision.stl diff --git a/data/MPL/mesh/index2.STL b/data/MPL/mesh/index2.stl similarity index 100% rename from data/MPL/mesh/index2.STL rename to data/MPL/mesh/index2.stl diff --git a/data/MPL/mesh/index2_collision.STL b/data/MPL/mesh/index2_collision.stl similarity index 100% rename from data/MPL/mesh/index2_collision.STL rename to data/MPL/mesh/index2_collision.stl diff --git a/data/MPL/mesh/index3.STL b/data/MPL/mesh/index3.stl similarity index 100% rename from data/MPL/mesh/index3.STL rename to data/MPL/mesh/index3.stl diff --git a/data/MPL/mesh/index3_collision.STL b/data/MPL/mesh/index3_collision.stl similarity index 100% rename from data/MPL/mesh/index3_collision.STL rename to data/MPL/mesh/index3_collision.stl diff --git a/data/MPL/mesh/middle0.STL b/data/MPL/mesh/middle0.stl similarity index 100% rename from data/MPL/mesh/middle0.STL rename to data/MPL/mesh/middle0.stl diff --git a/data/MPL/mesh/middle0_collision.STL b/data/MPL/mesh/middle0_collision.stl similarity index 100% rename from data/MPL/mesh/middle0_collision.STL rename to data/MPL/mesh/middle0_collision.stl diff --git a/data/MPL/mesh/middle1.STL b/data/MPL/mesh/middle1.stl similarity index 100% rename from data/MPL/mesh/middle1.STL rename to data/MPL/mesh/middle1.stl diff --git a/data/MPL/mesh/middle1_collision.STL b/data/MPL/mesh/middle1_collision.stl similarity index 100% rename from data/MPL/mesh/middle1_collision.STL rename to data/MPL/mesh/middle1_collision.stl diff --git a/data/MPL/mesh/middle2.STL b/data/MPL/mesh/middle2.stl similarity index 100% rename from data/MPL/mesh/middle2.STL rename to data/MPL/mesh/middle2.stl diff --git a/data/MPL/mesh/middle2_collision.STL b/data/MPL/mesh/middle2_collision.stl similarity index 100% rename from data/MPL/mesh/middle2_collision.STL rename to data/MPL/mesh/middle2_collision.stl diff --git a/data/MPL/mesh/middle3.STL b/data/MPL/mesh/middle3.stl similarity index 100% rename from data/MPL/mesh/middle3.STL rename to data/MPL/mesh/middle3.stl diff --git a/data/MPL/mesh/middle3_collision.STL b/data/MPL/mesh/middle3_collision.stl similarity index 100% rename from data/MPL/mesh/middle3_collision.STL rename to data/MPL/mesh/middle3_collision.stl diff --git a/data/MPL/mesh/palm.STL b/data/MPL/mesh/palm.stl similarity index 100% rename from data/MPL/mesh/palm.STL rename to data/MPL/mesh/palm.stl diff --git a/data/MPL/mesh/palm_collision.STL b/data/MPL/mesh/palm_collision.stl similarity index 100% rename from data/MPL/mesh/palm_collision.STL rename to data/MPL/mesh/palm_collision.stl diff --git a/data/MPL/mesh/pinky0.STL b/data/MPL/mesh/pinky0.stl similarity index 100% rename from data/MPL/mesh/pinky0.STL rename to data/MPL/mesh/pinky0.stl diff --git a/data/MPL/mesh/pinky0_collision.STL b/data/MPL/mesh/pinky0_collision.stl similarity index 100% rename from data/MPL/mesh/pinky0_collision.STL rename to data/MPL/mesh/pinky0_collision.stl diff --git a/data/MPL/mesh/pinky1.STL b/data/MPL/mesh/pinky1.stl similarity index 100% rename from data/MPL/mesh/pinky1.STL rename to data/MPL/mesh/pinky1.stl diff --git a/data/MPL/mesh/pinky1_collision.STL b/data/MPL/mesh/pinky1_collision.stl similarity index 100% rename from data/MPL/mesh/pinky1_collision.STL rename to data/MPL/mesh/pinky1_collision.stl diff --git a/data/MPL/mesh/pinky2.STL b/data/MPL/mesh/pinky2.stl similarity index 100% rename from data/MPL/mesh/pinky2.STL rename to data/MPL/mesh/pinky2.stl diff --git a/data/MPL/mesh/pinky2_collision.STL b/data/MPL/mesh/pinky2_collision.stl similarity index 100% rename from data/MPL/mesh/pinky2_collision.STL rename to data/MPL/mesh/pinky2_collision.stl diff --git a/data/MPL/mesh/pinky3.STL b/data/MPL/mesh/pinky3.stl similarity index 100% rename from data/MPL/mesh/pinky3.STL rename to data/MPL/mesh/pinky3.stl diff --git a/data/MPL/mesh/pinky3_collision.STL b/data/MPL/mesh/pinky3_collision.stl similarity index 100% rename from data/MPL/mesh/pinky3_collision.STL rename to data/MPL/mesh/pinky3_collision.stl diff --git a/data/MPL/mesh/ring0.STL b/data/MPL/mesh/ring0.stl similarity index 100% rename from data/MPL/mesh/ring0.STL rename to data/MPL/mesh/ring0.stl diff --git a/data/MPL/mesh/ring0_collision.STL b/data/MPL/mesh/ring0_collision.stl similarity index 100% rename from data/MPL/mesh/ring0_collision.STL rename to data/MPL/mesh/ring0_collision.stl diff --git a/data/MPL/mesh/ring1.STL b/data/MPL/mesh/ring1.stl similarity index 100% rename from data/MPL/mesh/ring1.STL rename to data/MPL/mesh/ring1.stl diff --git a/data/MPL/mesh/ring1_collision.STL b/data/MPL/mesh/ring1_collision.stl similarity index 100% rename from data/MPL/mesh/ring1_collision.STL rename to data/MPL/mesh/ring1_collision.stl diff --git a/data/MPL/mesh/ring2.STL b/data/MPL/mesh/ring2.stl similarity index 100% rename from data/MPL/mesh/ring2.STL rename to data/MPL/mesh/ring2.stl diff --git a/data/MPL/mesh/ring2_collision.STL b/data/MPL/mesh/ring2_collision.stl similarity index 100% rename from data/MPL/mesh/ring2_collision.STL rename to data/MPL/mesh/ring2_collision.stl diff --git a/data/MPL/mesh/ring3.STL b/data/MPL/mesh/ring3.stl similarity index 100% rename from data/MPL/mesh/ring3.STL rename to data/MPL/mesh/ring3.stl diff --git a/data/MPL/mesh/ring3_collision.STL b/data/MPL/mesh/ring3_collision.stl similarity index 100% rename from data/MPL/mesh/ring3_collision.STL rename to data/MPL/mesh/ring3_collision.stl diff --git a/data/MPL/mesh/thumb0.STL b/data/MPL/mesh/thumb0.stl similarity index 100% rename from data/MPL/mesh/thumb0.STL rename to data/MPL/mesh/thumb0.stl diff --git a/data/MPL/mesh/thumb0_collision.STL b/data/MPL/mesh/thumb0_collision.stl similarity index 100% rename from data/MPL/mesh/thumb0_collision.STL rename to data/MPL/mesh/thumb0_collision.stl diff --git a/data/MPL/mesh/thumb1.STL b/data/MPL/mesh/thumb1.stl similarity index 100% rename from data/MPL/mesh/thumb1.STL rename to data/MPL/mesh/thumb1.stl diff --git a/data/MPL/mesh/thumb1_collision.STL b/data/MPL/mesh/thumb1_collision.stl similarity index 100% rename from data/MPL/mesh/thumb1_collision.STL rename to data/MPL/mesh/thumb1_collision.stl diff --git a/data/MPL/mesh/thumb2.STL b/data/MPL/mesh/thumb2.stl similarity index 100% rename from data/MPL/mesh/thumb2.STL rename to data/MPL/mesh/thumb2.stl diff --git a/data/MPL/mesh/thumb2_collision.STL b/data/MPL/mesh/thumb2_collision.stl similarity index 100% rename from data/MPL/mesh/thumb2_collision.STL rename to data/MPL/mesh/thumb2_collision.stl diff --git a/data/MPL/mesh/thumb3.STL b/data/MPL/mesh/thumb3.stl similarity index 100% rename from data/MPL/mesh/thumb3.STL rename to data/MPL/mesh/thumb3.stl diff --git a/data/MPL/mesh/thumb3_collision.STL b/data/MPL/mesh/thumb3_collision.stl similarity index 100% rename from data/MPL/mesh/thumb3_collision.STL rename to data/MPL/mesh/thumb3_collision.stl diff --git a/data/MPL/mesh/wristx.STL b/data/MPL/mesh/wristx.stl similarity index 100% rename from data/MPL/mesh/wristx.STL rename to data/MPL/mesh/wristx.stl diff --git a/data/MPL/mesh/wristx_collision.STL b/data/MPL/mesh/wristx_collision.stl similarity index 100% rename from data/MPL/mesh/wristx_collision.STL rename to data/MPL/mesh/wristx_collision.stl diff --git a/data/MPL/mesh/wristy.STL b/data/MPL/mesh/wristy.stl similarity index 100% rename from data/MPL/mesh/wristy.STL rename to data/MPL/mesh/wristy.stl diff --git a/data/MPL/mesh/wristy_collision.STL b/data/MPL/mesh/wristy_collision.stl similarity index 100% rename from data/MPL/mesh/wristy_collision.STL rename to data/MPL/mesh/wristy_collision.stl diff --git a/data/MPL/mesh/wristz.STL b/data/MPL/mesh/wristz.stl similarity index 100% rename from data/MPL/mesh/wristz.STL rename to data/MPL/mesh/wristz.stl diff --git a/data/MPL/mesh/wristz_collision.STL b/data/MPL/mesh/wristz_collision.stl similarity index 100% rename from data/MPL/mesh/wristz_collision.STL rename to data/MPL/mesh/wristz_collision.stl From 4526b0a94ab8df6d19d590929645c5a97f4d24ac Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Sat, 18 Mar 2017 04:10:07 +0300 Subject: [PATCH 55/66] MJCF: support for default joint limited="true" --- .../ImportMJCFDemo/BulletMJCFImporter.cpp | 96 ++++++++++++------- 1 file changed, 64 insertions(+), 32 deletions(-) diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index d1a051fc8..0fb20ad28 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -152,6 +152,9 @@ struct BulletMJCFImporterInternalData int m_defaultCollisionMask; btScalar m_defaultCollisionMargin; + // joint defaults + std::string m_defaultJointLimited; + //those collision shapes are deleted by caller (todo: make sure this happens!) btAlignedObjectArray m_allocatedCollisionShapes; @@ -243,6 +246,17 @@ struct BulletMJCFImporterInternalData { parseAssets(child_xml,logger); } + if (n=="joint") + { + // Other attributes here: + // armature="1" + // damping="1" + // limited="true" + if (const char* conTypeStr = child_xml->Attribute("limited")) + { + m_defaultJointLimited = child_xml->Attribute("limited"); + } + } if (n=="geom") { //contype, conaffinity @@ -366,39 +380,57 @@ struct BulletMJCFImporterInternalData bool isLimited = false; double range[2] = {1,0}; + std::string lim = m_defaultJointLimited; if (limitedStr) { - std::string lim = limitedStr; - if (lim=="true") - { - isLimited = true; - //parse the 'range' field - btArray pieces; - btArray sizes; - btAlignedObjectArray strArray; - urdfIsAnyOf(" ", strArray); - urdfStringSplit(pieces, rangeStr, strArray); - for (int i = 0; i < pieces.size(); ++i) - { - if (!pieces[i].empty()) - { - sizes.push_back(urdfLexicalCast(pieces[i].c_str())); - } - } - if (sizes.size()==2) - { - range[0] = sizes[0]; - range[1] = sizes[1]; - } else - { - logger->reportWarning("Expected range[2] in joint with limits"); - } - - } - } else - { -// logger->reportWarning("joint without limited field"); + lim = limitedStr; } + if (lim=="true") + { + isLimited = true; + //parse the 'range' field + btArray pieces; + btArray sizes; + btAlignedObjectArray strArray; + urdfIsAnyOf(" ", strArray); + urdfStringSplit(pieces, rangeStr, strArray); + for (int i = 0; i < pieces.size(); ++i) + { + if (!pieces[i].empty()) + { + sizes.push_back(urdfLexicalCast(pieces[i].c_str())); + } + } + if (sizes.size()==2) + { + // TODO angle units are in " + range[0] = sizes[0] * M_PI / 180; + range[1] = sizes[1] * M_PI / 180; + } else + { + logger->reportWarning("Expected range[2] in joint with limits"); + } + } + + // TODO armature : real, "0" Armature inertia (or rotor inertia) of all + // degrees of freedom created by this joint. These are constants added to the + // diagonal of the inertia matrix in generalized coordinates. They make the + // simulation more stable, and often increase physical realism. This is because + // when a motor is attached to the system with a transmission that amplifies + // the motor force by c, the inertia of the rotor (i.e. the moving part of the + // motor) is amplified by c*c. The same holds for gears in the early stages of + // planetary gear boxes. These extra inertias often dominate the inertias of + // the robot parts that are represented explicitly in the model, and the + // armature attribute is the way to model them. + + // TODO damping : real, "0" Damping applied to all degrees of + // freedom created by this joint. Unlike friction loss + // which is computed by the constraint solver, damping is + // simply a force linear in velocity. It is included in + // the passive forces. Despite this simplicity, larger + // damping values can make numerical integrators unstable, + // which is why our Euler integrator handles damping + // implicitly. See Integration in the Computation chapter. bool jointHandled = false; const UrdfLink* linkPtr = getLink(modelIndex,linkIndex); @@ -448,11 +480,11 @@ struct BulletMJCFImporterInternalData jointPtr->m_parentLinkToJointTransform = parentLinkToJointTransform; jointPtr->m_type = ejtype; int numJoints = m_models[modelIndex]->m_joints.size(); - + //range jointPtr->m_lowerLimit = range[0]; jointPtr->m_upperLimit = range[1]; - + if (nameStr) { jointPtr->m_name =nameStr; From 865d37fcb5ea26a9194f573f02746c01242a585a Mon Sep 17 00:00:00 2001 From: "Erwin Coumans (Google)" Date: Sat, 18 Mar 2017 18:32:21 +0000 Subject: [PATCH 56/66] add premake4_arm64 that works on NVIDIA TX2 --- build3/premake4_arm64 | Bin 0 -> 380192 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100755 build3/premake4_arm64 diff --git a/build3/premake4_arm64 b/build3/premake4_arm64 new file mode 100755 index 0000000000000000000000000000000000000000..3b7ee4ab50e6e9c2316475106228aec0ae2bdf4e GIT binary patch literal 380192 zcmbrn4SZD9wg0`(ObC&ngfJlpNM-^mM61Yqe9I)@OMSZ%QnhH!Oacf5fsm*uXeNPc z(b$%eC{|mU1Z~M&Td{>o+S^M2->!IX5!-5S@BbQtwpRLr?}>_ezQ1$kBnNcv^M5{1 z+VPyd&f0sgwf5R;t-ba>hlWe8y3}V`#{Kh|XN^je&kEZh=fB28UKnJT^`EerWwQA1 z7&F>rQr43&KmCPMckZ<_)wFxfa?p&QYliN9DS$8R+@!8!oDzLFe=dc(4p5?JVf}}{ zu>Iece&IZIug2!a`LAg0{I&DE^VgT!`0jP}V7q7%sjFL0bche`kneN zf8tHQu_^w>`ofe{4(np(*#8~4+OhyP_wD)x>hJ&dFDHdqPCd1ej=yk<4)^NH^W0@i zs?J@u;A_j4EWd5_*P_u?)r)6LJEv~NIp;a_t9{{KcFi~Jo-}T*h}2(zpI~~v#sB@! zj?SL<+NG=ZpFZueo?*Y}ZCx7WnIx`uhVV1ipoGctg?xc^lf!1{;0BrB`x?K={1B~~ z!cTwG_|4!qQw9Et`CY*8A{A19C8=weYbn1neslQg?-G8FCNl;$#F($Au2*oqI(6?} z{)wAw`OW25&Tk$+XJn1Jj{EEReUsmOemC;_7Qae<`it2Ab^fDqUBGWq3bur64Zmgl zZsoU}-wJ;EtL3-KzB8ttYvse6#{TZ6y`9(pansoE24)Q3dEI%(zBVO%Y~;E1!!Ega z=+j$1TRyC@zUkzZGh5a+|M$ad_k(}m(#)r`p6dPH%zf|Qb` zZpgkjHZkY=zy5ITDaj4li@p)fx#E|Pt}PA^efr{i9$x#iUku&&;wfDhop$f$)?2>* z^+IcW?-M`x)uyqTzKq_xo9l+PtbTm$xZ8LB*V?}gAGZFN53im3_u+?cfBU{8^B=un z*smUf&i`C~$ z)@D9k_;16Weme5)zU|w$wfuW=xZv~^GatCJ@b12UobveEzgC?5bY1wNwMRy_k7|DF z?_+nLnK$G8V9VFe`f$_QyT{xAN^dhyW5 z&yIO~L-zhf8?uAHIqBG>(;gT*^}DwX`}$8dWUs0}`_wBlZX34$8~cNItT?>#@xm9k zoqk)>$qzS{Z3|T`7<`#^+py2RH)dGbH^1HY?us9O^6jG!uf6B-1EY>y^ux7(&z{?R z`Fn2;d*-^w*KVZF>_u1R_}~4*u)&PMML#J%`6nH#uD3x?G!{8r%gmQ7<1d~x(2 z#}58u*lEw5?N$5Ks195-hk^se{<|~Nz@_`aeyo8T>F!s-YcV#OlPCVY?E7kXxAoQV z32ES)(zJh=4!^43>(lgmFb(`yY5Kh@4SaQ)emA9ozncdBXd1p&r-A=C4ZJZ8d`cSn zbJD=?OG9To4gOPU@b63mucw{iW|X=7dB-}sc3w8?tH!Z3O~3D@!QY$)KavK1UK+VQ zo<>hTNz=}rH1LCI=p2~_e@Gg77N>zPPt(pX(!kG7!`E-p;4e&rKP(MBW76RNYdSfk zX(uxcJx`~Bk4*!ACk;J62QEFFb%GwAmWG~fY1;ow8hA~bexFJMzc@|5Ur*D1c^do; zY1;pB8u>S-Y5$Ql_%Ek{|1wR#pQnLemIkiaMReG)+5oY2cY@^@^)2 z7c5-0@RlWY^$S;3Ts?c)iscI{qE*Wln##&sZe6jwvaUY5s=l()R9K1Zcv2x*Z;Z-|) zEn2kfHX5s|Usb*GPP1_Jl6tdf`K{6V>cwW&!svnpOIDe>h4sr;R7YX7ZdG*o0<*|& zf*Pa`R>3@ixMk_BD=VuP*BHAORa#WPaM?07yIk#7N;uUuLaAI7U9!yFS|cQSSVq&T zRb6AERV&0t{Q{W3b>XdQocb%PR@IpL70XuKv2YbUi+Z4o>X+QQkX9IrTUQEDk63QG z)rKxwxMGo6bj!l}Iz3oMh1-@>sy6kvu3WSPHXLrMS1i9>2>f4{>bjN7&8k~PR%InZ zTfPFus-yKwRxCG*>J~19x5auW%ILCs*}~{5&`c%bfqN<~TDfY;^7=)#9N=QbZHRK^ zZS-4NxukAIb#Za!qPptna%cluXE%gs7C8e01@$X#Lokj+L{PLI0o}Udb}1NT3DRy` zGH}SOuD^5T!pbTUYT$68%@9foLw8Ct_7IZnsgd%yqFb(pS312)EO#)XcdS}czfefg z1=Lv{MYgt(YjKkRW=bep)Q>R2=?IF2ng%;s@oQc zBagHyzy42^_6Vs5XFMIXMY+(_)XcgyiefBs9td#-3I@p%&uY}Go_X?BnJusG-Ev!W z)dF+bRbMZgT{-2P^V~cPW{uR*m;dJ{+jTrtWe0lV6CVky<8htRS3?Idofcgzr=&hy zi~$T-<@$E-nU+Ka2l8jqO!_F34|l{9)2#gUsu|^rz>~a6SHc#&ORv zp(i}|ANTwZspni$?fd$lckOo8XI92QDp+`KysRXucTC)PMDPkBrvBV@p5S9$AXnF) z3x2Z)ZaSTQeZb|*-M=gkJmLbm=6K*y4}6pduDqT57xciD|8xH)df;w;OwT5J;L4%6 zf3rMr<>TDHum`TZqx*Nc2d>Jl17G9J07@lYVO}r4_vus z_piqTS6;UNZ_j}KFX#u75BI>&^T2aF@URCy$^$R-z=IyRH(@x@1Ha6JKiLC!^Xz&& z%L7*)+5HQ9;AJk5>*XH!BoF*r4_rBS_wNP|{GVJP*N6um^1v5+;IlmNl^*yQ4}7%; zu3WwQ7xTauyFjiRJn)4c_(l(WqzC?p2k!1u=yAdWzu1Gn%>zHj1K;j}PxrugdEk!6 za2|Gg;8Q&KFL~hZzJeYf@W6{a_-}aNmwVt{9{5=v_&Xl>)gJg!5Bw$%yvGAS+XFXy z2lRig2cG4D5AwisJn-=z_$Uv2sRthPz_l0R{!R42-F+23o9uyK<05mN<$+gw;9(DZ zvHCOq&V9{4s7{0a|zy9Ykp1K;I=5B0!1J@8XJ@RvOB zD?RW79(cY7{)PuW*aPqKz!iJBfA4tUqg)`@qaL_7FVW+HkMrQ0eFOTx(gV-(z_0Vb zb3E|#J@8Q;_yi9;=z*{Dz$bd(7kc26J@9}BKFb3y_rSv*_*EYGtBb9-E^)zt(TI5C7t_-kk1|c+gky z`+}hVckYj82ZsB?y*WN(KeNl3lnXuOA(YEJ^)_l-oSz(UkXk%Ht?^ zd&-5Bebzw#XHYKml#3{rdCKQduJV+pP;T;+XHahQl+UNU*HgZja<`{kM%m{Z=>Jm6 zg`V;il*>HjYbaNF%H@=sJmu>sw|UC*Dev`^Z>HSsDOXYU`3L%6M7hvYUP`&lQ(jKF z%2QrNxye($opPI}d>7@tp7K4EyFKM5%D#+&{_mw+=qcY%xy)1kF6Amu`9aD}p7O(# z+dSn*Dev`^AE(^yDYsGf4I1eGN0bXa~zQ-0dlMQ}zuW z=>JcY3q9p`DVKT5f2UmKDZfv-$y5HAa+|08DdoMM@)wl5J!M}h{bvpIpGmpUQyxOO z%u_yva+Rl?OS#EY9!a^)QyxuuucthYa<`{kNZEJNK>ue@F7%X(D3^K4=TNTll&4T` z@|0&#Zu6ASr@YrwzL;{ir(8zaH)NpyODPw6%2!Y>^OUclT;(a3Q*QE`Yn@+!(rp7QOK+dSpFDDU-@@1fl7DK}B} z4ISwJUdn}@^8J*{Jmv3FuJV*0q}=2wKTNsJQ+|~4UQhXP%H5uF8)e_g1O5Mqa-pZ3 zq+I4H|CDl-r~EU@O-}jPnqS%e@Pm0)`)>*JKdJV&f8w{2AKmC{|JZMedTTP;Z<=jd zKJc65c~eYFOI09#$e4}Y{y;Kx?cjKqe?;;P>WzABZ2S+IX6~bohIL)c&H`QhD|fE^6v@m3-_vx2>y64?dZO2!svLYdwuR%Rd!o8EVOuZyffm# zSv%IoDfHqD9TR`nixV7U)ua2pW(!n3G}ydw$sKS z+Hmm;!4>|4;CC9Q9m=`qLwmri9!LCd%Y=3h3NGDg;92~OzRiA~iI4w=54Cr2s@e?{ zeK4=I{i7Sp+CQnD-QHU>r~TNP=j~YUG};))?``z?kU!kpJ>JCsL_A2pHyq}dVVN5W zXm>e3#f9OCVO`AS`%3L=XX+XzMl?q+>kS*TpU>VD`nbXnru{FPL*SLgeTXD7Qh-}42BTVm*64UY#_Zk=Bl!7w| z*kNGE;Xt=PFB#fCEdF5%=O|<9;%b~TRX*0YIc%9}f`5;)QxDto+hO*cISeeUc2hbc zIxa!~#jC9YBgE@Io7ZD&cJ$l23S`q*mKT?uD}?v9O4IA|VbhO&`>%^l3pOy>df3Dt zS!h}keus`*>GOW{BVfWETZWk0AoFj_4CXRdhrW@?(3~8bzF&dMdL_^g-|oP70w14( zANG$-Vo!@gpF7Wf%CidScWnW5l_QUG>3tKtsV&JP^xW|H8gN^$bZlq^_kttm-2Gm> z{~jK%*Z2(tOfbIbLrTcS5k7^*)K=w zSd@AiLtBp556JO;+yCmZHJR-J>;C9jR(T!Q{(zgihNS|A0nqK-j*onOM z@H3wekB5#9kNas$Iw+bG`%JtL9LpCw_(R|tZ_)Dc=bHbq@{cpjv_xOHcpvqD{F`ub z_2k@m*NvuQZ$|83;(~RvV++WH42jSu;_HjR(`+sn~fa?*i zQ@Q?`>see6a~;q1O|E0O{*mhluCH^==K2~}KUcpMzXy7{m@lo|e{r*;-;#S9V;X{2 zcf2OT!)|*XI`;3_nio@J_HXT?RXXmSry<5ja%e4ymH&;p?p)hJAINOG?dRu=uyr|$ zu{m+BEd}PzHP@!dCg2ASy7S5HFBMZHN2dDhLhpqm+)`-E0lvj&-UC*iF)I9N%x5Yb z`w>V^fq%_Q$>3b>8+?YNQ?c?I=3L!9;Z28tNA?EyQ>S?he6XiddnkX)X!TJFjfLQL z`F;I@5B9r|L-Y~OpCcg&u1 z#_Ta*Cyv=MU?+}Q-{A18KGSrtZ?<7x{kngCSK#MFYYbjx(?23MwC7eqmOHn$%RZW} zQ{x|f=Ez;;r!q{1Ma*a0sl*v^jn#Jg)i?=uHTTTRqh>>PyoB*W1~yzg*!Bs0#S$8~ z2e3~T@-xH|(n-6`v7_S`dfF>a)r*3ERVuciPOju$|1I_FwBG_B=YZQ*aCyI-lPolD z-_*D%Zb=iqfy4(%^-;rfv-;7rqGfjMi8PVL( zJ+oN$)5Z0H`xkJK$I(zu7J4``*#n<#v}5Z$yx)jE9fDs2e{E-$9%m=Uxx6Yy8Y3V1 z+%|Z$c@>`_>PU9(+||0E2fD>`0Ns;L7;NA!Xb?XdlS6};!?YWL&yi-te$CxZ=zkiV zPq;q>PB(PMhM3+YczsJ}%u>Azcut*W-q6_p1oyF1Om8doQ$9cE}Cw;&j+9S3F>$73EqTFD`JZ^+`9&Xg&gP~3 z73g!v)0KVSi14c?+AqmcGTQ;)$HfK(!PGnrV9z!jeDKr0&B(00lQj)A9_&V!t;O}T zknyyVl~!#jbov%gn`O|qPod4xtGwix6XjG8IZjSq(wL7(PN45FG<##;d%r?1is8kZ^!uLFb2s<>B^pw`X$&;@iQT#x z!{|mcmvzj%k}gyG5^@Nd#)Br<^}aP>&!eT5ndxUd8#b8Q7`_GI!V z$FvXF_fGtq&3y02dmoHuZXBBc3AjO-moK&Co1z2>$#c!McD&h&?`Go%@Nc zdk$Rl{Fw{fIi8n{;%|ncGfoVfmn@~6MOpLk7ud1HAhY95pE>gT2V;*GA^%QbO}@PS z{XQ8UI8I~x81=g##S>$Y`!i@bl*&KcoPujSp8_u2DEG_pH@bK2&%@Z8ZTNQjnI<^+ zxo3kP1ed+IfMBJ-&IC5Cw{OQondX^2y?qrgz@v0WdPSZh`MPw&vz|ZBZfBXfB|}ZE z>!-x)2Yz2N%Wo>^ce|M!ikr)$v!WaU3T_DEV+ww+aVsR=4~0W<@vCyT${RwqEe!{d zH@+hV4boHj6U$Wgm{{emQe%1}Lrh0qnTc=0Cy6fC{v2Dg&5jQe`KDLv>b7rN?bf!k z-qzjDIwXr`;XK7FUxneVOZ%Gw1hrHw>gX-C^`>>%wZ z#)sA&=VGf`n@ii(UYK?HhsfvHnm1Cu%!%EkQ!_@H;csS|^Q3FUDMiw?Krq~UM7HdP zSjWD5))F@dl4XBg``V!pc_Mgyoof_+^A1dJzOBiRUkvQOeZJ}7Bv~_j_eQS4-(e%I ztZ;8tq1GOO{m|8HWf}ZnxVINt7K{w{MvB6{1t#N2H8|Ut{}%qL3|!$?8DDc$bvBrG zlfb^mzSW~=g8O2p^}J6Tvi-{61c29@Kyy7Yfg@{oE&uEGk_>a6cid&?KY-7?iQ(RC z`t;ot?y#`q)%S!RD_a|SOnUy~6rVrj+6bLKo`;A#6!TfowCQHk(KwR0AtUx+tjP4% zWfnfh8>G##GfwQ^$+P$vN6Gg?tpgaFa8UW4Sb0U*>bQt;lFXw;rr64nFT;msAUo)@ z0>+NVtf8j&|Ab9T75p+5_I$sBH9_Qs@SWCk_mxNXnmaXLA`e@|k(TZAcpM5`T`~LUeH{^-TTHj-P_uW@sV0<;p7-!9~ooX+aKIvcOhA)P+E1#ow z|Ju{HS+-Vkw2+s03D9qe3Dn$5{Z??Er@r_ItuC0?rnYQ40yRJ3Ir`|>;-jJXJ^9QV z(ZrZWkfC>O_-+VyR6=_VbxLVRx`y6lSJ=8cu-;HVc!pkbE6{2s>xZ!BNUb}bfmZn= z*Ir#W!n7#H(>#^V#+a9pagvF(zaVVhdmzQX#zX5Y#c&#D6NWz84Ff+>r(As!9YJVd zTy6XO%Xzk)Ewbf!A#KbG_j3O1NOh`@lX$*+IX;jw`{>)(Ut1KH{aQeLzP{6nHxlDC zk(*t|IA{z4^c`aitj^Nns*A(Dj?EsC{7Z>r&qwB%-p;+H#jJ;G-c9x4Lr+@&b6T_V zok8?RK2tpHp{+dZ5_7Oaa!4nGEv^ihSFQ|>=YJpu75^1}vr%?LYd>Ov-mS!;TB~bK zbI1AN-e>VAk%vo*BZJH|jeALssa?Q)uZD(J@*a6v;ojR##{RY%)3MW+u|EnQyPq{3 zoc{#p@!g69tX{{01JQ2!V<`eNlPpg&4K;+Zq9@n9C~1o9!aPBTBc ze2z}rIGQiel4tU;`6HXBgR3#u`mdE(HpX}ajd?lDoc$wuB{|snVtXw#5YKw`!MCxr zxXhn5LpBs2M;==CELQ$A$yIt!j4vB#CWea>#6VH{$KEw-9V4286T%(73^TWIg6RnM z_1QjA?KIK`xz^2*2TO}PzZf=C_OA;3aKgMg2irKCb~T^E!Ei?zerN%X+b!M8DD5euj|CZ4&jkF{f>^;WCuZ;!z2)~O(b-zf+x5(W5O`a7{u%vM z0xwH!8C`v#u(=vJ8TJgk^Y_@A4%!Ys#DNKYz9nOfWQ(vKKedz#O3NPT#0zi}e(P6mJ=~ z_O)sLKy!f!9Jw#sRLG8T9yWkJ?%(;voJ~8~E8F7BtN9ypu+!Kg3(V+d&7rL$GTY}AnwG62E^Uu4zN=^cYSx67<0_BVh48;Yurh{LHM6`EjA1t z2>MO4WTdeUM~=Oab_z1AU0M@<#(b5$Tv@f!&lvF3m&QV4 zpt%@5L-B`oq!IawuFDuN*<;r?omyeq?_?fnY>P)&&3o{_r)IJKWM1X3&6uP<3e2fT zny9bwkS={LydjhSpBeTq?X31w%hUp!}xQv455H@f%JivQzeh|9}Z3#X{A$nX|np1sLK$mNu z6pIK)F+iv3nW=WC@jP@OxL@$S)M1_7pDT6u&_1iXgjjbVpKRO4)Vj>ayxFTfzve1( z_>eZxwP~Df4EXTp1rtrN>{vDSu^QaNtO>TMAFh%C_QAH#8lx~c5%`K0$?jkFwgJ;na;`wP~h=2Bm z@5FY_Ror%BtgtVoi;6*9zx&y>(C*1OihjwmGQ-(dYNLHW@&ne}fc>FAhsLuDbE2t3Qa8Thtod%@f(y2}oP_FLka{OtkqS*)Lmn2Xbd zOU|??Qe=vS_oQ-P(pBKnHy?f17hx+s{JJ_bupSzqLGiIKH4fHu;X4%z_S5`aVf-Jg zxzu(LIjT>C4uuX(+aE;_j`u?Y=N0TR#qWHCUz6{VZ_2+R+?#QO={=RcMzt_kk=G9@(fe=1FDRb;{36-Vk+u!hzT^_{?_><6gF$?FXmNdye6Sgc z3^eByn=`i+3$G^DP+WdBdelWc)AGgaO$lO}mV3-&oy6kUxBgiCAnlT$EmEwZed#;q zJN!BMNN11w*qUE@^UNESgUf)gY9BG!xlRn$+Td^ZGiS8kwTMS{H)piB?KAOe&6U2s zqoK(c+4=e%#1-VdidqZAb0FDvX4sD57LFrVd@j7uCUN-7rP$T)e=OSaiU#!ah2z$g zS{qD7kLH;XHHrtPt-WVc)peWZ@9Eo}tGT5yy$$&&zR*09tU{5~<4tGK*V6i3o#55^ zOm^8clRIzLh@zh_own;l-FI{BiYGo|9pA0_i``JnnUCFa)>_Ip=O^FAzghSut^XV8 z)0prv!+C+}=w@SCxMLH%1&!m2ZokIyVFrK18n#2viG^yeWXzt2R_Wf8ubdvQnxc3z zKe--S{p18@A}7U-Rn*yo4|~(+tC4Sb+3wG3{yly>gl}+tc4JwrV=MiJSX290Px=>! zdJ;pz9btTkt_9F4J!u0cJc0aIM)>_s+KQYJE{>U;8OmX+|4XlBZ3B%K@@_0M9k!f2 zxq8_N$+x>?*c9_dbXRy*IJOEB%6@I92t~+7rjE>9VTFM3zj)& zTHI$kYw#92r#O~*%svA7UakW<$KCC3u@|SdX``3?4!KwSJZ)9dRw*&cme2jQg=_QY z8T#GAT2?YzKX&xI&`r6-%T|$POo!}WD43f&+pjgezo>AOuZX@n)R+2H-)^7c>1_{B zyWvSO$07e9_{mIm7sSd%cPI1+*3La=M2Zx1xNS%`?KYrWdg$7p58(wHRP-^jk)EpU zAUs4EW3}}#ZL$AR@p^Y zJ2X!|hA(Rt_t4P|4fYxyK1APZw1*sWqf^2ik@HPQtlZK28hbp=M){~lVxK3^J|q4_ z-h^>|O6`KO;KI(HVCvH4hB(3r=&|tz^u)7_-x@#L>y4W2LHxHlM^CZrj>NiK_i(1KVR?&7_ zfgST6Y-FCbZ8h;$&NdvvW`B>ks11J;1;_O*zK>XA+k4{fp4*q(RU4|)O1l>NM;`T9 zl(yY=@BE5(|N7za?T%;s8m8e7&~NEN89ElqiglC)bLaUbn-A}KEwVVe%iM5MZkaJf zRf|KrG{z0HsKfZnuc^)i>QsZj9{fd%7wmfB29vw@CLj0{b`|nWdN~1mRL1k@;;LP) zU5YL)+!cc6A2ELY`U*YT0}(w<7I8T3O1IRGSzWcuOuO{8ApSx4mCzAQ;p(|)Rv!`i zFwnpoep4d!5uu%6No2!U z4CJM8{#{CDvuQ`q1mA;g{|)dA`VYJGigTEuAFXJ^Tb;2R<=Nhjb+3bNr;@3U`epocYMq zEo-dxJ8|8_J_@m*&U~2U^R(IM!$&h-m1mpU%i&jin$Gd;uT;&dg12yLe}%sAae15v zi*O4@G;f-6n;3Hg&%X;2!Yo~8zaDJ z#Wuu-#5%^K3&x&zkzIw@_~^LN^RP2TQFQ*KRGSSxza2BE9rbJRQ~MXvmSoS~O-Bsb z42-F}uP|`N!_EE5zG`hD|N5-zBL~*A_Ij}i`ial%9KZ@_ZyZ-PNpm29eB|eU!kQ5| zO+VxxZ2SFo?T2xWP;HDvAJt9_+b!IyXj^L(`9|sF1Zej2i_9?SgS}T)J`^0zVf5pO zxA7<7_`y-U;jU+@pv#Y3^69U~pI>x4?Z4$8Rn#~#+;NzG)V5-f+v(>;=xfZ?^ZX(` z6I{>t09PELb;?7w?0l0XNBMGBj^2Ga>AxEzNsiN@$z3-OgC4c1vAv0V^56Ikozp-^ znPX+>nEcfb(b41Av6g*iuaLGP8Ux~hJ=m70uWS*RRsI-{4w&q`e zIdOF$xq-Uc^K;AC9OVmbJ#c;G_^dMQqOT^bwxA)?rek1DHVqrogddb%%*IB#Ycgl9 zSV{6^n-kFIhmQtw;v2|?wlP=Aj*gF)US4g_mC_BNW}N|!mO(eM?lR6x5l7U9;3vWv z2%Y26S&iK~SBO7MAgcs9b>3AB6a*aIOW1RUb1=woh~UgI`}_}cOnx}QImDpq(S~H( z&f2q4WyY@+-IpBfHHrF%S7Sy^ab)A1(Na#j5k9p}48f=C%ZGj7wS_PApP{kG+|CDC zN%jA8$@UazNZBE;y>Zuh?s_haE!DoQ8_$YI#nM{a%XfxZ>mr|L4nb!GTs?2(9{O!~ z1o?GdVdkRa;u1i#SA^(5%m83oDKOpJ~*!N|DQPx}~W zb4)$}T92BX318Z$HnXDRK0^0QR&<=s>`$a#S5IGs85JF;^?}L}%09|v;f3RZv9f}{ z0Dt}czRiDDy>N8g+gxoMcf#7ymA{kEx8TX2?D1zX|D1Krhm=!m@S;-WrM-XICh5^d zlqEa&Jb=zyy7PAw_q%yce++&#^Sl9nXc03p=gE%| z)5$-rCdSm-xPm!NtmMciFR2_`D|iv`CZzmW<6`_6@lhjosPrbQs1ZN5j`=COBst8q z`;-pmCEMxqFtXCQ+*V>3$+QtU>DfTuX5Y4njC(6^tw;87)n4Htu3FDp)YG~t#8qo_ z?F+HKvHi7l)GaHfI0OzsXFp6nUHf+~j>_`6Zdr9KVm8eoFDwM?L>epU`$Yfi#32Jd zST@%6!?Fh-L+2V~;Og62f9Ci$!@9bxU9=7OwBvKi*hB2qKu);?9nd&i*vTfwHpJK#65E%e10`2E z>k*3>-JToRXZiII{-KPx*_v!RN|BFZoDzIm(6$$je{6v^uYW9~&cmMhb|KFdL%rqt zan_De+VX)TeGtD6AN#gV`%+%m@u$~-8$pi^XK4zsS?|z4bN6T{HX$CoJaSyzD*IUo zz8#O!ugW24kghuCQyp6=J&^sEej4Hi?Nw^d3IBBPqs%kiU%Zo~Z){}+@xwI5 z+NCEsG0%47uyvndjWZ(I$XvciJTlgH3^5pAn)08e+`D+C;7tWjF_O-*SAjoUu?#xC z4L^%+90&zZM>ndE(~U56D5j5a)xM9`CmQ4LBd2`I%G)@)?VREKKfs&p*w4`!>GqrS z=f-CL%yVZg6i6!0l}<&W?MiUGK3DNyB-1xZePwD)Qo7~mUbaf`w~&M5*PXtWQhpBI zNhqH|PTU~hVCp=;>qouu>Q%fot9eng8-Jiuw5L-JBx~%p3TUys;u*Rc(#iQ;TUa< z&Uv9jwC(2hR%ve;9^D)scBA~nbu0O-WMC}keC+)L?Gpr&Pt8;=OumD)Is3Bpxpsc3 zJaQfJ0(0r-?Bhtc8j7sq24Ci+$UTE6C5qT@d(hn3K<={Po~%iog`B@ofB(rj6WaX4 zsip;g-AfE7y|Lr-U>0Y`6eoP?43eYoyV+lf@!Vp+ppjTY<1sP|S~%12ztwvtRZl+2 zP*-t?Ytv8UKQJoXyNNuj#)@}G%ReA@5j{U#Y;i6jIwM?MN9?iFXW4m5TTf?AjF0Aw z#z*YKR!!0SM$TN5e~L10D;YPzp5&_WvF&)FW5-<@p83>cgH!v#nolNzPoZDM77_By z(g(ZGwG-oIIi|&lBYeaj7QUH1D(s5zLK&0d=kr`STAc&bxqkv+TsK zCOHb8oppq-sCT^S?L`MP{^qPw_7Q#A1?-P1&c}xw(7OO-FHMSDr^d>a8~;fA^x$#M zF#G4oCh=hBowwf{?s$_uJMEVw9*o@?6%PA3#fyVI!84sbn^J78Y?_`usdgFjC!d%U zuUe(t_xH-RceG9C;n1xp?U@5Jn%^X6d;hV%3hfzjo}tG+Pr$xUf_)#=@AjXXv~BL! zc~|ej@STAdr#1JEM_i|Oxa9c#!ht-oY?JhVIr~<~)V4($zfe|D{Ow_m zOb23uz1tq+fQs_%%GdcOTE&g{50(9lUzxG4RE*+#jx#~XxNJk|omDx$WwqfO_!>)H-svh>#`Vo z-e}b;qaJfTmg+BZU8?Ris=IbmlzD5{MGr=L>Sn9%rPO6k#%M$RMy^TKov*rgZ^9or zb&uZt+F(!J&pGe34t*o`>5b8bU3Y$}?#-!w(J!~(9`IdW|Hgea=L4&*h;>NEVzd)Q zhpOo#au`SryvR8Aslkn0L5u(&o!}?9nwWVt0o|Rs=x2S#+yY{diO6}6E#HxL z+!%`R-UN21kn=dQ&86sz?XQ5jwwgJEnDf$sMPEI=meOk}>Z$UO; z+8^}Xgl6rbJjwXKfL=X`OrKx8u&2ZfInXx+9(}_LMo^Tg9k(6yv`+9Fm zwxRQK#uMCD_+eezY@Ka!2BWkXKibTgcEqMQWec97d#z%|x1$T0Bv?-phzBgjX-*dF zjSSzUJ-|yDBR@9UuxG&7>|l*jyal<5M%i$k4b(f1n&%<#t!bvXldHuCeyu0_LGGc*$^BSGpODKtMhp|o zFw-NM#I2l5#+Ox)pDB_Z>$iugci4W-zJUAec4U1v`;UrO+;=G^QYLp{+r_uoe?&QC(;1fB z8?fJkqqtvngQ>Xx4}VL={kCoUa@?=}6<;d0>PYd?LjTe)t*^#Izxw)DzMavm-(bZjXOz{Jznnn9j+0Yfer_?vi&a za%Vl;+r~L0=JG*TH%k6$)hZrS{F$GDKVh9%vO2@wo3`&0AX%KaZoH}4?+)| z6~Bu)slM-GydwCbf+w8){oUld6(hQ5yq_Axc-rT^?HD2VpP^rQ9o4np%8A*?68txi z5w>q`3G;abXJ`Kc{qQi&rDq>=aUFBA+Kjle8r#RWTI_i`2YEM=k9nNFJ5#zY9od7v zx8f)FpzpFx-{ZOV-gjy}O1?ee(aWhGy>#L}H|PG#_VK(UR7H+Jep2$s*Y!TZ*f7oq zIWN^eZ~NMuGun184VyBOaZ12L-|ZQ8-s)2HS$V!ujNK??;jT}=mf?)eVfg8W&JZ%* zgp4ETy>NCzw{nKaZF{Km?D$~hW{=@JrZz%ORC~b%jD1-98@qVlldIeIN%W~0vH;!T zeW{89^u_49%&KkW>fnt`HXvJ92PQ&K8#>@V>*m>8wvQT-e7C^W57xra=*2t2d>5T= zz3Zvx(jnei3*>K2$v%P%gDIQv+rJLjgyUuJd^bRIV+Lcehq{`>_S{H)14CyLbrxPR zxyEM4cwc-LbP;$RME2VsV;yCJXU2<7>-!15RUx_gax&)X4AeWwEd*XDxcAW#bLzXq z&=raueosF^{Hx}F5Wm`bJ@H&hS2|~#9owMSWM#~~O}>)6<6n@YbX{k?Z)42r;5D&{ zXVaWB2?^@9J{Ifnk+0O*h;Zs`1phk5lrU!_ocy@6H&=)*@4n3R9%c-*wp6=O-Z9Km zK8Cg}Y?O7O>G)l5-!%5s@>^#j#~UK6@nbo`ZO*%QhPiYHxQS-R-h7)mYVT)i-Ul-5 zvkyA|b`pA}HK8*``N>hAXuLG1@{{Lq|DN~UI5CfV)*cCDr#c^E+fPFebUz7N)aHNK^lIOGw9VtE^x^K!wiRM0 zXnQAdkZ|j$>&oH?c-kjbTSY1U0<@{RRn!q&b$>+NP2h=6TmEZObbdxYLv(&ZtoQ-H zeZKf1Xtjop?dgI})eofF{hT%!t7J7})$pOI?ZkdGoSjh{B-hxmojs6TQ*kNsT8pe~ zdyw@td@ph*7T$V`>3Fmx+;QI6fiuYi0PW0eN=Q6xFi@z2x1E;`) zQwENc({jF#RYmy|@)cWe(RfPt{YBcp*8R^@_N);*_OB_}Pd%_I>cz0@!X?*ff4j%z zEFah9ADesx`VZRUqH&Tgj{FUOxgyGVDQq+9wijlsT~+{Ds&T*M2?;?(@t8%|F?J z!}x_L{V6}$PVlwhu*a9LHfBImD|GArX5hA8#fPFF6)t=haP9FG;BTcr z-e>3WO!^{z+_CzB!9PnEX;BYAo|eK<19FFFriE>6izviW!7AMHOBru_Kj z#JoZLxWSL}KGC}tWp^xk&?lWsNZ@zKklFc{ZL9|+FX14U+*gpBp37f%4Jo~=6n`g~ zBsQIJ4r;;Z+*aaD_Z*aD$61J6>0=-3Os7x25rFQTg}qW-Ek7qb`NERF5)XXVM@}9E)BEM>343V)bfdroH?=_OI+U4QnRFM|!8hc~2!-CES=v=cnzssnW976s_y5xMC;8O^Tm-u|I<~MpN-ijNz#fCw91saoB+kL+2g4 zvGJUE6S96}^zk;ep1Q8?Jb;t5S5K-^g`D@*42F zpd$edAKEri@u~A3-E?phFPD-VmYs2Q_gBQMvCsOZJGvJr(l<+lV-c*$hx4A)m5CR$ zKarn2q;a)v3Vs!tSv>zln9_D?)D08ro`E4z5;@cwC&`_tePV7<4x32Zmg0VnMvixVyX8d)Q)udi`l%V2p!VTM)oOu z$dPr|+@C+~i)(D_;oW3AYdveQZ&K8PPd~OF8V&DUZ-JL2yhMEAV)-KMQL)<4`>FQ) z8@y$-_NMBF@Sbe_xOwN$o?=eL->sFU{V{i#{gwTHIev{WFb7`P*0=7YxRd8{-k){X z3(k7qnFG#zNX-G(0nl+!xd!cJoXvQ|q@O#Cy?0tLE29>js3>@VIX%==d;^-buF+id zadqPIK=Q|SeB|tP`rw^&Y@1_@r}7la7gZBqtKFUAd9_uWK==R3n5iGN6{LKXbbgzu z{RZWP)^AUlTD2eM{vp+CF}369vw)oGboz*C?bc&zZ{t45{cXbG`=@!riDcB~0gup! z-R^}MwZ9Wx>f;9P!6hE4*a@s4BcoRKsbFzN?KdcQ!tX;|^*%tsvW(h~z-{FIS@i0Y zy=UrO$iPQD*M3Uko`%;DU~|{f$gBc0s%D98Px(F)@(};xT{3tF+gCU^T--Wa{xy(% z1o`Nh?Hj<`3S4+^Vf%JpjBP|O8^2=x)y5iU4|7Ck9ot?*cjw<25j8TPQ{cHnMV zd%LSBKZJ}D@NHglY!r1is_oFIbK{xpjkfYk^J+Xl&8r}IX7y>g!Ixy8_>LiS_M4ok zw%|*-zdekfa(~JP>P&}n0nyKqIXr6I{)aP%E^Z_3DQ|F`-(jE3eK%G8P2jnE#!YjL zyy3Cc@ys!DJ5hL-%o5|-E1_RKSFUji`r>`3!95rL$~(^7 zA2=s;{9c^$EzjApxf5Ib0X>V*u58$%lznc^cE3ZhcN@VRbnoha|4;QpsqZiplIKz0 zW;XeWttHNTfXd~{e#lo=;-7T>;C14#J&biL`w_81#+mndv=^dxMA*|{oJJ$1;Yl%PYNe9P*TJeAjX@+~hNf45sebB)O(+_Qp>1K(el< zZG9u#g6>wv!NOjzW=&)FM0D0T-$A?yG?v7xud{j{t&szCCLp+eE3wLx5GSe?-?DQSC zPQ^p^m{!Oj8N{fPaq-S5ha2J^J}Q_iU2? z&L`KUHa=Qfx2rSLwCtR3auYX`&sjQkm+%lwmaIU`WiioSM& z6C^*l1N^Z3|DTWd|Hsz2I_o_%=01-BcgV2FyGP`WE3{uGos_MchP`NnPw6e^C7swh6;~W0k1d@Jab`*H&EAJiXvHRk zf|KKqus7|FTTpV&bk=?WPVsiW@=--PR9laQl`~^CxSVjEFmR-c$ai8h^Or7`8oMry7 zkL=_zwxUxy>pd9UH~Ch_%RJK=hMm5VR|YQ(cknHbE2m%R>`|y+wYMJn+EkC+u3*{p zsjGC_qE1_O_M|54K?wbAW$p{FjXA11w-9UC-=`s_kRD3Mq+e6L`epBPy5C?J*c+37 zlb_PwRFt}{jF;>ZJSDXUrf*H`n9BNGbW+~T{Ay$WOSta2{!{4(ee>v;y9YL~N2`9c z$D_XNe(yIXKFRiap_FM772gdd2yINDwA?b9PHEYL8owd%f*-fnP^IK&UdF}?{(IZ*INz-p*n=F1yCn;Ee(0M_v++#Q)A`&Y3CdJj$Zcpvyc0RuyjUoS48@0+oY85yu|5_p9qy&W%EPtYQQAKboVLu4>pcAFoC`eJ>p0@A-m>+4pCgMi zC&cjD|7TCI|2uSgpVr~gB=^(jc+USY_YX?1vN&I$HQE;^o0i|Q#+5#z8wc6julWwR zyYFJX%lAdKj;ZEMfSxt+&Y$*u|Ay^pWUho(M|w&*r%^bR_fOGTzL__qj6R-RTGey9 zF}Ip~j7kY5;PxSwg&-89O#e2@(dH>COCd1_;{P`uXY2IkQ z=*+SFjB++=U*}9Y4|8NZ^fle%n>RZU$nN%8%_08Xg0iEPyzAu4Zt?l95It|evl)iZ z=ignRF8l?COnoEL!#5#zL^zMMo9_VavF$H&tV;X#`N^@213qDTg!R9*j-LtLU!rd& zAbZ*%_A|v(X{Zh!|4tu_Nu2KyJhKFOir=m9x^ldJY)=vJiA6i1-Rpr5;|I0FN&#TbO(gZHwB$bPiEfA?$p zPDm8ls;qOaWyGCR7fAPPc*4IAj8Eo7fzFYI0#wwuik(nb= zXo}z~f*(EXeP6+T$No>qB5d`{lrK)upVkP5 zHZ0l(U+e!J!8fXQX+EjGdnQ=(vWtEziEYrEibB2_4lT7^ymMjq#k=#AYr1~ylp9TW zMrd_@uDOcwQCsfwXSa+t#@Oeag7oLm=Z)uxtDsBgL1rTh`CZND24vDn{|W3p^ZLjk zXwX?Z1AAoh4r@{O}i3o*z}&0EC{QS@5!YUI1% z=JPq5SjQbn5a+BP&yOE^eamR^XL7bYdg9p<;P3f|o;+zzPUT&1!G9TNy0?Jq z+h`Ss%$7&3S%w(H;mynuWx6OEJFXawJ)uF4J2ulo8k7rY`LyZUs5-v!dB``Sc{B3VIG_VN4)NVH&8=w%rZpd0TGyj* z@trwGF+^Tc=e*o`=AB~$^UGH>E!CI$P@5y^uZ4d0_yWy$(@!hoijM8*rk{OF>#@I; zJ!J=`HZL%~=7oz3dpI+>tBE-u;+t6Nt91xE;yE{I>D{0W&bujv*d@RD>A|w#o=4Z2 z&i5;g|6OdAo%=GpBUHe+={pwEQNg=XXYx*xzW&8u`%=(U3?s+lf3CFnEz9ICFd5nM z`CH6MHA8v!1ov-Q8AG<@@V;?@{MNwxtQnW1zwjvgZl75=3)w11$~%$|j58J4Iaf@Q z-YghC=dQQOi@trDnciUW9l_H$*T(k&PGL@0zkF8nb4#js9rh0@S`S}aRtx>|Hq($T*di4e9PueV)IWqN4mx2*1UVF zsfcmj_Z7=Dzpx~->yNbiJl`B>*vxw=W?T;*`W*rXVCRqw;< zJjoPfwhtM$<;{8Rg&VGUP5Z%J{;cFj#F3GF)*C060n4;uM}ZmE(>tk?0Ds@wQ|9U2 zj!ft)CGTmjW{rdWI6}KmrEvTgT$-)EgcAZD!{!^~&qhWyR%hj1R|c?yd^%v8IIDV;01DQk4D z^dXUR#a(~SSwH$@Yu1cd7Vl!v-`{fRe-P_qwS5EmEXr%L&D@6Xakh6Dw&;pAv#`tk z-$H&bttxcry7)Xe;Hq5*l`!AvMth^t*li=!KLU&=J`-a}sOy1LK<` z*unyItdsM&*o457@S}0!h3tw-Yfz2oz22_JcO!OwCwa{Ob$;I3ortIeS72HIN2ceFdP zQ$NB!i7#yL=1%VQ9+Y$>!FQ4hz&o29t9bi!=lap-@~oOVjB~C2Ew8N_OK>Ivw_%Kv z+x}9XFXC+Kdgy)Amr*km9XSI$^G!!jmP%)aWBcBy?(s3F8i|J*EOK$^iENz4S?|xR zyE?q9!JNAE5V~t@`Lp zIp!?lb)OT9ah7DK)+Ww(2Lef*yS8=lZ0w}IiGD@&xcBGH+G}2G#13zQ*18wYkLx{+ z;NnP+;oQ2~oCz%>nfv<2N&$I-2YB!Lb@?Xdb=V5eP+h~fJqwL#E`yIsbeGto!fiwI z4jtKU9+(kVA8NC%`+UCf%-$Ax2-#-l?G6*XyT4y=ou5A4Boph2{#ZyUDqg7`4;Kum0c{Lm}m zsBA@eS9}V2Y&}~L?ug7FzUNF()UhiY&78^cD9>CT#ml+y@~ZTYJ|0$#LVRN9jhPqX z`(@E|PPjM%zb|rsyYp{m92^e~oygpsYlq<1Ab-OggU;!lYq& zFdz2qY95FhfZii>1_W^#Qm+xhOW z#^zLFSbK~rB%=}bdtHTV>UO!ZC*K;scc^J$P&)EyQ@K{P-%2|p|1aqN_b<^ss_4Xd z>70phZS3y$Zekq8n%1@9j_)xB8aw$gcOBz>uRv?m0P8T>V&?LWk?7&?h(TM24A@=K zdLwj1pj-b|fhD?$KPB@$#HN-h=n=lf_nvi*G-!-R{_OKme>3%?)F&1#4>ATJ;#Q5d z)|3D8u9JT%<(bQy)`SE#lGsIa4EM7$;+N>UE+c-auKP0LmvOBkH)HQ}RXY1zZTkkr+nNW_9#`^o z-GkT{VBey97}q<He^Qe8sE2I zpC+%UP4LwhV5fO6nPUugT8Z$ozubFGR!KD{UIGd}xU!DXM%dF=!A zS9yUj>si%(g0+Ca`*x@PCR?Rmj_8PE`6y__KTjeR}XdRVy-{w+Ub^E&cpj=iV0_T;ua zsx@F)=Y{bkbhV!F9?12_(d7Em-R)bEX*KfH7?er2{GzL)J=Mq-xfWOP+d@3Yd#-xF zs6w&`jk+j4i#}ur?K1x+?lj8K*Z&^#m*zTSq_K5!3RbeN%bOD&ksPHnAwJU^qYcg1 z*bwr{U$UvroNgnhFPorzj$wQ?pCxZMpJUNR!G)%_UH*jFF~rZTwdP3=IAd$?581Gw znQMkxb{uJqo&6g8O*2_0muGWLkUGIVc7BESatrvL(0#NQ5`1meJmoWy`+>6X#qluj z#AExj?Rb=NF67sM%oO)Fu+GZjYU2hk{?fM|EWYm=)KA~RVJ)mSe5|8@**Q|lm@;#U zZ!8#d#Kn=Ug&Ry=y*UMR=zwx)Iva4@{6WXvoX%9_kGzkyqStC`x6e8fb8H7^8b;?D z-oq(~Sha`X*~wAoCH3uli+aXXKd!n7>Oz09XlNzg_?TyY=yc(QV;f$pT3ofd$t<2> zh{5!4!{{6ECGrdKDn0j}KPYAH{Dd~_xx?5F5Gei(kFqp}Nm@YhOR#ecj@=h%pU zBLAoPfj%p*tA9VvK4(XauUK*GRMV???t}TWC;ecZFaFumaQpS>Yy$kP?8%ypv*L=+ z^v(in3;QgG>ii9Qv_23{XP()y9=-D!KmWdvzPl4hJ^{`W_J5w>c?|y)qm4%CFFq<= zOz=MWU*QDNUG%&+$eEpjjaF@h{I4DJaR#ZAHEzKJ#C43xz34zeC-+*nzGBtVPlaMe z3!FJT+hlrXMoR4OVH9Ojt}5hv#`~r=qc64J0awpH;0)fFqjx_T#g??OXTuo07s~m; zqr=_$=l(DCdFIxS_}Dk!#~#m%miBsz)t2Otfh^mqwGXTBF{Wtx|IjA?hU>TpvJ3Lv zfMAw6X3Nks|Fxb}KOu0`XDc#Pe=+1J8z4FI-faHE{jwNYq_yJSGBaFq_(@6*AE)Ht z=UEqZM|RF=?nEZ^+3WWI|JHYtr*Ewv-ToENx?}OSe}p|23sYmU`zyv`f$Tc6+{!)_ z?|K~+Z%@M8tT(aWz{Rh=yZ@vu*Fi;EGdIfq{=mogS~=H3Oq*aFcJH@}!Pn2O(@LFD z*=G3oY!km4nYg;D_pl!2S(C4{-Qrwv8S#?(z~5~mM>BT_?BhYf45lJ2GU>=he5k)PAv z)~tBO&-d7z_~%Cj!`n5!ih&XZ#7>;U*FJLVc<#?6#yTr@(G%y!E_#x<>qo?0KPK*S zVk95++!%>?X`P9`53f4Q7ESRY+8+|__WPg*Q?w4`zwP%RZNJMmP?+-}Y+DKELqfz6 zQR3+x#HZ(B54OBtFw5oN^*JTRvcI*exVs`~UR8YX%l~oy-Lh6}jJ?;7O*%&ZTYMw! ze+Q%=zH55?x4yvsI@&Mhxz44Xni^}h6MDiIZ@JXGI*z{eZ*MfB1A&b#kA}AU81KB~ zJJg9Rt)FF|XTyi-s`KW0_BPMdPl!Hj8YruN=nbc?mygkJDi%5ZtXCiy?!5$?&VJB- z)@i-UCumQu5c^gIoNF&JLPsIJ5Y&`o-qBTsv1N-0ud-&wh;W@+Jr&J#O z1IAA|0mX?Q0gnuJzN?Nb_%`*xy94u6a0~y{O&zVDc!!!;Hy`amVH_&9_(mMj8cF9Ow*cz`CSSRe z^PX(1?k5;%W-oES_5lrXh@Ifv%RmGk^%hlzPXhQ!l(S8VQeDEKy69K zv?uL;50iHdS`L9DoA95+zg=JSP19IO4t$HtmWlLAaj)P(+A_#Z`Dx^e+B@rY@#CZI zAaZl*^}bJkh<`6^JZp}v8Nr!uoGAMBEgORliGIZ|%I!4LhVKc{!28aeTe9QfRQ^D| z%a$MWllQ=OL|8|M`_7yxdp=NaMDjP(lB2zj%A*iBeMsL4 zpW|~9L-;qYu+8F8@ep>$w!Nj;t0m})P2+L#(7;*B0CXu1;@qPB?-`2@VzT}-e0(=F z*@|71e0w>2t#!lyL)*K6M^#;Y+-GJYAfQ6-1SB&76{GbA2+`I|0=2DoV(R^EW)j=_ z8rw?Isz}Ww&{mCYnG(T@Et8;q$+W&j0ZXhk0jxLFB6#c7fVQPYTfCB3G2idM_c=2s z0b2aN@8x-Ta^{?US+~8`+H0@9_a1jl5Q|yX125#?w6B!yC`xbSU6^<43Y|H$v$wm1 zHOEkN?@r=N$m{MH{D|xhCL^D{esIi^Ga$uto$naKH;jRk;ut#TQNFUycU1h>f3Bm- z$H7l+s*YJ-<9tW06YA_YdnO=x|0bSPYf7{y&E_$|%M9zUx{H@YDOfb54A+%_SmC~VCjgn z{)j)x?@#hqy2Q@a*!M#2O9EaeD3gFLVg8EW9Yf9_{Rj23y!PTM+1T}6^eH}yf09Lw z1;soyR>wS&CI7`O1%%$s_FEj&u=W!0U% zz^A+y+4a3Q+j(M)v7Tc51Q@gNkA}}^C;n8{Cf}d+E%s$f*QQwCRZh0ICkJ1=Cd9bY zH}z-vRtzt#T?)WA+O;tY#>wmKDY5f&7SX2+)IV+fv0*q6jvLvv&3n|IMmoZ(EY zj{OqQMzo9En1ifm_wA_8cg-1Kmgl0^-KK1SJvjDkR>3G5%2r$k4K<$r#d_ggK3c|! zvo3>{I?qV@P%sXRuy;`jzcBRd;d?CP^!I>QjC~sVt97=Yf!}4wdarb;OUHKZL{l8K z>@JOW_Oe1p@sl~&I_Y|~<+%G!VyqAKk}DEEbj+!iHoh}Ly!}b6e`vj9{tRzFcpmd2 zd}X)YEDuUt9^|D{%(>fvQR^JdjBohS-$B2OOB>hZIWU5~ER+dg-y_HibB_K9vJ#l0 z^TzpI%zab(J`)}0#o(Mk_KrJXc<422FC-J8P*s8-)?xb0Xah7 z?v3*QB+bDuwsUaVrEc`N7n_oQAsr!opgLi6L>2$BBg>oxr57Fse^-(NDISjJ9X9b~ zdE9U>!u}{Oq_be{ zxsfsVjB*c;up3J_2AFu)1#X(}HOgM{o7|UZzu@(7Q2qsSTU&;|A|H>njARiw^kQf8 ze06BU#2?g799fZ$lV2d-Y3$C$zDb5?LuU<5t91PWhyG*M=P>(ur2h<`e7FlH!RGa0 zZLqa-8nZtHe~rruVx?9G+B5t5n16{zm$7EA`F@I6ULJSF$q&yPlh+z+`NDdKxSM>G zzrl~|TAb(SRXfjTb&b_Wufw}*fIoqcX7>}>_qmJ_t(C-D>eiQP4VX6K)E7U$3XKwb z2c{irzJI}dhflR}`q1|;@x2yYqxv4K>nnt|FERda=KD0>n|2vXYPT8s#~5D|C=(48 zZe9^`c41>`$(b~=a|JO54k9x5WZpc>d43?6-*`OhAkxLkBUFFO$*+sV0?C_MM_Nj5 z4fo}3{nx2Z+s*%6u#G(n=`ZCLZkE5IxuaeCC`f+_7^5E!Oqb5ta8*NJ!kN&za{RE) z2>!}ZoR7tR=Jb7e!#i*IJ^QA|pV@g|-e)=+qE52O8NchE&>^jHVBo$zWIV^fFpoZt zBL6TJwDyj%-Nl}>IeWP0uQ-%{w)Snl@%BLNKI7Ef!{*s%duONk`5|yS?5|u7|J%Rs zbOo@_k^>XhB94wu*?PmkiXWtA;Y&>one|)AN6|p{+mf3U`Im{8t2>t;!B{2!U5JeJ zKr{L0@M?=QWmqzGIy!DiRmGZIC;2e(jmn&fUr!K=Nsv!p;Y`eRm>Va^%ZHECe#^a} z5$DL?=WbW;dN@-X(%Lt<6_o*;l~3Xj9RJ>sVK-oAmX! z!y)VA%nROmcNjakleX2)m3cX>iW-G^uL`(WxZmj$1T zx0NyW1Vb}0gn>aeu#B-8904vGqu7dP-yf(|xu|QGqx=r@?7Uxes(A3d=}z1I;8P7P z1PAlsQ>&qQOOW#g>8CopU|W4C*gCuE@C(T?J9QD?7D7XPTg0~pXl%#(g!BvOqQ3<# zT`y(qV^_+fm!G%oBA(H^<;>g4)#n?WGXT8}Jzg;7FW#nnfjIY2#u{UN(BI6{!sDGT z!BkD(2ZBrVRhtd;{WNU}j{}wccQ{1ho9HF`7jvJH-&%A$ci%+!>b&^7!TDZzD452J zHvdnGBp)Qis?`TJ&jh>&Xw1PHLu4a5Vmk zbZs;ECcIb%>lB_o%cUJpA6`#?Dg0j9?q159yBnZc3ZHnk_E!xE{XJd3}AWd&zZZfCwM_&x_* zvT2G9iH_<+W&YpvqxKG?z4j&0pS<(aXzvoYy}N+BxOBm`ySOt~a2HQnuWjK)DirW=b>^8{3eG+>us}3>fqTHBj6r-RjUBafH05T)<3-e!t(*+s7V+Mr zr~EFpKg!pBc#>0l7WJ0UPU3v>cYq*RfE@;-Vc#ds0Cv6hK_ z34Fv@u(U6>v2MNai)}1jZ*WRE&nJqwI~!bu)4kxNeCyd4Om6k?61;-b`sowWw*jYz ztML3DYXR-h4SAg_zt|}wCv??-@iRS|RnvZ1o|R$bWA7!*3!_tF6Tb`H$Ase(dy#34 z5%c^D=Dj~3n5JSUDEJS1!>4l}HEqftn$G%);LuocpoxWTT>3%$ z6X0Hl4&4%IJ0z*OQFuHuNVzcOBD0jg5J<10T#9n-rxO!_50iHZ`{_ zNb9T~&8vHDyQ@_`a?h}25p`1V&LOv?otT`38+?ITaY*S};UheR!S6Z^k!xo7k9e4=)TP#as0++?OM38h?H{l}^=I3J?#f zZ@dxNC|w^!Mp8q@?L6ihWxyl7rLj}Y9+SI}GqqJ58n;ggD3?^?4=p=X+^m z4L-K(rY_y+sxL|5P8<< z6qWr%3Lo6HJs*%yQbjufeBUZ~EPD{;uXuMZ{D?~5xxQ}??WTxHCCvS<;?som?@w{s z1n*_cPyfnT@Z|M(oVE5>?f}@>Qq`%sgF~KC@r_rS@fX@uRiWJVmB3s_IegpnN?%6-Ir7_5@fzrH;v=F;oYt9zD`U5MO8(pNaFUJ>?9xe|5rz zr9F{dcUWE-zy5E3va+=kKVNgT@V4njucVmQOIL`t&Vt}_GpBUMZ7vN28=p-M)Ydr# zjpguaHoTgI9{Y|HYF)^@p6CA8kjqK%l(~)Wt~2|%BIq!k0h5{qZ<$;BbGV}DpU=H= zptas--1XD$PR9D`$mroFhv*dM{tk2UY|dYHjV=$qYi_P}9_@|1l67di$2&-TtMa8% zauV(x8T~-(D+y?!eJ;)L;xcGae}?n~>m$sis-2?ET2E38u>K5UawcwQ^Q;E1hlNf)9X`q~`XX zf?YT)33_KX>IwFjHV!A|=cJVfD%fA1Kaa6flrDSO%b`-dob!{Bx5wGn8V44| zzaoo?)0|132WO^pKSFD2m}AcM4mj*(Bo<=kuFm*V!t9%ia~4b{CIejA+?(urFmXrb zok7;+ob-d_AG$un^a%6`hhHd(v;Icg<-#vs?o?R5*gIDh+f)py3B47A-imWVm)bD4 zRJu;Svh+ge8TMOT8)ZK0tZn9Z**RscRc+D!r5IpjVzq;>Y-59ucGeBvqiXhVikGuE z+rDfjxopH&s+k+q!3W9w=lNTYUJP(fQ;huV$dt^)Zr0ej)Wg8p|3d+$2leB96j;M5gSUH?+A<+{9$M1 z@|EaC)s4INu+KnNy>)xy%+ft`>aZ(M68BsP{Tfn-CF{9!vw?j)_3k}L$j06g_$+aF zqrSy=_QMy2fUQh0$PWu|Dp6bT+T45Q`_|=sBL`t5^r|uNJ7vq&PLMVxQD3;|J!jGy ze9FKlK7!{vg5y;u>~xs&Az+3lxlO>lLGUP!!M*GO=6MdjRM2TD5x+x;ZuT*S8Yx>d z1v{0=r@)45?chy~{{`%Ogipf3-1&KRY(2Cb8^1cdUiUou?-bN;EALj1T78LZ0gtEG zq*KuixjM@_%J~+u*V~baC@|&$V?036EyNj?SajQw)_xM|yvC)HgS%-j49dmh)Y=W*RfvzDw0=8f0- zK&pgxkGC3;f1;IFl_Mj$)di_Td`I|X|Op1s+&~;KguT+Y2)0f0);O@lz%LFhn@3`=gU()+1CLhicS(#S-buM}X8eTG zZz4ZE>_wOt44$oVAs)op|5zRFF*yrrTm6lszaC(deu&_Ui2v-fnugBnZw@jZia9Ti z{sPDl`b*E8>4c9+dqMhg_`837`m4^+2<#(c%-TY&V+1kTjA{N`o;vAMh|5dQZs)(T zd$iYjlG!s-LEE{?+0eRD(=CC{7`oQzM)Xe;dMk!rP#xW=Yv*6~OswDV+goRo4)Agw zB%>|Rznc2qdY5E1!nly#sdR$79OS71x`|#n&`o1YYYEj0CNCdOyY;6fy3}V}Jkopg zE@z)Cvuj`W41K+q4j_kn>j(J0p_%OWXUxdwTfvywhcHql0mHeSQm zR~%jPAsr@I{)Ajg--R?@U7gZSS(TB0tTJmUqkIn8pPz%Tm5+SRpdfdXF+ z^N`)CKAZ>JvO)Rgi#?yroMl1VlIeE$tQF0_u=(ZMr`(1mG$^?swgL6X#r*+`l1bvaEeE>r;9;277O|XPRiurUJPT-6VsRpgoWUx9hTFTiyrbA$L*^ZNq$&iL$RK2#YhCKtZAoHpJXybR*M@+W~UN67WNO4z6@KYjiep zQv|&}-Klo8-mdXy$NdwlN*I4CYy41eE#9obJz@O%MezA3=(~uvsaMm@z6$!PoowtT zXG>!L$+;q5@IjO7DIOK#JBUwv;FI=6SY77I)7PvIA^%Z&LVRZJ*6>rjlPpV*G6$GT zKa1r{T^Wpiptx1<7}n2_=O41yWBN+x`AXJC@5Fz(4R|6UVlV8MdvUb0?qPD6(2ZM5 zuR3kL!OXb)|kS;|1E3@jQcuY^{DJW~r!TLV72fRN*Htt*%PW|# zHigC+o(gxz8E@hW8yMrt=W(!u_mIQ;J7~w;a@5VxY5daq0dSI?jyS_dad%N;HG7pCwltS0 zHu^aDpkrzmfuqjOwthlUx*-@kdko{n#y7QYu04}Z8xw(i*2;^(U*e1<obC1>+vN}p*Cwu&7-WEB_XqS&7fH0sLe5L&*4a^M3u|$r0cs|0nty`9y3zA-w# z5uGX;N$+~~t|K3X{C9Kb55bYKdT;Jvq0O)G&4W#Fy&EbjKMr`M*Hmsc>+80Bfx%}o z--Nexw&ca5r$5(N^L9T@9zMeDS|2`7fKNX9UF}bs3J#ookpg~=%Vx%`-dEAbXz*L% zo~yT+_bWI<@4Nh6icDD83Jq+h?So5Uc^~gQTr|cE{g2Nz`HGT(OY=DM7v9KMQCp(H zF6#Jk`%kiRx{K3B>I&W&?(g@&&ujDOnLIP@Je;ltU-vopE57Hev(ILpbQbhhxd8JI z)j>y@Gcf5VcNeix<#~u7{`srs7JmBgJc2x5GZ%K!V_evt1Gb&qCGWxak@~?8a)0N( zK-*rwT;kg%p0LNI)_eD7-Z|l`CXV=H%-kWb`GCItigvxRvGa(m&p#9<51u#jY(Jv= zEb0c3ZMCz;*G_hf9YC(I2l#ngf9q@OBY4j+ zr6=TL-{$tG_NUT*3cc+0x109S=?15Mo;Bx@OlyyDliRF)7js5FjZX-WCMfnJ2Wrx~n-(U78l+$QH{AFubV@=eH{LmjSLLFMd=HOTcYvD%f7GwFapVZYYv~y2jA2tPj;ePZWt&}n zHJ9i1kydwom1mcJM!wGT$=BzglXSVhN05hqo(!(E4}Xmv%jzXNw{&wh(Q$#!isgBR zZx+@7wlG+(c|tcij0Cj}t=x8N-WVeHJNfOxlpCPmN1k}%u+y7pPOFXS#)IO_aoeeZGQUhf{D zZU4CJ83LbTW?A?O4SW-Zz?Y(pfsw3#oBKU&8NqfpJlVrJF@5xzcH0fm=Lq;>?@+Qb zyVAg20{*sc4(%5*7x3^hZ4H6zTHuPI^NsCAKJD5Z`iu` zp2e5yftO2zg=g!m8;5<3XE7GVd(Fc&zO}|IAHt(Y4|Sdc2P-2E@}_%@^3sfa zeuC@QXJZh9ZI$OMd?`0WqncmA3;FocNorF%NpZw;+%n)^(+Q5!Gnz-K%tqeneXXxd zsiA}Q!yr8i=HKu~} zZCf-36o<6&h!b`ZXJZXG!n#pF>qh87{NiL_ic`^ak@Hp+cG;t^rxPljoVj=4BV}UY z=mcUr@Wo00_w&MA`4@TR&MWh7OgJM>jk7-^;*2Bi!2D6qlgA~sm)fJvRd3;g>wQkn z9Oku2=aqP$#p$8UnH|zK*cA2&1UnPxUCjXk^wWO6o%^J)GptuJcMFyWN7{9@NX$tt z(E1s<3k|HblP%G&b1$_2RA*kC#W&{K(`0v2U(cB%A5r(Q?sWMafG6Xb_r{LaeBG{T zc{-{a{t6eJDS@n}BPWf+z7(dX)28}~Q&;w(ly#E!^P_|IGVO#19!;%p>+Q46@-T0* zx3(H6kKZ2cjIh3-IOU;?y(-o$<*RQW_$O!Z1$K1;uV7)Ua&PUpO0FE%X~Ji!v7_UXRQMiE(Yf76y=KezUL2VP2y zn{cr0{E2q(rN*iq<-Bw5L8I(gBG`7Bl`p#xDwvNRdNvN9cSicEu5{aIL6<| ziyS-#?RtHXGvRmeZK%BDJLI&54^Fl#z`t|~YXk5nr}*6YgskV|Yu6qu{f>3%7ei-l zpEvOohj}cqn?~XkU2nR&DTCMKlBDJ^TU|TopU-$PgM9XFYrINl$bWx;yI*7jB#*4? z^=o|U{g=sK3=l(UX5JBjX90)xFyhmqqu=+my4lLL^s(7b3w=CYVEjRRdff?dusFYQ z>|mOKpRu(Xi{F5U-9hKAp1+hN_59N9CCMA~H#c$jo-@bmjQ6g}Y4~59z4r|Dh%ucU zhTfI%Ak4eZF=i^S3C!))x9b9Pd(fe?dA9>u&|cIco`vI6z^l8vn>B9Sak>0s;P6Xu z5YOAV|4MU+dd8L7J&!hCcE^HbQ}Kp4XZ(46w0w*{I@~_U&0MQ7(KgZ<+d{l6z`0WD ztG=gfbEIclYXZ8Zf=<8IrS!gv{M4)HN6#9I*S|loPW6dj^)v4&x}LG7Z*?C7mL?aL zlq-8??O{-^Np@eZWX;Liw6x|6)1BMQIriF{DLAB$S3CsI7%BzQvARO<-lq&}qeuC-%*!_0#p<0q*eGAVh9xc>C9 z&^``NkYDVVJy%*h2{8Xvo`}bHB{x=-J z-oHD=XRspdH;(>1zbE!F_?e&$>0q3N-FvDh zB#T=oBt_@A#xOou59jzw|Hc@{iq9a^CrjTt{Jx5@CVidI`)jRUZs46{%I4f5^T48c z>wm&&y6Y2N0X&*JcHbVDdp&UUu*doi`eMDt==(e9OKZF2_t%E$s~g?oFz&Wv=eoZg zn0uJsJq;|>k?!ceJ7CV|l-}%qI51ahRozgS}iszBwqUT-wT@Oy-=gi&A#_y5e?7VXQjj^0dPQ3|Ow2pW=bZV$iZJHN}GmbS}s#@5i^x@YZt zHcn2cb7TC*)S;KKXJ7ksxpxGZMgZSuDfd&#X&&j|ugVYa30!sR!P4)37yl@JXBb{N zPGRnLdWT#{w6T&HX3 z+DU-iGk>{Xs2sQrE$8{}^N3x{>zHWrh3Azy$@s9UzGiH^{PiI8$T^X_d|STIr{C>n z{oB45t+tY1ru8X5Ub7}dyEZXj%Fx`b-RP{P0AqrC)1fbG@|_9tw__6r!)0-`F$$fp zY1UbSobybaBetM)W<5OVU_BYQwyHf~*s8PlUc--QCzl?b)*p7ybNQcVyfx+Q{9JXK zsUzH1E+jYMnNsp6L+NeQ&(3SI^J%SdY^VP+*29%sG>fsf(mlgR^PL#JNI}ebU;}(3 zcF3J@iLEK%*14jikWJQ$iBsA4_(tYDLw#4Skj_!mH?94z;kP;8g>~^TeMDUxz9Aek zYcO{H=)bc-@h~$#0>%_HQVs!g+00oq@_}2*6kD?QIVqNt0M?jtEg7Rx?!Qp(&?fp% z)Jq=i9bt(t*=NC(*r@#$dFi|L{J4Eyrst>abDN%@v(M=FWlL*p-DTvz5U(ol;N1r9 zoKud6@)2~d_6@xI;d!=PFZVP3kl&S|!p3K@mvFrkFovxf_W4-ucbB zFv%UrukQ8LJHZB=<=69VfHfR1Pg-p?i;g#bqfd2K@LhS*q9b+4`E#Z(y~x9-uzVSL zN5#A+c8p!Nc#8%V{8k;6zv~NL`Qq{-`n`m2rJ4gt^pSP&0!B+++DMXL?g+vU}Ed(l<~*% z6K5!fT-~Xh^u%cve=mmb>Hk1jad>+sjo@r>*EC+Aj86xAqEB#i0=T3vfS8_~ zkW6Le!%6>{HbqC-CDA^JT%2(fXTJd#eqg%k2Z4&%Ey2z(G;4a?xhb|ZP@%q?Haa&o zk*C#E;`BEmCp`Bz-7@Ofrdtj>mVD~|Cg|LB9)CX?*?B22icaD~qJ=dAz9oK8RS~1@ z#MQ*YPUBnfuw&J3JVQfoJ;%S7M)9-&aANnMDb7=ya2MQPa_OLF;csLP8U(@nXK!2C z2|*jlcNTx|Y~}12Nd+rkN)30`npg_7h#(t`gNoRWV3J%s&QfF-S{)2f39D6MSFXRv%90U1DWZWA*1_vuk}Hm630M znRJYmAN3`j;~?8ceuDUQ^dlOb3Jg6T**jr9nVpK>JwUF*YUMh}*86iEM1QR{iC>EM zlM9sos(a?YmvpYpfi2{C%kl)+{ze^PVA6!0zvR{0`&7VK*d z0Q+lCW%(f;?T3Bu&E3dl$m~H_Kz#=|ytQI)J8~FL4e`lU&Xb9aE)1flXD8y?_uX?;@+XHLFwf_pW&h{&ueB<_?7t;^4np=% zq?}*&CjqO*?SW+fQpz7l_HXsk+RH5*Oz*5-XY7`v(^=aNl$-IkC@`n=O3qMF4y$N` z?G1BYJkOc?s#dwM<+1)fFIbp+0)FkvLGMa)kLBHu2fZuEoy@x*4tiIlb-4VtLGLE! zDyIMaLGSW%3wU??pm)W&V|e$iLGO;tmH(X>^e#VFds@*sbKfC1Kg2Um@Wi{)|WvolmqIsBeZ^v?+;gUDLB#*^%z&L&mvZ6qgJQF&v)+_~&9w$XVtBWa&J zhYI376-{mIeP^D)U6=AL%UMrY*6W_F8>D=lQ@D%sRceJ#C9!r>cC?e^zT;hgW4tvH zPu86>&S>s7U~T0bo(2DkV5l+0cX9&EKCxKPF>AEK#nXMBoXZdK^qH~2W?szrM`mRc z^iAXcqeJa)J$Ddq(>IN=AD5F~==o!dCnoFpek5Z|^Ljg;Jf9(}Pc<$zPo4av^>d)j z^T^Ta$O|VY@8qsHbb0F+;lZ6(Po23WnAggl(h38&tKUR>qo)@hO730Ozb8*(@gRFt zH`b@CbylOjLr?30+JAEseLe|Z>npLN8lRJb$zrFtRXVTY=A)CRg3EA?Klag#%3ri~ zZD>^MJ=mM3VDYZ9Nz7M+oKXf3d*R_ozPEpdc}ZwwD{&^P+i9;7y~+Hb-{h7^zkdc_ z{p~uV+s%Avm~CS_Z5*0u&~k?g^NCDeBq+b6YrXvW~kRQsm1k z@1riCxHkH#ZUXQ4`(yB~yThzK)z)!OL4tYx5B2UbTh7$EH(=J;>K>sS-;?^z{ZxvX z*Y&#Jo}oPJYPa(ZdxxGZNPizW%3;sju%bmv&G3D@*?ha{$A@IvJ0#OyJ?&lV>-$=j&6LZ@l)Hp-U!q(`Nar%yK1Wkl z@mk3w>rojwy_4~-ck|)T&HTUYiDQhc-MsA>BePZTC;(4Vvs_a>8-@%^^UcUX8CnP`n=KY)063DV!!I+Q0i8rTeJsAdRb@3wD3E{ zc$!Zg>GGj%eQ`)z+ks1MNw$fj6%8$a>5%eOE`EnnRP+hgD8>wh&Jhj2mft4>9f6854_XFYd|w>&GO2Fx+X=+KB_dQuv0iJ#KRn z0{Tr|{HxX~>i?Dc`YpVqN88!M7a`u)Q8#ChKf44Tdpdp3p#43MTVHD7p~U4eUi(D^BwW5f8S z&NWk#7lUhxGV=eXQm3PIU*EOCg_pblR~>y|kA)9W4Xpe9BgrX95*n3abUnNptA zd*izdbMo`KJ6N#XN$iU?P807|S(S+-%9FnUrqQ&~J<@qVzLRWQGcgp?mg8)W5z|%s z5nxuETq2sUcjQW^Rn8CpSNP`7^H&aEo?th5K%57Hf2e*ZJ9Qsu&O2||ijqCxR}VbO z*{pu1937ljejRcoKXWATXiZP|GkE9TVwlG&2CsROd^P##1_rao-NxA`!G|VnZ-V+w z@ID2v<5+4s_`Tl)L%ai-gwH)1DT%&(X$cB>n7&5&^7_Q zn!8BHRq_5Kert^&=JY)zx@m7azWQ6#`$1l6g}J*cPPvhcr4F}Tm9Lyb8EEy^yuuZC z*Wo8sZ%ObwxJzr#)lS~#_%P>r;7{uOBiRu6xy8UlezIUtZt2J=(k1ZHox=&YD(1l# zpi76+Yp;7Jnc)-qPIIG-{$Ou-24Ci>!c)HdEO113fODb2xeS`TB)l1;L-7`_7Vko{ zj_{1HT$#Z;Xy`MIHi91R+;OIy*6MKc-46AI|MB=2ZS1SN0eNW)21ms|Fai z+I@51kdJ1vAK4sot9L~!!E_`4MH|sk_Cot26!+5{V;r&QJ>BjzVu$sAK@MQPm-)3bd~chh0a;Zv%WQh&#SjMbJwAR z?x#F*usXrmj4+Nia29-G>#3~~$=n#bre(^~*3hyKxn%=x*#Pl4`N|sO*1yb8FD-Gp z9@E^bnDgG~Kf>P3X5MWArsl2TR-J839>)W{z~S&MHZWlPSOd>B$0dJ6A4@6cwb_I2 zi0RxcVr;U7_tUmh=&TbA8+Zqd`455XtK@7XX!BKaE@-#*bkSfWdKEjGIvib&E>s`# ztryWp9NOx;aw6NghxuO0gpr?x!|eQm_26AQpnE;#R3N*>d0-X~ zgd_4&>!*J+zb!qA(^13MaBDNTN6;IE@aR?cV(%2r#6_i3#ou}K6J_JzOc{;krY(8l2RALHZubp#RKypc{B!`7@sJ zDRxq>auqVpT;w%i@nj>P_BEGJ==+EE?@_#a8QDFOzgow0-WixC_|b*Nw>lE}iM>6r zmVWYkKNy(iwdZ|TEK_>V^Zzu4ODOB%R^3m&gAeAf0duNvK>L7`%Hj9MK}h{DA5_jy zYLETSnxkxyiQk);X=Z)x*Q=~Oara5#dyONXR{BBqPI|-JPcGj~XC%B!ERVA+cC85( zZhi{rB+H(TH~6}Klkpit z*?559c!|Auz)&t9%=nAv2eSHprHu!;u^Xe$6ccz1x$4-&H>3aajsEZEowWz7gCX;> z2Q}zj`Q)+(emyVyR)YNn=Czeh$*#*LHQz0NsDwK21WQ^AIM+xzp_z7ma+K57V|}v4 zz0e?X@A1j6J%%32an^O69_{}ZbSLqB?K=8d7cAM_9UQl7C2~rx)AJ?Flh*~uZJvH8 zd5_$+EcxnXo>Ypw8~KxY+zD-E4rfvG0wmdX`Gx=4U|HV7yL*}uzGA~%P zS#U|Fjy)RO=->Rt4j;wuDDa*P9_mYDLH=bN9&%2i@ozipt6!#nLc z3f#}}8u#pRUST7=l7AF;`;1^GN7F}D$ii?a&#DuIW&!?pkSpSF2mM(3 zw|jVOoA>Zu{+;Gxf?MOb_m~x&@i6Y{7_iAcy=vq)KmAu|9R_Z5M#A}3{fyO2{I?pq z43a6%9P#c19thd_6L8dAMOzX6vaaQ>hwLkFk~R5FM&7>ci$5`+l&oo7$aW$RHIla} z$d>pe-$wXW@qQBTto(77E5AR(nxx{39pI^Q&Ah9IW)Dy<)kK~;WBZ}go&HjnC-MPK zqfFc3&YTsT_ouOjABv1|{_>XNlWKDc=dJ5^`=*ij|B0G&@mtni$ePflc5Wn^V#8Y3 zgbwXYHE~7=@x`;u9!IM$QnP}|?w>kc@52N61HDH$Yu8^0A81SVRq{LzxSi3?9OXxR zmfU3IWpQNnzH#Fe^*WgAs_s3+fW||Ie^6IrPV@FA&PieIgM5mcX9hy!&3XSRbb0FX zDqXeUnBFwBlieG5XPj>`j@FIPzK>OP5qP1f!NX(vE?lepW{xvGJ@wM%9U zZLfp&&ZoT&WLw_?wAW61RkRmyoC@WJRrc6()a>06$R%*hq0R^+m%*fWKS$&-XHF0H zPv0NryI^_B$Y!zO@rFreKc>;eqV1n4%ldD*=vW3_euN))=#Vx8y#FcXR7SMZ7}7KE zbH5M$!iod(JHqejwBG`4t*$RlS1=wFSN6)k$@hd?UiH)b_WECAU~}k0GDLgld?HC~ ztWCIl2V7R*&)4VHa&;4YV9%Gv;SL{v8eIN-D0zjBvO58nmR>AWI+C+1(ht8eFirP1 z3Qo1JIl*4lP4j-%@As=GPCz6tr`S2n0?u}0n4@%@tHgah1ZK6!gBa~5_@*{Mgt?2bbgA2bY zA4I;)H=e)k*46u4!O?rqL3r7IqN7YdBYkDR$@hKN93D0I?MiO_Ya0%6fXE9cBFB`I8|S9sNGNc_CdMpAr8LH%p-vZyDpg2rpiZVpGfRrz$%$ z`w}PF!r$jqDDqnK zzr=v_&HwVu{14y#EoaQqyAx&h-5vCksJDB}ZqxIZ?DN<4ywT?Kd`-`f z+vjWa{Iq@kZ#_R}pXc*j#Q7cr!E`k(GY(3NHzbYduB%lSg?g@sPyX zgV&c!Ima3wGhcP4sGK|RiZ)iP57WPFuD-P|#CJq4kDyFyDmJ3AqA$jG_S|>LhN{eG z`KI>?-hTj$_I!HgIrymZpI+ge%9W`f_HbnB@y$W>nD3*<*F=w8=mCC9FB2`CM#Uo( zORT&x+~;8Pba%Ul|0l4KKjd5A+uz*QTqfU+TzvW#Y+>%P*yF+w;P-#x@g+Vu&gI$g z*u)=P9$(~iZ3Z{>@g{!<<20DZpZ2wN8qe@{Yof&IUrH{b_$!>s$p3@C$QY~tAE>`@7_7#IkUjpoUYEtI4dBVOUF1jIpR5- zr5WwN4}bO$_!Pr`y^lR<#8~F$jQRBZKNBPVBJ;uq_^GwX(rauyISNcp?McZLbNe9g zSMpcB#@g?2M>RHpb+u*f4S{58C3c7LHWk{K-;~ksd~k+-(}bJKMD92#sXGPr+t{S_ zCnc+aXY=o@ysFG?e3$@ld#7cXA7Zim~yim$Lt@pbg*k&M*m|6 z@?#GD9uBYBR<1*L5Fkq>>k0`$bYw=J!^m8<*WtS9<`+y$5+7Id3xlrlZfl&rI*vcSN6ZciUnlP{>s|nM>{vbQ|VvN zhnad$bw6V=_deRzISkc?p7>-VPL^L(^RQ@z?*M(sXR`Sh%1glyU#mORztkiDrrVq` z@f*sDj{dwVwXME{V*#}CVkGjrwTAY;^lR~)%KW4tjT6^~z3(b>^3JXcvktQ5q7ORI z5%~FIiNTP|kZ1B#@aawYv+)NLlvg|{k2)&Hx?Gpv|A41my~s`&*ea2IWU=1~Xl-Yd z>#JIRu&(98=dF(g(_aOr7K39qnquM!g9w z%y-60F?ui`k!z&{r^<*yJ&3ZPfBw;yBPN=aM2nOesO1Nc&IbAk~2%qa}H-D zDi)QWei~e?{!7$6XZ-#A^cwzlkZ&UxJs)pJx2qcs{kOSs#dVqUSdpPEl0o7*CYGl) z2jlBqY<)fC)vQ;EKfgqmAScsBZ_e=2noN1*Lre2Dzzsd~^-Zux#vEpNbq~HL@3y3v zw?+C+OTG;}QN@h8<1v8FFy-+})n26b6jLWfTZhq>ayt{mCu8u@x#QF%=LLh8vwJ1) zb*HH5{~23n33U`7>bQ8YZtI{wBY$R{Z?lVkR^Ld^C=bu_H<;eUy&u?j#!_DT8J?vB z)Thxcv!@!}vIyGCXSVUO>^X_jEBN1o&UsMVti_hApY`tDC7xcgGPiNnAKW@S&?8y< z!ak(!i*i-3&+yvhgyk-$jj+jMv-7(`e%rB!y@FRWk$wG^o>}OAGjU+rx|45=d6Tck z_#JYNkfn+AlH$6O3FX>}?~kBA6T}q-3-SkT^3xphZO-4b>#M|>Y5zG_Cd=qs{rAv+ z54ysY)7)JXEo>T_b`8O{bq~CgKFRXQ(-XdY3i`%2q`yfUl0mzVN@wD^XK}PmHFL$W z(9)x;H&^s%`i^W1^C{sZ96t+uI@g}|h!y0)Cku~wYunhg>bq`xc8+u)xB}(V)fT?2 zWZL7eY=_#Ze%-=`zk5K~3{1c#xQ0P*(K?0fdoam=xf(i&w|@BcgJW7e)OvvCgv{T{ z4>x!^b4LT)3(Oxy>v`BKwN>&cz8$(+{=HolV5#n|mW z`jzac?-u%yF2~w6!X$AAZVr4_f@1uRk4DTu=$e{LSRSvR%o z^L89E-wsb>92TTIppzYgMaK3Gt@F4!b7k;Y-ff)ujAMKC%N$2WegbEzs-eF_S0+IFIR%`VB3_S?SV%CI_3n&cu}2HP?IAZ_ z?CH;+!D|oql|EXP(pJjodrQZ=!6(I<1azz^C09jtcI4hw@~{~Tc3oEQ?((%4Fz}f5 zwcHSV8s*Yiyco_m=0tOQpq1)X@vhm@J#FXnw%;|3&sMi@_3NDSp>FU-b}vhgj+ zud9#Br6J(sH9YB$Vk5QQ^J*}^@o6)z?3sdEvq@22v5%+hHEZUAglKghsUqzWruAv)4y_*;{xJ}c13p+IT zD~6xkxz77oz4lex`0LQ|gU&MineGHz1EED*#jis0jyQMLoGTv#FV0jnd3mA{duPoY zJpj+**o|h^nFFlXczePHb5=iQ?YG9G=1E#N{N^Lxd4YB>o7IaOSN(23cwGtnac}~! z{(N^#YA)%=$L6am|1z7;h~K_ia;LeJ?yL}=0SDimGh+kDo$ko6b}MLd8~d?a7Xz1B z7sKD~=B_{Ohk9r#Yp$UpV9!tgl(DO^9K~jJ1oK(%VSQj0b9U|#{V8_^| zAMJO|AAZFT4x9X190SyV*Dw8G4Au(-vbV#cc7)lRX@J-zWIxT$Jh(tE5BRk z7#ckBm4&DLo$H~U`jX9*PJInNDrS7;qN=_ICueiRh-k8joT-Jz4vJ4X=^S7X@0E`h zKps?A{EpDhO%oiJKW(h3!+^a|MH|^Tjve{w(i$Tzexp zKg)0Q4<<@EDVjUmGY&rQ>P^-82DFm=z;p9m^-iPSMc55=1pcC}CqL4AhOafl8OO3^ z-n%Z^DZu`y4{VUB_mSzRAmitFW2P*pZ-zgYGlQq`4TI%F?OU!7SFb<8Fp2iPzD&RT zZa3?D`RNhJoNTIBUb3b-g5ebs*G22>n6h%FvBY|S$y3u<(wczAkC`jFd)%Zu_8=#3 zj(6I+&vv>B!MPUS1%124=;aa9lN*uAx1dK4Z8`T=_iK!4tyE>?e?}(Tvs8`)Mq7_} zPacze;g^gb%BHZRwk&6;e{y+ zN9_yucG{9Y5#G?&jP)^Q?CFe6^1CMyuh>1>*qQ?a`nh4vyNuY z-Dqe3zJYNi^Z08I(H$%O_o7d7z~f|K9lDP6l=>LuUqjlz-XD0_>V4@SWY6eS!KOHx z&PS6?>xDMXNh7u9k%`GYyPNirtpqd?T#+${CQmasGbb_q+BlrUKefR)t?}Y{syFZ< zarS_7g?Qm`=Xw-AsGj7+i{VxLsHWr0SCf_dtN%}beeO{|>0{P^mHJMPJ#Rj;pSt_& zb1QX@dBn<3{z2CHHFYk67s7M+LDpGMowwkN>U@AM8A_M^!KS>3X>LDn9%P*#Q|J3` zo!CW)&5z0P8S@bjf*|1N{M!J3{^Q;T`F8lU;i5)*0x8nUm>T6!tq_gvlO|yDh zvCsv4bGY+M_W)=uLi0M+`z0_*CrT!EGHU;Q zY9ePFD26dtx~K=ern8F^=tt4W8Rkqs#@IA#3oir)&2crpY<{`9gTA~v^+}^Y|N4Ra zhx&))w{dPekFDgl*7Ve#=FH3iwrF1JwYQD-$TK~A18s_r zYTIi!%zf2r_bg~(_&472&-$X)pV0T6?tAG^eT(e;Br&7MRxSEKIUPL%0|T#C?N8oy zAH_fZW%;UcQiY8Co!_JqDK#A%>OTSUhT4a zV)uUQ{3TXF-G1(aeK4>0rFR|m?{(|7 z`|5eNXMb?iP^a6i({_+`K24o7+&bSm$T~Br%!(3T9+gI=3(e=X*29|ZXbEC!@@o?4{Md8TT8ZQIE9YT<{cD_X-=@JuIC*h>>C%7p`tiz7SF?WqS@l)M zIkm(;n1`A*O3&XMI-d-l6YV#5kK<1i#MoyVbk=E}qy9Yly+j{XZeBpVg}hhhsF55e zH$X0deC~kb^v5|jC&fHDFq-GD@{T<;VV+}Ob^3F$f3sNgeI1@OaZXK$vl6TDPpT$I zp?5IdK%0}CNw+uUMBna(9<*IkMcc|fd@q#4T6DBuF%rWUGgr1clRHHF%a|)`4xggl zq+6>xXVIs*GmZWggAanoPkQBJyX!o{(>>!x@*rH}=dpH3PJ9{dv1f2sh&fZ3K4a%G z?-Fdl8FRw7mja*oB_83AFVp_^@Euj1G5S=DC+Ci;zJ>Iw_1x+a+=s$K-Wg)RpMMkf#R(pyYD`uR=pVe>06{;xn6Zdz3IL<`i=pl}y@A|!v-}Jva60J0M zFjjE}f#5MQiJ983&irW4z_M$gaYlc?9!v&^D=+r7JGI!xqBRaxU-cq6q2w;=>i0$b zSDvokzx2J3$=96@Y(Jxay;IBvd~(UCj%q<8dP{VjmLy3gum`2Tq~ z-?+WHGI%^y$|{A!SI72Fl_R{@Hg61fBw2}4ryy0?N|8dP(pj%gTfWJr4Ygx?Z(f_pe;}r{Sg|b0Y#FlNQD^fWz}eh|sQt!ExywX0Mtz=2 zABt-s1FN-mAz9OV$=l&B{9e3fqz|_Hsi!rHUdEmad+sqlcqh@H)+nw*u6yko#cJW= ztx;SKZ@=jBBLF|{aO-+~{g}QaTWb5Iw?oFS&^pH7T)FbiH5lE0)6Z_J3!3!t;w8*F7>oY4HLL; z1RJ6;s2mUVq5jprbiLxt-=Pn!&3NNmdiN9;SI@Sr2VbqvfU_I3W&F$>W^itWPJ&Nk zBZk&iAAbf}-3tc$bYIg7Fh#$$}wz4p0QF-}*(8_7lr*?5*` zJO9Z`%MQV_{uat>OaxgAu;Nn^m4(8{CN0(8TbUpzBwTK*QGzDZ__7z ztIz5ShA00*AK^^D){cLc@#gR6T(_UW`pL#}I_Tfk2KbJg8Q-jo z-;9Bpi(R?Yc<69tU1g7U^_A@WJ-mlL)?an^T-{GS&G|)dzh2%So#z6B=;+Bt6?LxR zou8H?pk;52BQq8n?mQ_H}u4WCqNP`1r8WH)M-?r@Uav9VRYAv9U6Z`F6$eRMP7 zDQzxpDPt|IH*DzoeHW$x{g-&U5Se%d_*A!rHu+ZbYueKp9zBN_v<4D&eGz0>-__@M zzG<#t;UK4qesr&FMy8mX2)|<9L$lR-FWgkVA%8@&`jaD*5ypn@!t#G_h>bKbR$mAF zj9bpKkbW@rBKM3+GVk8n3@(^1rKQFChLqo0>Er1|eDh>;aPCP~zDyhp*)lp8|Kd_)>jl?F(O1nL z@KGDZ$XC8{Ci_zMVsoLyzCeYwdS$##evO*w*1!HD6jSUO3nm&kNrAYUt)|GVWUjHf>UQBH8K`-Hhr_t*B?n;!`DH% zI*(`keLqj`qrP;M8ryBWBKf%oxK9?Kzd*jxfHo2K8meuKJgc8gLfX{13Qd zN7w1wQoboCi1C;kK!-u^w|bFD>1g4Xv&QaOMQ*q|%z3_nGnbpDSbGz7*r(0B`mf;4 zoT*jqu`bfzOq&{ql9!HS2A?gxn)W<8D@No$%Pos*cAZVQYVI!o)#B>zYjAT_I1A9s zEffux=JJe1t7QX3QsodxX5%6e7 z#+hr@s_q;Yesl|ZS~N@KJ}jAaX`^*N{~6Par?vBacnvx?cp-YU%t^j$nsgTmMeEZq@_dLzZR&ll5mT zyx#`a<9O$_sXC`qUNW12mgvd~&XAvr%+>DTycVzA?04WTXA+gJ4w$n>OVSU)7fs%po!i~* z-lcFm{Uw6q&fX)LVn5$@pHBKSaC&3KT-5&98d z9lo7Re>TR+S@+;JsN!) zypau~cZBas7hmX;dxkrH^!zUGrQ20cGE~Jo$&BRXtO7e9@a6#*8a-&&9_F=-PCm$d zQF&~VQQ2Y1JN0YkwQxR=l^6Qg`$b#hyqA2*hphkIH`cp$b88bc&^S`x8NbfZVACqK zcfO&)qn%~c_ux=$F2HZm;aA87dd0v``IwO7XPxXG?mriO_7?*X&Heg`GpY8`Wul+X z?A+fN*>-^PR*yX@nHbdm6O=!UF@GTax8uVh{kXbs9`u!*!Hb%m$e^nO4Lv=-?jvZ@ z2K`kom*)a#?$!A(Xcrx@F>ZLBE1vG;9+DJs?*zI(zKE!PJGdgoy38mfZ zjt4f;c>ZeO3bO9((iPg_BUKrDp|QcehZ)`MpA-4p(wKV&e1z9X{%RaYNWL)fS9dNr z;OZ5%AAmOn{1)yW|192&Mez2{M3O$!em}{Cbe#NEjcc848v$R**jMmR)P~wsxdGk_ zFTHDHZu)j6kFJP!`RUuiw+DQ~j4O{%&mglJzuz*sD^>_hQ+fOmq$qody!@nlSJNEWa$ zizfh!>#N znU}2*4D0_Tzq26y^v^wgNn60`!ReLrY&yDRafJD&2eag~mUmlsGcN*O(E^_4ehGR= z9`w7~jceWjKUy|s<2Sz%tX>Q)c0%$qt{)=a6;U5PY-y>^F>OYi@ySj8^3l=B(OM$akA|N7I{X{zbKgrjPli1I>+SW{b{HDF zcDbH@WA41*yNrF)_8^;^&9xU#ZlqmLu7R!Q2yKY+Zj)BqYdeQjP`@wA}Uigs90-m36ZLZY=|q`P^Sy&0brSJ;&G9*U)t-cTP3arD+iT7^R%Yi+|T{qt`Al zrhV=HkNX@zSD$zQIIBE-T|E}?=^+mX%?oSjL$O2QKY_M9e^&H59+}X4`pI2JpVEP9 z*KwMM+@Z678lUdLPn~n!=Qz)2`JNpgUO%V5gXQ03U)!hpp5Hh;%gbFZZ6wQn9tt_rdp= z5567lvvM-jZ-BqY4(ab|Uw?le(%=1Ve`Ux)rcamO%jwfUK7Zotw*i`KE|c?QbUuDi zEq2G)n6>}N=%$*(UB0N@Ew0}2e2X=C_8fgrjts7zy~MuAzj%Z(FFJX!-2gnAb1Roc z@8iPRm8qY(^Tr78MxYzKd?1y%kb3g{9G z+hs1EdjA}7c)Ipw`SA)~Oa-EHrdh?bF>Y!VJ(d==od6?g&oTIkE_#O6aS@m-l zbaNDgy2HlVI5&5WsY4Flar7m5x95V|c7o9GI^x`%b3B8XZsT>F1SbAJlhM_jDLZ+R z(bY?kff)OYMML=$SwF(YJmo*E!|t^c50WowVuI`~Kz@x3Rx>Yo>p@0wz5_!Se?27JaoZB0^hUE>0P38=4uv$NI0bS%S?!K0Xc3;AiB}8$WLW zyZEuFO4dK=obKzWsxCTT06 zh1Rq@wA9?2o15m+Bsb*V^ufcXr7FLv&W`|s3L|L&r5T*5BaARUC^{m4ag>J-9A}*J zP#N(7>L_(^`ul#@TKk-HZ;}EtzyIeKrRVN__FjAKwbyH}{Wu&~&|1dT?&jeb98X?^ zecuiI{CJH+-W<^8`@n;8&V23xybic|8D`x!9l!ehxXUu^$CKKRKLTf-C)PC(#N%-P zB4}`CSZ?tw>F=*lt`2^f-1%esvF^e*6WL}0y7M>aFYA#WoL|(HW{F?-S=8g2%5L1( zGl2PPU}u5<{&O~7!sGtF9<^iPn3-?%zd(O$hifS6H=tkNh|&1B_zfNlc{vN(@ZOJ% z@qR6R9^eXkOm2_rP433nIKVo_c#Q9#(!NAvyZDsBe)NNLD-WZU^)OGDajo#v0HaJt z^%(x_*GBu@jNdHxD%$coi@ZKkPep4TRd_rOjk#D2(SH`(X$GG01d{4sIQ;!nHr_m1e zkl!EkY1jzhCwP1*8Vm7Beq+2lh&r?hU_-GFk!=_m6Mo6hwJ??^p^rlbyAJ&EN5Jv= zfn)t+@XBa>j6SqT|EqbggvKn^1Gfb19Q)7<9vR86ytCK6()>V5^oFOwLgd}rHcfOJ z_id0Kw_@J=?-)P&7lcQeHKEOwpwq|yx&I-=RV1IfX(`$zy&l0`><7SWj~u6V*~BQRb+ewcm>yI^rSfkz z&I$kh-aRF@ z-)9&3G+tLA?!<3t*7F`5?jcs&ckJ-J{2n6YA>`@rr3M#+rzy*jhqVF5i|<@|+F;#< za|Rvu>Q_BmdX4lwA9TYQPo+QS`S&5f^S{3(zx95paoE$q{$D6`K@1-6h(ki|NtiNx zLnR&$%o#iZc+iKSKf!YmyHN&osn`3&G>`A^Kt6QF&>}MzF#D3SY-{^DQvuWw`k5FG^1Uey-clZ~OC(j$C`L)&#;giPX zVGsKgfX%+Us@KlqdyM~NoTUl%PaVel3onQIZ1O)yzjc4-cTER8AkV4dAII?!nd_>T zH8$eY1X%Pfh|_P;KlYt%evLeZ{~iz;tIpeob`r27luPto>LJams;KcSl4c?Bn zrrLgZ_UjTW+l1fayiTv+SC)&9%?03t5Qm437kNlRC%YqbKF9J~*mul>I{AG(%0}a~ z5#KHL{UYD22ACLJXyE+B=D`+*C*@lIZ62M&v<{l32 zA3fLx*#Cn3x5wbTSLm%YVH=*$iTB+oTNcCreZ9aw8sl#}}Ce&`oq4>Pby zq;-7$$+kH^pl$y;+9U4j?@S#gPVCcnkYIVIl3`#e$RWdD;q` zSdV*ZXag(H!{0L;pGWw4AN(-W%f#hO(2u(C!S|mk{>K*q)2|1!ocbmw41N=1OyAGj zvFVTlPy4#|QwN_%9~J{QjMYBUthw=>gRK8B>V#FV9 zc`9XXGUth5xdqdtE`7r=5Ao|H`v1vz-5a&;9jHq@_&$OE&agCoPyQhK=*P7RdLit` z(5Z}-KV7Tvo|JwJ>3+?Rpnk&7XBQ~W*T&nuAMK*Q*P|TZ?c33;XA!xB|c;ZTL2N z(~Whzxc7l)FP%I2biRKS{!f5&s?%{sHEn(q&YIp{JR18J0FU`~ICl#_O1?*#!1>3e z*sJs_luf{gs;rBf)Ek{8s%Eo` zC6Yth_Nh4A%Q@jded9sS36BLl#M55Rpr3cuD^9yH?@nO<#K8MWKg3_E^!KsI8$urw zy(di`z`0*n<0c0V_Y;A>L!iZeoDojo?CJLENoQwp9yWO={ZD+q@+tTzID>H8qQ--p zZ)-Yt+ii(+x1TRDor4Z^u6u3UGus#8Tr^xcL+4PKib*tc2Rc-E8W)&_3=chH(+ov3jw)2kC#K{u{_l=J{y{)4*F=t90b z9b=pZOww>a&iroUIYrQ#dHeCL0Jh;KAx?%^%}cPCLB;nM{5ju$!F-Rr>C;DGec+w3 z^oQ`C_RqgR;h96XPl=^_e{u**0&Xh5i$L8PfbJN-_mbXipnG$>lf40L{v7iVV?25n z)5#b=#9yDn9n`QP$AWG;|6#mV&$E2P)?1?a#1wq1gS5|pPIZvM3}}%-Un#ds;TzmI z*RADPfPY?bZo#0tBC`c_nH1a?>~bc%Y3%VBfLuH}itPRY^VKx)9)N$2{syH^Q$?<1BSz;<5E<%6aLX!uuTKfm0yoknLMe!TyM<>Z^u0zAUrlq{)1L zA@KS->o+vw6HwUyUNdm>c%19mfLO**u>XW{m>-X?IpvOf8-pht&g0*Eox9^+?0*Gq zrluD)KK#?fz|A!%bMKSEuAL~e6KBJB;u{E$xSE&K&{=8du!I}8t1hmyI&-fDGt2ee zUeN4b)Z@AQc8v2*H-6Uu>ICp72BzVDNa(wZf%``wZ;uVRr~VDPOdFVMbJ_QdZZT( zJY08O@(#$wU@*z;`e)LCV+~%&psyi3;6Zpr@%J6!*_UpL7n{cj9rNZ zFcAKD!PDPCTcf~#kHO~|dBT96 zSmSUG-(gJeX1x~e+dvY01iNrc5_%!VKj|GtPqdqX-mJur``vh#V;l4f@PaVmglz5)5$ zpfi}q^N*PiK#%<6|7w8^+}MS+o;I|f1|B7}OgR4o)vy_%;v=80zKmsyQS2|hl;=mX_oxTLLbk!Swg}&3K zq#;YNGrM>nMXTBSy3X_n+4*Pe0|1YN_Z(#24W2?j_&pii9Cxs8OZv6#XfKKOn$ccz zrlWlv`~zqt?V?|7x0^Hvk0rKbUwd>Ey|&-l;k~I2_>#VC=VH|3p0@<>ZR*U7+7{3G zq;Vew?~KT{3_M(gyIa$^Zz9e9!NxXkaq#8buJk1X54-(!yBa6BT@Lq8RDo`6%iGa- zoY2qxsH>--41E{qw+F}@JHZ=8oNJBW%i?1U)u87#(DP%E!EMmH4!pG+;~gIl`bbrv zR{+^+h5yxrK5jeFUEMr!*)zd}#%q963)gYc|En7(4Sb60Ak5SCkVo*HF(+qK#{>4G zSKwQ;uUGH=x0$X&KE@Ak1WotjePSS{2NqY#(fHvE%B2A-abK+5>XGFxN4W#lPj;9oTzI{xhEz(d}@`pkE+wuH09ZFDZB8z`oOm%zU` zjDJ35_}ADkm4(kooy#^D9|BDdZi9_Z!;TDq?)3Qwz>_|P^qlQS5xjT^dj2t#qYnEJXnC(YV%HGpegJlF2>QPcb;gq> zC_4oI;SrPta7;fZv!J4hcYeM;lQ8SruyY;`~0x1m1$@w#sZz#B0G%J0!AgL2fF z8-YjK!~5_Bdjse`hi^L)9@deb#yoy%20E2>c@NSiz~sJ3;z51os@;PhhfECs2JYjY z6HMHHLM!092?H%N7kHb5xC89h`TMah3fqIbhF?7rJbL--P0#FZ;8`-=e|hnD4&DAm z%=3mCz?g**QOwoHg(PxN{Fh;W-W40Y* z_8HV40L}TmjHA%+?HC`<5oBB@PT7V1+k=0FGW@Pu<@{F8)j~ePHo#+?_Y;2lw#J92 zUYB_1fj@5hyUe@fY}M7bP9FFa`GVt^S%mR%i6_$NJKOsa`0G}j!%9OJ(J#Y#%d0DK z=WZHx=`&4#{g_ufNjo=5VuzS&JjJ@1Meg7cq&aB39W-_m9{p72X4uE;5_hEWZY0jp zzB;jqz?p3_*839q4KyKNr*X$rBgT2#2W$2UKeG&UBqkSkE8+TkPSaAL0h!i$K>n*q27k(}S7%&9W-gp%2OV z3G*5Qq^G%qO#$Ypw6TN-FP;_AFIQeL*R(9 zX*^fX-5n49sEYQ5+oDFWaSD7V0&z#4W8wPXEr^+rw|RB}{B>F*X#2qUM%bd` zhVQDH^75@W-|{KOAAe9abypF-^IzS=J+73CsZR_6mm%WfrtTU7F24eO9b~u)8MI~I zzK`bXv2BhQ*DhP#l$XDTK5qM`TH<#+tD7+yBzyZ`Yo5Y z;W>b|@oh2Lzrl7qull~~I#Z&)3G%`5q|ATgXMU|);5xaYdqz9rM|j116ZPm zEdG6zv>nCE6L^nvO~(@#@@m;$A*-_pI8KMJS~E@e1wl46?rZykQa@#Xbban`fD3;U z-e)EterxMA@5eX6N3M}SvX|$3iQiPT5fIn#{^Qa2z&svn>y}tsUqM?#x{e~a)nTv7 zw_bd6>ku9$aef4NVmxGhqZ>3PPH{dD_y2;QWeptu2jhk-}- zunu(@>wI{OIzP8M({X2_ugCJ-^YI*bldvDRzBl1_2EQ49<=r;QAJq~IKNk6;;q+aB zAKgFwSLky&?f*Lb9vt}?d@tvy6Ik!R4ZqLC_|xx~HIL6qEK~N{J^1{>!9PNVKY=oj zewzDUjvapNZphDPaqs<%#9-6(ftD8Nq5aTVb%4RVx=Cja?uC3i#9^qnCmD_wsE)cm)l1=^3JFU zC|hTH6gC5X`e@GO+>=SZ$M+N2_SxizZ=E^#580~0vp|mr(I&@N@aj5qu&Qd{>3zu4 z^TpibJ8k&m&{r>f74rEuxA2kEv6tnCcb$Omu3WVrwt(ffH}G8cG<=(7pyfv_hxOeM z=DstrZgOn>9^mjPgS)+6%YO%DsZY7zig6*L)iTo`NL>AB9LCDC2LA?S-i|WUCnm1mj`(cNq^4`0i}5qXa*;{HO|i?AwAo{0!xx zFY0;s0d>(1w59rS%J6K^jeX~y%ssfzZhOpEdav)ltXcWH>_+yRvRK(~(&CT*HL~Ad z2QKk`&pb@O*P`F=V877^_WOZ~ew>NA+>{X9X8Gc5_*7FJO3-}6bM2*_zj{yGUjjLwh3IyJsWnuGBJ5 zSef0>L4SysDWJ@CTIOq3=25`;70O_o9@sNmaDTGyfZiATm~a17@d2ChY`&oX8B^BBL^DEpVw9zaeZS2Kt! z>?`y5?Gonk9o9XcrtL<2rsb2sJq1}(`BES6SI?V{HCSImIo92ed=DSAeVVr88t7B( z4afdZ`a$@v7x-*3cm?gg%5)R>{&!dpJ=^j!Rnt#r{uz^QIe~I>EcSvd2;ZH2I`a?V zoW#Yj)y1llPJi(Exsb`J!ykve)4LRLJ{&alco46D5&G-*29GyAPzQRqA>Y2miu*CS zS9IF&N52difNgf@6YpP&^Z4-Yh{xrw6Zuw}zkezE9-Oz$p^chtz9eij`R5Xh1#R;O z(UzynR{X9)Uz-oi9pqYD&9ufp@s1s_E#a{tnE5v-B?9iV?apJfA- zqfMWVa>Qw&w0Z3C#lYY1$$lI1=u4+bL(x-_o_Jr3hWyT)^7JFHXRuf41&IH;o9N>= z??+r^YTe+!fqw$P@pDtIg;pWfxD+(XfCn7bTnHnm5nu11L)@8ZSu5gM73_bghMr1e zjl*FbcPaQCw0Qa`r8yRZr8wx$iw=YOFMzX_6ZO15ZIN* zgP+?QJBth3P9EX>26wH=oQrf$fCfW9$2m>-O4M5k#CkHd61P0KAL#&b@-)&3#LzQ{ zlWa$vCNTl=HY=*bg-ix?n%_6UuKy;9J&BaLf2E_Qzpg7V`%P!^-SOnI!Vl2NKxRRJHLrykprk zXy^v2gdS6W$w9Pf-7lf9VFO zca7tWo7l9MzSlyFJKXK6pSWT24ZF5sedK=d18MkAz@-}Foy7Wm){T2&+y3OsD?x*I zd=_^5IP?=^v~beYT?yc^6yH5)#yfu7VJ6z3kI1(0O~iWQ!lxf2rWuo)<&%s!cX zq8jz+*R=xQ&!OG%$j@ONW+vYwcKA)~-?$Nd{08=Iq)_%l;K`q&-yZ_6aNSR6v%hg` zu-|RvZ^m#NS3*`-DlNSIOCUc9IjcJ-idSMy;^k$)eI~wfLS8!m`?`0n3UhtP%)unu zU|+#+!jJJdPQo?qMVTku>&u^EyGhWqDe>Cb3GiHU621*8w5fWz3VoV^`t0XYz~h{f z@0!s!mh)rAeQeyjVw|2?kc+4;08^9J#8Ga}5NPw@~Ku6Z2?2w1Z|LjvEa0(_O zCXDx01Fa8nuL1Ays6u`t;^171%z$5x179^EFM)AsLOJ3Y04`!88-D?qjmYB~+sE*` zIab$Iw8!{<8n%JB{SkNCvR%+w^humgl$)?kM=hIgjy#M!VNh`F);GT?qU&bLz57_Wa2@SsN?{#|vA z#Gpub;f7+n%y!s7`peueyd5ySul$L-;77>XnBOa`cs_#hb`!C059=HU zKEnH{{P*be{q1O%v|#>p>}jZ()_lzY#F0Gz{tRbqerj^?QIw@jJXbv)yfkk3M&b-w zHG{5q(Z86~{3qf}SUNAS8Sek8-ZLL>m+%Oebl6-0lY6B6SltC#Lk#6lL*N<432y+N z7_Sz}#WuvY$n(#EUc}|9uL+IDpuNhnZ}a_VgE(kEYKAY1wfTs(x!?N1cAo=$ep7bN z*DCvR_%Uq+TtB89&jU7|dk~va`fT`gTJ{BUKP2}UHvXC8yBlLWfUyniOljSSu|0gd z$uZj9Y3+iBPiN3BZG&&uxhymdM({dJUH~NP@Anq8+KtMYe z@?11`7>+Q8bRR8$ zk5wOc*y)%Ax@J38*`H$kysf;!>eNlZ{#oFBA7nHMnl&F-G}v@u`M!6;V{AtC#W;*v z&G1vOf9#*{3wT28{Zi<5*ch>^%xeQ*1-O=mK7lXe-v_Sk)AY$QqAT3PjVM=H#;@^J zgMOS-*?B@)*W|coCS0($6}n&<=>?uD!7lM0Ss$OA^^mR~4xkP02O6kVU)jMHrE7IP z-mh6ULDu|Q9Ce=BZ=PAv?}_LCN_}#_kJ;Nj?mzi+?3>_RFQPw1{FZ_Dbq@m0Z9)d1 z4+YoncEn_=MOBo=Zt|R_ntkl>w$3tlZT4%%a6fxGroPC zP0)7-?$vvT?)JZZKc)^ZL_c_b^zNm!fgEc+JNg6AGLr3QY%ZvJ$M=tN%08km_0&V& z5B1}{Q|{-UI(*IR;kbxCxfHR^V>w6q;B~j`06$>f@C5z09T@K{?#f`^8tB3)PoA-B zIp#Obn4j@|+tK(w1N3BD5#Zd7kC)Ugl<_y(j<2{ph$nkREkcs2+{melOF12|B>`V&Bc9_hr!^>gMOM z7mV^c_((aAB2MunWAG|dRl_@=3-?&8f_!@|U@@M|c+6kl>FKMnhSgt$u7^)VnaYA5 zj4AGU0erlS^R+3%n;r@MLy@uFhyx4&KJ>u1K+gv*_hT=yZqM80`-;|~ed?VI;B#y) z#yMsBkxWz9QwK-BWOTj~-@Ma%A#Dx)B7+0}qyC5r7=Ro4qnTQaXT_c+>VTNuspmOn z<;QZp^E~cjHoa4?Hf_rA-p5q$47~}x6Ze@<0=^jYhnF&r2%Sb-u-$9{d4ayb0Qi8h zg}Pp`F)ek72@l|10(`X_?Ip;kNDH4%U>qZE+oSnX71{znKD-@eThY!C+G&Liq3_=c zo3I^EjsfE;7(1Dh`+c5OwCMw~)*xqWs(=^gX>6DL=i65Qw0vw|#P>AGo1EK_UzTBf zn+M!ei#*@pce=K6Jj!Bh`wqvu-v)foyRY9-&bzz+UU`>%Oa6`XE@g)JO!IgkO*|_3 z_p^6KvA`&f75Pk*AL_7S;6Xotyup|sVei=Co|=j~PPSL+oNW6Jos)4sg>NrBv=sj5 z#X|Si*PPAc_G4UjQ+{G|u)D!?tV6xzJiTOZjNfPU75GUe3l>)*P9HLyxWAt|_4(== z=uF%P0e;4R~cjCN|jJWl0&&<0#6&xmO~Jp+AT20tmuxvKI1fbsu+ z(BmE8FVYfz#K9!iZ<;`hrI_RHhp)$cp-q*}PpNm8Ol?x z()3j!SIJ(TSA&OT{3$=>x*^)L$FW|3eo&6s7s?UGD=tS<$!EZm`l}B8Yr?#p{#2M= zta95lpm7t@z~f6;4?M2$r_16-j77YFm>zXm=E*w5jnt;X zN2!M`-bMUBdXL<@aN2Xg+sCQYo>hsj0)1k(&g|=0~0*S8?pxv_9g?~^mFbn-4XXSyuJDIUXT0k zT~&Mc-0cPv0cZoe!F~`<7BKwWpLEN@k07qtFFW}6z@_pm@NTwKHn-RH8l{Qs=fQo+ zj0sf_SHn+h$GF~ubsOTraVWw6oQiq+t$%se;0y5IXnS$b@i6bSB0l3V=3Hm>cU*mk zIAEP3-q(S$zUul!4RF5!^0f^*9kycahrnNVV_x!g%-7hCv;mvK_~X6b)q85Gw;jrO z{Y^XM$C-QeA0MZC^BrR_?z};VIYS1UV1pYG2giB4M#R6#pWI)|eXkC%lSp$cm*LwO zvL6-i-0Sat=0q#!X1d9gbJl6TZqqHTm@nRlvBuubC)xmm@V4QZsk&e<=aQXv{;LY` z(jRU-xAD-SGbyVR2;*k>aX0Ip@ig}Sw%z6)W_{ohuCMvn3H$Xr<_W~n&u79Ip7{}H zgKsH^-exsJH=O^Ec4ilRO<#iW@q8*%TWPx@eQ^fnn%i*431#DR)Lo!urC<9UeE(oa zRTJg{Q|gc zFy`DxMBVx#zNe9{QhyEhY!n|><$61OGtOI@8H;roGyHadBfNm$i3y3lo*z6faIHf8 zbo8gPA9tc3v@JIyUa0XIz1L_K?qs2^d>-@;*v=6AF!&D4BOQf)W&1q8y7$A7N!qio zSzPYtUbh^hy5+lQgFfD#W$?}MJK#DwWbrxD0WhhDnxUg-ApV%d9Q8TqipKzJ&oMmz z9O;UEpE`7Vv`6eKW4DVv!V(jNJnut$Jg31u#Ka+uG{^UM)#HbUxaSr)B)}Jp&9YtY zA0~Ynw`ITMcAsS$V|G80h}-=mhCczCc0d%etGl4J1fqo@zA8~!@n8rUx_(r;qx}wR}&$gp{oW9_L$*eQp?#~xKH9U?X?uZpZ zrmtjM!L;Dbrp(!4Zp*^QOhWq>Bk0dbeLw93MlySnKYH$(y!Sr&D zJ=PZnU?)G1cFF&{k-rt~v2T_B#dFY^ccUEPuxwqrYVa?9g!u=?S>?g|8`1oLz87t- z`UUcxg~{a0X~xsQZSqeJ%AO&S5vIHUBs^QsIORgzN#ySjA-}V2wpI6g-p%s$`>y(t z?mZ+;Q-H%Vz|H(Z?~CjAekh-}f<9ccCk{#I!aa!dc)3v=rw-o^IFyNx!X7)&?&wd- zos_WWQ-=3|E@-O-e(vP+|5^Eg=_64`=>j?5BHy5H`RXCi`3&eh$TREK4e7V-9%BC4 zjGK^-$iK0Aa0k{Cc@M?Vd9nOg1kU99nZGoaf2Zbu2Kf$ll5iN0sC%FqI!x|%n|v4F z?K|nc(7iVeU4XM*kLx?q_hF1L%klS>zfIIj1R0q?Ca}pa3Sab ze);@%(1q{6in5$b;Ep$umq(E1o+zfh-<2R-#$A_wGutpj2 z494gtj#0R;B;UUm<+-jv ze|xA3YhybR3wXf|?na;f5oP&pK*~=w`n3~j{=OByD*L+w{p&@30(OM{YTbeA!71oh z+U{>kVhlmkmis~99aW7S_gBaZta}h^6FbIB-ahgH^M22~S}O-0VBT+-hcjVP7vs-7 zt}X7EYU zc*6fN$!+2R}yMY3Td-x9xm-sAiyLclG#P7vOi`+_^*5N9bM|{AQh> z{TO-_@4iqyVHar})L<>;Ii|>l|sc&gl9q>Bz3C2Qo?ZxAW z`@UVaH<(q#|6PAirmZU%lnOz%(7QG0$ZKNutm16Pe~{hZ)gJT|NnrpHv)Y3~HrwBqYY#Se60la!_iP9Res?L~ zopZ(fH96PU=H|EOHqGzv%k;Dty4|b=r(Y5OZ=O#a=7%rhpYgu+R)5&QiHx9 zu=GT${}D?+Yvp%a`kvFY{LPkLex|1HwDjYazR%J(S^DoR{n4|u{Fg1gcA=)fY3bAg zP5+an?>kr1&szF`wf_@K&z-05U$FFR)*n~#_da`ntHG~$?dJFP6|(b-xvq}+xh*+2 z-?gr8S#fdGdsehATXpfpO_wZp%fOm_`3;?=Ahm2xaN4=&E}VDzf(7RUEBiAIg}x1Q zgVmQVo7a*rxC>V_Esv^SwxVUtMXN5UsE(Saqxxy52k*`l3q8T=T;IlgPcZ=F1*Ohh zuo}#e*~n+%DsW2#ZrQ5U?`yf}f(zHWu6$4b7T3CJjcaXMww6t_Hnm)U)T-4?;YY6m zY3U7yoaG;~0QO;azzIfKcwtUIui_G7UD`hvg^RX${SIifBTz95~ zDute${>m4nn&kFmAUgUhx22@Nils~+er_bN-b|^pn9KBKJ6&HlGw`zH`up?kXf4xL zEOhmka&A^}ewhv+n%Pcj15}BNN_Xa}LSKkhz9&lbI7+4fv9+n4Vx5pg$hqN}0K z$n_NZH*^NwkgvY2PSrx*>xWK|9HiXfmIc5ryD@+a_H}d>HoI)5hqe21#s2ObbWG2@ zVt=t0bc8C&7WxYPr96m|DV1{Fy(OZ%HJ^i)%4GWr#UffOfjXtmLi_w>^Rk()uAq$? zDgz8$)e%S4)zzJdIE-`S#=Y&RQ~7sXfE538|KX}?CLBHKci+bEvlgG<*t~r5yWh2H z&E;3R@$M*h)KL@g2j9TWk-yXe`EvuSfzA73JfQ*|=_Y9>r@wUghOE%cQ73SH=9 zUw^g)bqItDL017C$1C)_2VD>?9QD7@o(rfLBa(FV_hd=i0E#uY1^iVc)df_x(B0dW z+k%$m?>C9d+`k^u|E1l#VY2@9P(GpQw}gDH^k`LNO;=K8TQ+<1*cC z`3?Pr{$gMNQX$U5CtHG^+-5Q(7%SIPniK0%-v+Q^PpL@a8-6|hC!lq=6}nui1A~(X zmu{J(zq|6?c|ei;Vky^aKR4uha(x*XqVN?OwBN=pbKLADvpLqY^F6bpHmN0Drf-8= zOa*Yh6liE@h?OwW>1X%l4TPnb2Rmg*XjBcy(B;v~BJjm4VMMZL0h&T-E5ho+!I5&{ zxeYxe0~sxS_1g66tGiB{w0LdTb@G=^r#q8h{_>Y!d~xmCNo{RAabekNOhEog?dQks zd51mkvFH8ve9)ec*z<9FK5fq*+w(q-ewdWt~`6qk+mp!Y#qwSBkXRSStw&!Gf z9%s*!>{(~enfCmK!JBRAx%NEAo(t`{#GV)1bGbcN+VfI-uD55_o*V6{QtaHtt1esN zR<3GV{vP?adDW_w^5c?=R=NvTti5#gW!S-r9~Z1#)vUkPHZ`wY;nsv%_@$-rL*HGp z;&NYT<-1(d^5t&LrOoc*OINz(7hQ%Hm%G)gE_at+aCGK6TT420ayS4bSa@DHUL}ukhsIYA1 zsx>R*-%DFoxXYSaU@+OyiIXOmCQmArrj`8P$@ApbnP9VViT)K4WbayoV zT{<^aPnBN)A8(!GHgpx*GF`5Ny5Fh7cco0e%PmRq5m2P(xFzeBt#`{{>K4svUqm$( zGaKRqtC~n<@D3sZjRQRqSr%kQZ>X@dkkuai=XznR3Vq!H)K{q!&F8ZLOkb=j^>T(P za&sYsUDmuWfHvqK5IOu!8i!ji`Io4wqEfE0KQ%DXztrD{`%~Ti-~X4k?*HYV5+V9G z)zi=MoaJhda_eABIgd!XE3rJ$k=R#ted0ERrhbw5W8%oF8C6$Q^;UhT>Vc|ftB$Fj zQvL4gSq-Nx+~C9*LRZ2)6Js4_6n%!F)RpVmfUyj1IV!+TX{`oI14alm6gBDo>$tlwN*^9Yi)&5_dhpek?w|jg-7mc{F7;K$G^q?Hs<$t z;otWBCjKrkzZcGEYioZ`H~z&S@?Xpd@Du;2F5nN)+qD%6UAat;gW>IK&y+H*)Csq# z-C=T5DyT1GbU*5NIFoPTFW&>Lly46<=C;xsn+><4G#iSJ^LFW0kjFe6YOf;elFTL2 z$^xUufgd$W`pEAqJ!k$<({H!*JAmZw(>JAz48ZI{!~kE`M#!4xAbe@ z)AZT?{ZBOQD*k3eg5cwz69vvoa!{?C``{g$Gz5hXs95iPkpP&j<@!JZPZ&|!L26cU z4xK$E30zMIt5Sqs*=!xHs8XS?J=YidLIKMZ3w@YZY;gFU%V6SU&pfAOoQ!ShL6dCS zX}rJ@amQNHqs2c|y1wIE`fRlHGJ9TV&reNTCgoRI`civ(zFukR%WU4f@z)B^%gOuv zdwZ_8=X=RQ-+O?{hlAU{wb+ zXR#ASS)Vg1j#p(i%&PdPsKW6i1Fc&JUwHj`GFf{LlP4N+%!Ey{V!-fP^e(h;46HST z8E&Q*6SLga{kfj3&EvqEn2I6*)?RR!jO65>e244EFoB*qOl83_y$C@;DL{!}9+(64 z5=2(wVs6P2cm5K$c!~QU{#7EJZyvr|tZgHmD|DPsTGu?U(_nLG~H%SzJNS0ahg#2=C~{S+?5!Zuu?&S zH;~y`v$C@V2W@6Hm{qI|&}#4R?hQ8NH|3&OKv-Y&a7>&LgDU0vdV&-KVCvxl_Ut*M z73t1nZV6ePy&mtqTteC;UZTc3CXe>Qh4BE(C_1HDQ0&Tk`DC2M1N0dA`u#naKx81w z?SZ{=AtLK$2bm7wPkMCFWebaZU}pWPOB+(_X3ewa=KCnZd^I>eE)cehVd~0cRr{H> z;-mso7#UqBEa2L1{0uItU5ngp|`5w%* zyryNrPIxtduwne8@f9!-fCf#gFA{TI>(+F^ zRLI0k+Vyrmm@%teN}!D{h6r_zhIkh-U=T##GF4WGg2Pn{Is_m&q3J4^$lj1(}}HU9jy^D?>q0CM{}wi!wt)Xab8dl#f-_oZ?{IyXUg&yRF$Zr3Ks#OW zYIvi7+!o2iqWFlBOyRC-&Vu5DbI-QnAK5~8mZ`Jn z8M9*(WKql{n-|t-<#G{PYrUlD;uWs-VyyNwEqhPX1uNWaEjwGvQ47(?63>jNFt713 zzss??sBy~}*?8@dh^b4k3YJ7%rUom!j@@4GT3uIvhH9e~7=@joI*TF%YTul}@`{Jr zY2`)Divs98_Quj!=A}<2h2vd^I+lfAQCf^exbqU{x%1A$LPo>TczwO&E-|7Ya(nLL8&A8VzH=|5{LN&BRgOp1Q3Ncpt!H@$J&?Vq8-ffa-81d@1M-yeA1pL z*nG?LH}(j~U&5XTt=u7de&uDAiw7<3=Ydu{tn1CMIV{>N5+f1AEPVCnWNHT{yM?^&y9AOE?++WWP=U$|c1$MNLvvG8mEfR^|D|ES^T z@%^QxSN*G&Tlju`dOBTa@4sp7-)a5v{aa}8$Nx<0O-k$Y=vVc5r@i<6tFd$?{_nbI z<%)Xm#OQ(%7vr!_2ubJqY%G+^W?^+GY#*+Rvtv(yuD^RN)i#&WlN4j2dJbDUPy8_>K zboIlmfQdKapVFqb{tj3xEc^hKQo)o-zNZ(}0fLWGcdvBbx#Mb2lt9(*f1z|eXwP}} zOc*~OVb6*7Jl39ZdMA(|UsvNloU0PJxNlJYW?T6td%nk>E%vZq@qdKBv!_{rdc*y}!}kf6?MJ z6Fc<%&+Yw_8#H~7rCmYO!UfiYW zf3@_4jhcSN+@$;e}U1@hADgm9)3>CZ#RC}XY}#o`E0ws zpKs+CmNb2qrEj$Q=UIB6l@A-TADl6Ga~nGJ(bSKd1iG*;3)deL4;WSm9lWLh{LIJ? z93=Q(Z5aq~Sq=iGoEKM2*bw){<^gpUY$X*FGC+XzN0XYUj4VKh=9wE6dU6{OdEb-^ zMPG^_1{CW<&!#*AoQzS)6e3)#V)#-a&VoY$dF{ycY{C{S-3?)gASXZg|~l+c==pqP-hoz1Z;iT7H8^G}ud0G}3c?kX-{Bg)Lj75;6nrg=fw9EH_4U zUf=ijpVThD=`@gJtan z(Xtz|`JRpf1I!$1K4ZLvE=wWy-Bh&<9-RKo@KVqKexM2;z!SL2kQm<(^$1w0V8PWb zy>w$aw6;^KMr}cf>(${@L)18(cxLwm%Tl#x9Y1-@S3kNlQy}eJ{ zd#@i~vGk4h{-bwl`I{_#<87Mu`m@u@f70GBwDdiee)bkEPwK?~;2F0{*z^1Vquf)f z#rm_P!S3DI=K{V3uW6!N{8|K;9Pw!U>(=y01jJ!&+6DB>{Wc%*&6y+nZZx11 zEG;jySYjvVJJlIw>aC-zXHCC5ACrL)BD9?r3?m)ILVsTtJl=^VjMidb)^%lyC5GDD zbBIa8Cx&-{kfda}p8npV#6LE7B9NWIW+d#rk+3{la9ET=tPiu|&O%`$W}r~7sx!#c zl82{fc9~f4MPF`19<05Uziqz{`Buu~spas)zY9r-0XSk}H9q+PzhXR=)974OjX!eY zF~N+PkoQG0NrTWgEDYZ4?!jPY?aZcrwB3i8T1!K4QLeAQh?TeQVzzVZ++bxxaA5=D zWx>0!g(!z9LVF=NCAhpHSO&2xvht-ZD;EWuH*ek!z?L{V6 z<6c$%I?A3??0KR+&#))^%s(z7(x2iV_Tgjlrev6Dsc=eX<-LL8SmVW8Wnm)(U z_gT8p(l=Rpg{9Y8+OPLbwe(7R|K%?!yfv2I{|}n>ct879O|Q524;g;MKmIo#E+}V< ztyjojEck5urf7`&d-7O>5hs~3Ik?B%07#(;d;}M=gN0axIT^bKS7lu%_#N}S9?Xfi zVs*-4-(|7n>Pv2OduFTK%719rsO7Vzt-V;%z}`!khOJ=!?p$9!>)?#T!5~=Ip6}?8 z4b0fIn&oCnta6pe$5iAR$R{fc3+L!oE1q7y3&jSj*pbS1x6cir5a!h4SFj{dW#6Ea z27RlpO$t_a&YW5^#t{gXnNy1(Z*3&)#Rje`U<#YUe{6eBt>D5icIR9=9*8{`Yx5le z;N**`B-h9bn~TXg+y>iIYXyMLwLx-Lv7x=ID>;|HlEL-0gn>7xsU1!wIk!#%2P}F; zAUiYpjs2qn1WtfiEGS6+7!@jl8rUiHJ_!UE^ccq7jHYcl4E*-3Xvdn+-=ns&{Cz8z zw~p3S84cbn%9Wt#tt6AR`9gzCv{K3W*yuaIs~w$gU#4D5&3l!CD<76MAN3` z1nmV+dl`a;h9J2p3Eq*i!T}MWMKX0vDPxd1L=u1neI)KlBm?M>&MAXx2pea}9%VEw zTwwzrH9j9?Icwn}jTiCf{6$gdNZus{tx+q6)$9lNgA$-t0fs>!Ctb(2r^H7Z_zwm8^qG(yQY{i;2t6H#Ue%XZ=tzEGUI|o-ps>8!E z;jRRuVTwXWDw)f67J``Yn`Ai zHGhoZDu^zOhwe&kYS@&oGX|B|qESw^1jI-eDr+2h;Z}bv=aSLp!sjb)oQoCVo)RYj zMHv$2Es}|f941I58|Hh>$5$Y-mgsLwoe^gmPJOYP-`<-IAe>%ss8y1FBxlvDD)KKy z;G^pHYY~V>^kx~%zg449Qs3e7ph9Nvekg|8mTVX+POM~?R3ws{TWKtwexeJS$ z{aE!ZN3^~kIvo@Exp1kmU9;BuFU@YwceQ5`!Yihj>up|0X`%DxOxMO-Uxbu4H9|B4SB;~8lsnvr{6d!rby;`Ym2oUtPR@OrtF$kK0LLzsm zaM0yIioTpfO_Jh?i1N40u@c67+D3<|#8J8tA_j>dVr*23FH#N^qEU_&hOj`H+3+kX z?{(n4Ui7eeV#WI7hfm=AH|Yip*-;NYq?c+2?J+pb`s|A_NhIO}J_aV*NYJnD4EZ9q6LUoX20*3#>3t~x;BdPL1D43+k5gABEKRW!BViD{Z#IY}9 zFFA&l0wiznv~LBdVg%NKYgsR)ptL2`HO)yU)}x+CS#dJjNzqb*JozKv18hMf^Rf_a#l>oPkxq-pX8K{9}P$u*Y|P| zlJlu6jnUghE+b9{9k5Rm0!%}&QwfI`Oyoz zL57aPBf=gTY_4JS7?U_2uS)e|=(m(S$Kuu1{n**UQSV)Zlv?81$=Npey}%mGtOj!4 z>C!2wfqaybF*kJy<_(WKNh?K+bAgkE$O5ZCD`a^g*jLpszL;x#2$ zi37rjzfk5Jh+i&BB!D~vP+Y#DMnnw3X`lkmR>G4Nw(Oz1uPVi66&Q^zyZ^Av&{AbyThk>>P)SK_s)y28pH zi83`g6Lb;f6`Vg38*5I4QKpBY7}-JvCgS91X(fsZBAH4VE26L=8u2~HX|7FISdCUjuswxq} z*Mb-OIzn!uAqtUW`@ONoLuM&!9OISesEAzQCm57%3+I{;gjyo61Mfu`-8l?GeTcb6 z3OL(&nxLcogBPyqGuwH3n0@+OC?TLDd0;8T3d9vNEC6Bb)?!-FgRboUVQH^jtnA-m zx;JvD=Zn_{RKWos!oRi+}b@l}O5>fmDAj;zzA5ci%NAPzXE7QaY1o4kZt z6WMcWQDC%pQjg*(b(aX7G79_gL>ZJFA;9s$zNEtZ%Vwg|~nr+^TAgH9#XjZ30d#B{<+W%PK1&cMg@DU@XQ=aL0)2j`_DxfAC_JP>t9 z5C|}mqD+h(D{6$1q|n-j1>kzoq{hv@`DtMhhCXDWG!Bpbpi z(61x4WxlA}3*PEjNN~Rab;m>%5+O^FZv}F)p)Wfsn&QgDrrlVx!L*uF6kQlkC1-$? zQUI(RzJ&@cJZZgTIIRarSndUl&*M{VSD+gHF-gAZHD|h zA8j%v33c@p2Mr%FyWGuU6H=J=2`|g180EgWM_I6AY4HF?c*lI9jg~8Ij=xEoy7*Y5 zz;UTm1Xld>k!;e3we6xf@P)2+{)GFT+sq%BgvPX0Xjla$8MUxNFFf>k+0aTGB>1SI zTRGZnr)(Zk#Dxo?3Vah2o+vu=R%bj>vxk}QPzRFn5Q+e1N_zf)KECowb&D#@72+Kn z=%l(n2)VLDHa2QZ#!#F-9$Dn1i0ksQzQZ3n4*X@Xag62ESq-!1&HBKsnX^)}=FFP4 zehxJb4gsA8F|+z3s?DlLv>3&3favhWtkCI)fh91gIvF+?t3ebxov;}BVY$c{uror3 zXfAIHsD4g|MJ@x2A6>Y|#HN=@8yd9PHiP#oK4P|FGfj<^FEI0)k!X;Q<`qkGi@mg( z-pXJJ$FM7^^A$B-AS!|ZfsdF*129Heq#G?V#y;;fN`yq}(FmM3>1o;AySx<jR)= z!XB+~S((eioH~s{7G*$g`@o1V03@DTv|clojoivUNn!CSW29wSo3 zEu|nZrH4H%J;fAOV^pRsptULTkI+M?Wum`{Jfy|SY{_9fqWFYUn*_q4kjJLII41uCg{t?3y$I`}n>^|jjJrYAZLfEz((1dA{ zvwd@MsagV`;A;Rme+%Md%sEVan{-Yd4FPX>oKbRxl+X&<|k=Nt72@Cwc3oqqGnT#LU~M zOlBnxLz>7&VFAdFFmt;`nBd;A*}BT$`@pp#5IZWZB(O9q#Hv?-Lh#)4moG2aDG0xu z!s8|ihQFdHD&R6hC!yHV01d2em;6#KNy;#3F{;hU@|8DTGlTb3v75k*W3({GH7HqJ zL=A1EY)wv?5dY4FhY=DuCO+}Llq1YSaazg-?2c4-5w}i;Q%NWZ5gA>mDAs^L0c_Fo z4G1kYG)PvcrVUYFB)*<)c0h4Ngh+cWkji$S8HhRDb0Bx{rnInkAu^Z;%ni51vm?6mKO%$my(Dt%V)z@P?f7W zPQFe^EvP+QdzS6$$C2iDaql4dB2Kb*sO@EnL(K&@X$^GI%`aiDDtw>x#1}u@XCfG5 zYH}e@JeXJK-})+L;}vhy3}QL9>wNX~p~V@qfT{~@nPQz-f4pxQ(t3o=mW))nr4)-E zw}NU$%6%PLW^{~?NCd@PV+No_u~~UZfKG=;uQ;UuYUusKrml|*Y7huYVILr>m z)5h7eqi>6S^cJjvXK`@it=w{HCiacX+FKb5c;jY8a06Z{6QZy8@c7+3daNSa`f+VC zcFi-xaqvYp;6jzzN5!6iOqhn*9$XoFVLrVG|1#%p-}rtDxa zAajE=bYv=e!H%xWU?Yj(L(d>nE^!s*c`8S?e*2zhP^F@bz@(6@=LlvXBb=k+6iPUd zcK>%QSl_b&`!Zyl?H$1SQa);LJ)l!l?CO!}o_R5HFE<9Wffvvrj;Qe^oF?k=ZxnVs zCj}Tv5(4b)yJ}2;IP=J3qOCm}q)rUFy@`NZMhf5*wwEe#BL81u{y#ulUD`~89lG&7 zwPfs&L`-d{XK7->U?g1kXs3S#vq0ukHqbU2UgeHbP&Ka!cg6b{*OkpaDvBwGnAY(@ zglGxFL?~R$t*FgL#tJQ1hfS2UGdgAEU565X@Iu4IFouaGLggvPIVtk<60SZ>ABi;l zb)6(1uB$jkWuh9%6e(z(x2}#5Uyev<;;fKLCXXuMws@+|igOx=MFUrFfdIvn)`Z1I za2)r!i+&fir;1qG@HC-O7ez!3qAkM4=i6Ix@7RWZ90kV7bso3EYo#%dkV@ov^wLqQ zTF=@ki!@g@h3^|ckG`2^q~x1vVnp{sYh>4Em0KgtJghacBD6;M=^4zl{+RYC7|S4G zb=>ruY@7$k|DjD%{A7jU4Q-P3MI;%&<5mgD(e0AeiI}!Ra^f)6CXLFgR_qP5gO-W{ zjb1y%8W~GFSdsrH{jRX&ol!*CASxk1{NHGlnu^&-EqHB_He6#(nc z1_$`!MK%wQ370d#u)mpB;M3rwSG%FhS~$}r2Ny^MTP`9xVL@BKk}~T~gWFWLj^)=e zsa<3>lq?q){TLOrUrGf1Eo68@++!d^B^D|Z91y3&P4`uY%rg9#F&Xp3k!rxyE)@oc zIlkA{Qe5z(XKrm4-yv#;88?{M`_5FzB*8XN6O}MQ!;a)a4-zzQ!W9TvVe}fxw^EjL zrBboPt_!#dJ&0_gp>kj&f|G-`uWR-<#+2v(iLiV6_`Y16`UU z{*TfJdPK&O^o0qs=r@0WKx7Z4Q`}jQmqbtI_&``P5a%jWKR#0sEsF*i@KUE>U1lDH zdU|cOAroUX6$q;>s7a^rOLQrnIc#*A;WN#y`lQ5RAzkDw>5cj^)|fAaos!W=YZqd& zc>O42EzV{M@qED@i!XBjsfgsYwFP`2NTkaX-Fg-CQ_C8GPh;+QDl@k&3eqSyEDqX? znz*e)P`O?MGn(*Kbzmb*02D_FETYm^C}6LE-RzG`rV-&XorUvoz!lM@f+q%o7NeoB z@T{&M{(Mm>DPO1R2|U{gmMGH!4_0YG+6T2^S_pzh1(U!RpHW5?Y*M$)Zyr(`4q{{h z2%BnjFa=&Lw+yU@8Y?8V3=OSTRzneqC}A&2N5NG0a93c1ixoy9gUm9>f{V;feQn&w z52re!3e#m(6dB41|BH|UzxyHQSq@O6Y-Ch&L@I3ab)MUoxwVgC?FTvXGid;Src2^)Kkkz?YHDsbyW# zK@eVx*$Uq=&*dD6x8CuJQ3*Q~dVr*g?i3?C8)bmFuPA7}6~o{=Z9*tsj{uQAOOmpN zrDh3oTdoK+bFsCImYXDlP2ik9UN3y7N(i{ae#qcNHZSyPeXLF0+E7ZoOKYzi81ik` z?a}O~M&fiJN?b$p<%I}zdJ(EK{J?EdBgi)X$`?1WE0ziy7N1O1&>ZcQl|vi821kRl zi4OWA3@KT-(&Nh6rbOWxE)@4bn*xXw>nN+i$&`d(;gtYMSJ@lyc}JzqMK%P9g~Aeg zdu)Ufq1RyEr1|AxZ+&5+%-dJ;8%Q|Wl_{&b>fwWwo`Pf&boeSkGRls`7T9o=1x0Y9 z3qGsJpprty*G!ozditZ(h+tVz7A*spsx1+q!k-mk0JxQLv{?=sC5}Ha^Z$+L_NXJ~ ztp>X=YPU5ITGsTO*zQ=GBEL6QXVh2W@*ylfd1oa=qq4Ip?X90+D|-uiw4Wt5g131t4N5dc|n(X>qa#KH6- ze#Li`9Z2zwWmXwVS)Egx!}z^pAw#lV%%g~uA*)4H-RP7W+i#%(dp0!4#&F4-8_Ygs z_S_&yo|5VAJrApJzN9>Lmp9HHO9`Gu9-{~X777HLjmIc5d$B_48Vknk^R>W+F$-MT zhZ4zCW^7roe5^*U?D0jKSj0#noe2jnjGgfbSO z8J!<0=Cft>LJE*efb9(5A9_AC;nrP6d{p=$K}KOTs`*NJ;7MDPE{mp<9w0#65QK_P zHrsquY@sZ@<80u>lF{BxX%At-+&f%kC*v@iifY6yiU*C+a|G)JB){U z-ATN4_?4*duc6XZHvg32-^QM2u26iz_Rf=wh-vnCXXjIk86SpwgY4D|9i zUzTDv(sZ?X??iZnEw&pgEX$sRv4)WAP)o>6(ZEh`C^VoU2l?V73bKQnV%JlI_Z8@D zj`c)+AlQ$7=-{=X5XgBg4#p}hWLvk$nk=MAku2{GN*)Zifzf_yeRfkf>rs=1j$)Wi zkiIR}8>MWR9WNUWCT_nbF;Y4eLRb#FJae|EMt?U*Pk9n!jqE2}i3!p`iK0r-Gg+DI5GyC_Lzxz!FCpvIU$ImSqib|LK`P1s`H-Qkl4VEfMa)X$c;n{b9s^)Q;{P;uh3eM#mHA63RV?R z$h-pJRcnkW{io70#UxZFjs#F0;M?%H##|=~oM_4UHh5q$wrnrto^QrY>wA9>yonz3rsb2t< zmq=pfo8O{iHyRQlMHLB9!o#$kI^hm6?kU0yrs678!#d1W_tEFZ8s~71hJb1`whn(u zu8$J8Bg9L+N9i$+4vX#<&8t5JqqbtZsN7fO^^h8_2ZTa859+5 zRSDur@aLGuGA12R7~$ZR(*$GU+lrBDPEZ?~Ad;}cqKDlUSQG#t=zU9$K29laC^lSD zxQJhgFTvCYwIUIQdU8$Z0(hw@M^A@A%-|^4m7B*1ma=>dQZ)9`3`bN+s2gf|)`9L; zd3Pk@3l|Fq73t#e7mu#eU9sA1K~GAcuezTJv3uqw*UPFtD4><4BuGq}csH1N1_%wy z*$VOULO{r^gu{ZAp3&5kH=XKRnzHh!LN??W48|~Njrx-@u`Eok4Ue!?TR)Dc=hz^2 z<;!ou`;GN{Xt0*aZrNND?n)u4#}XiomGI!jB0_UT5?=0&R<`GniTtg~5|9z`y($_CyD_4sM}@)s&}(~h zURLNAy*b0~4}LXdvnpTZZrQrndyNCC1ypB=J-6v|rT4_v%l1C&AxzOO6-|sR24t`z zt?iW;ZrG5`mbqNMeVuHFc6x;8<;^Eda(rpY0!rTA$t(2A2bv`QjrDr}-RHTmXpA}O zx0=JSn^e@D3k; zA0S2D-xst9(J~xAkqZ^IN!d)}TjfC(Z0Ev2F}v(mL);0fjadaPfbys71VW)Pt^j0U z^Z_GAC2Kd_mc(+r1}D?U_+`AH-i)M|5W#Q&jFk%afEWVwBsjC8wn;J1CQ{JFe$1qZ z*gkEqyj0}8=@;0zJSW>QED6M9+X7I~F(D$Q5tsD)#;gn|!ec;cu|}yE-R?iK;zF&6 zeHZ*R9Zz~j0jy}#M1-xJ&JZxd^HqQnpkG_A_;^ZV2C7Y zWX;y@HeMqTw_s86O1T&zoz@dXNwHTCHWThRLUIg=qY2S`Y$}{P#Aczz&OrxYR*zHLz)P)G}2J*Oy|=j9?L%H@ZTb@bNL+OMy)` zs+S~%de;W6>M7y3KZ|M~8{$!YkCozd8UK07V4p@eT=}Anl$>ATu^kQ@)`(a|M8mSmTog*D_fo74jfU&m z$ml@jQob{BR>NS6=>p5*fXzsk&9~|=Ae1;n5|`W9z6ioV83h)t!zyUmKZl);C}SUG zu?FVQPB6PnFb$Rvh)DVWMlea(uVNXsuo|fC8q>i1+BeW6$HG>etXnbP)NXS^+wl{DC7$;Ea)+`nSD9VWiAFPO82lrBp-Hfmlz($J6>s&M&X%- z90(N<(p5z(q;97Ds{SHA7K=$AK2qzKf)QDV%i_1vL}hp)5Gx_PZT$bR_wH?N9a*1f z{`RNXj}i~K8-Z`Rv=irju?z{*zAy$S?#J=*BZR<80MU}L@nrJd&+oTxRkin)0LMx9 zoYR?k+i2Hq)v9%?RjXDJr^pbSM-|1TT)8-?>21t3ZuhL_Qc7zp2?Dv&BxxTa!WIQXTV307LrS$wLq_6M z)D*7uhn+u>Aq-S2;!aD;Wc6xD)^6wY3bM@rCGv`lW(E?_R_`?J9h}YhZ;d1*>6!p5 z2Wt#&K#ox6R}aCw$Lu})Os!{;XQ9CXoj_1}FI!-4kx~3+5`cqYGH~FN11`aN zR%+y8vm(VCr^``N3jFY1jaAv4HC`zdlmeX@2=$yNRfD%1)q`4zGZ*fAc^Fb~jKHkN zQ+P`^uxH}~92vR13`5Wb>#dAXn}X_p^?VEY>r@u9Npzm^ijW><3?Ef7x}ks)oERf; z0{KYAk|d&5I>{=g)#1uCdy(N3sTWqr6hj-e8j^u=_=fw_kt>C^s5Na5as+L`U?cWO z#n{VxNErBCL)_%M1z&NC?w@Hj6fs%a8~+zxK&vG)Q`sF>KTX~=U`lka)%@rWfLR}I zR2Yk*HOi1`F{dwlv`Guc+{l=Ix(tj&h=3piFN!gzqS2BX)V-_Y_&mfnr;9m&xj3Rq_xPz@PdrMYP-NjC+N-j0N&tJ!u@j zjlu*%)bRCcSmv@U@z7%e!xyjHoxK?$!GM?**fWxZoJufhL0=}A5v{Du;dc!(Z7*$K zD+Yw>8;VZxiHEGSsz~8^|E&b~UjVB1oJk00=^K~>!N$wi#}zKMkCFP;CIq|i&2SQG z#^pgdA!lQGKoyZ{W)OSjhVYmRXEv)0OzS706bJ>XoK{UgDOHFls*#dxqmc;@&rrii zNt-U*8GHQ}C+f0kd-i&6i<<6FU9$K1l$mG& z(WD&)-BYn~%}B-J!v2qcN+y6f^leGlPxd1|H1LtXK*?xHX5cUPm!+>A{D~cqc7K~J zN()RcTiKAX8!QCTDL@=!rYLX{0?S1@x7b?m?M_Q?w{azgb;&O_=-rlTcdVMjtJTp^ zR*LZ?Y()5M5yiKQPYx*?tW>w*MOTX+sR_jq4STOf2w{YCTO~7o`|4U+|Cjq5X}SCW zY$7GPXMNAf^Iu3P9|IF46|o)?o?ikTFcESDj3&T|pI%gQr!%rpaB)FWI3t{DXF^W- z7K1esjiOT1cyD8Ajh`St|EqA!nb-+pu1Dgt`u!Ak(qBv6_^fq_3XxYjIiNn%Px_4& z!D3Pid=`ThK}GCG&+(D(f#`*o(7IgECu^b0OY}(-F-;yuVtIVZA)9NSjzG(DKRV6X z#{aIW+R}q?dIyJphxwxzt11&k$s)Q|`P~nW!|z|?6ML*G{C^i+DuR=gec8d`Iycg6 z<#HxuFiSI=u^eN5?P6s2Vc|wc22XQ>><)+O%XpG%eKP68{d6$K(e@+k2}M|DI#N@7 zZqi)fr4ULWp3@H$bk3n zLU)SxKz_IT7|tmA{7)bltJxUI6J-eSyZEnH6=i9l7&}NIArP3ND=nc4LvNhSCfxY_ zijFu**0BXz!6y#GPl{@Ok>L&WG%QP;te&16u}A;OqTe{ClW75vgTM-f-$CFP?ETEm zYhdyQYvyPQWF>OkE)1!>C!@q}mn=Yo_5>Mi0B(BMdNMvcd_$Fwn*|j@o+dE;hEv1y zaz@n>aZ6D+h3|Ph0aVMG&;e-!icD&N+K6B90^JGeP$y9}S`*!KIeKoF#ISV_uhft) z+1ELJF4DSPH12k*U2amsU4z(zBf|*}A%Gvi2Fw4*$&P1VeaYcb9iqaCol4oBg`QZE z26$$x1E{AR9Yb9s7;5N(S3Dlr9O0deK9EiK8C);@JzO`i9spv7Hi*uJNIIcd1on##IHH_ioH6eQc%E=`<~q3Z zm9g0t=Ys)PO zfTCRu(`+><4d|z8d>Kzt&1x%`fRwi)5;NsWtsUQ!@XnP~u7tR`aA7XE*~FfPIbMVx z1hM42oQXNhi)0Lj%d7@nZFI^^b|QFXs3!>PTd5AYe2Oqi2IH@CVZ=^SBquon>|(bd z*j2vu(p1HYN7u z3B<2#vQ_7SzVy8lUlr308H%E-!m@IerOJLABD+P*XIKQzjFzCscu^z?V?k$+2iFIa z@v%%uK^MMvz=$O(Hw-*)4gsl6!kfOdHY68^yBOZgJ+EJsVb~hABVjU-I6j~tQyNG5 z0>YGNTpemT*}84TzO_Fz+J%t;n5?;*R;*$(-8#R}Au``QvjM^wvROLAvKEgtbnv1RwMg;<4(cR?q9JTw zw{M&rI$&cNK{hyI$6yyu%_JvV&C)p0lb6lWiJ11q;bT6VST2&lXeB>MZ3SC46@}5L zDCO)N8Lwy@aSs|d3gzIAE9NSnG^u_sZQdw=Un)#awcfEy$p9BjkOOH6LPDLO`c(eErU`}6t;?Zy7sDT%< zdM2xkX|(sNOz*OAH#R^v6C%4ocwADw6np_q#fr4h2AL}(jTRyk%)pMnm_|f!D013I zYUw=*o0>#&+0$Z`&lnS>YEaE(BV+7|kVyuDimnOV7lF}^T2QowMy~ezvp!ZEHkz4V zE%y6rwKY@wNJvKCd7%ZHSyDpa1jB~69RW-@?VSWo$pF%;YwEIhoyrN^FU|g=Z?g^z zaEz*#$9-_OnEU0v?Y&N9Olw?bLLRM+qg|@uk#{H7Cv56aUYI;)(}!JZxS=g8W~(oN zA+$KYS(@qqA|2F}WDXM~0%rJ_w%^vHK*hL;U19}C6=w3IkD4OpbYx+Z)+MGQq;-!u>;=SuI*S&rI?~#WRf@-x&H@zprE)t zlI*AikunQ4nbdAEureShs9>QE1&=$*MQ=03yqcP6ejpaf^syv=*`|vQ7P!B z`EmG9s0zuad40SY33fWQC^AO(RZF84%3*=5NxuY4qc}mASE9Wlk zafOwICLF&VX08y<3I{X8i#LNn3)fcQGr3&wb?RDfNJ*zRzJ{P%haLyPOooz<8lK#J ziZ3T)0svBw>a1pTm3k9W(2?{bbJe+ug%GiUqQhpGL3WTQjw3~3yHsf>H_9v%%z7ab zdDZwWa&C!~&|M^!TBQ;xg_eT|Hlf>y*)czb9tn<5G)U!&eb|9w3U=pEE-O5&z$JhZ zWQr098Q`C4sUS4=OtXXGN=W$}p-6R^zNAbblM_D{WT00Di((I!mo=+S<)}U zGWfFtj|%KpI3wUmmuLApDyZ-U4rV5LK&@Y|b@22mK6TFh#ZtVXYH~y_+(dukA}D*~ zxe*?>ljl1{?D{ntKo;#T3rBB!dRMoXYd6Gs@T*m@emV_Gev<>-)Wb;wha!H6|!X%rwz3yIZn z2+^Pg>16}FA(}&WnK8hIIJruQxB{&Vz9c%i3`moTwa;cpl3O&r^8qqh%i^WWUOv%_ z+F~zwG=9&stg9`&ST8iQFo2xq5pt8h8R&qV@@EnBBA*h<2=IkXMAR1KHg^OU%noJ~ z@PcI@^3LW4R{kN*ZXYw=noJU3w@z@vGr~m%aL@@)e|L5^iXX!88|R1&`msO3waLRN zi#Or>I4V9Ijr+6BKCeWels|SLQwH+$asLGSXkpIBn>|+0IK&@&Q1J3|{Kee|qgn6G z5SIt_!^Zw-wtlkT1JKBwBrrc2Z=4VC1P8fUD{W37I=9C-u@T7v){k68TA_9eQ$GTn z(E%Jh_6zSj9QTi&DZS~p26)@O@3rLF?(P=<@|%|V-@IR0{N}}0e%RTN*6QbZ##`k` zGQ{tCnU#Oyt!UD`{yFU*$X`fZ^B7VSA3=(E=neF79h#T)ew$0TY?vKgsWt70nCQ8a3qPncJ} zHKlm=sgM|3=91%pE(I}jaL#j#EpCnKT3V+Ok)@TdntV`8uH)4k;!xzumK@sHt4LR4 zDy%h{UYUP9F^O#zpe z@i-Q_H)AjGCUCuo!OqS`*!1Si+&Xfw^L$cL=LrJ&R6Edtw*0Bm7w%u(`NI4^QbD{- z;vk^|WOV=5%AGHGf~S2TDAV2)l@to26-^u^j-tUE%R}{Y{Xy^H#%6zS0B*f`>-L?y zpMUY?SAXliV$uY9%c|N)bj1)RC3WVb`rFFiZb*!67f}@wFx_ZWHn??n<<{NQq-~U1 zgTJlZ%Eq|3!R@;%w=XdQ&%VdMm=n5SK7V2M`SY!Znj0tQ)_Zu5dN{#F6(R#vBLRHH z>Mx=d$p@9oevlU~Pqt``AQw_*^Y{wS1rC0Zb?{SWudy;$44;T6rLax{u8aBrDNsGn9fOCma?1lreQ>xZ$+HaaMn#YlMno|u zJV}J9l6M-E1V5Hh68^D(398@7OMuT=x&lmGXxN9)AM<+d^9GV$!xn#U)^VEvX$)2S zfCrp*<-4RXkja0dPi}?z7wPw>W{?J8|j3V{p8#x6l`expd)>WnN6Ng&iIp}>puxKbenr3nO=?_m1&1;*A!-ce(Bv5r|Qn5OLwWhlg3_}XIx z*RM{TbtLP2B`uktnENnq!|@&Fc03C8dKDb9GrVT*v|HI}cp7(#@ zbP@oy|uJRF)SV+2LaYz?p?G<{nA=;S0RAo~lSe!sJvx6{<>3ZXW z!b1Amu6SusBz@JD^%g3v)Jd(M3w2>hu@+Pma~0W^lrF)CdJ{x`>dCq2FweM@{m_AO zDS%Vuna1)-^+I49(MtQdI$4>1-g31m&ktBX-Jbc1o9xr|!2br$DXawxRzv=-)5j$> zp$wUIhLm7Q87^L9X_d2m+geI_O{w(s3Q5o;Byyo$Bq7F2o04r9%>_fTFiOh zf}uc5LXu5;u5(%38&`k@IIE2;dvP7P*^g?MpxP@>%l$(0`VZyYK137RIQ*U0W73J2 z?a~#^qO^8R%y_Hi=6W}wh82rYk#b9)>2WPi`@#aviOL%$fCcIaGqwl{CEVB{OSNgH zgj6U*uciGXjj8yQJ{U6=TY@5M>0kch+j2+JJnM%Bq}54+kt}TND@o8CElGL%mnQti z&5YntRM2gd|57cNeaU8zs@`)LVOhm4enV)eiNE|N_; zrroGAT(rx2vqRW_3gXkXz~Bhq#;AEwa9V3=VjF#S2v8wcDT7oys}eZLc(OWtJ{u#m zg2G(#@?US~5qV(}Ys12jtk1dQQ6aFGgea8Uqf0Px^3p6zd|KFX@~c%2Bxg`+oT=GN zGC-AQgpi0X^Fv)qT@ZE6+#L4qh&4NNka$Mjr$CH^+h-gM2^YpnSH?al?w&q&> zb`8vZj6J3xM5E|`z4rPw4HT4j+(!mab8X4WFlls0dRg{Slsxevucp&6o1R|@6u$eKza;+*--+NLb&Qb$QY zW-ASBF}`-~gHoMrh#85)uxG?csZ@0Y-_{6-6-%|rhw5xrY zyTvCBRbb*&E_kA+bO-EY_zoyc-egD!|4s2D7a6BV!1MliIOT=OH+>|qw`@a@rXm&K zqsy*WH7VZn;K+hCi+!mmw-#2}mK$L&IYa>1Ez(I(1NY)fqW*G|X!( ztfN$qr_^Vo1HCG za#!gbTE;pjSickh=uEF?Eca>cC;{k~Ri1m{Yq4Iaud!Oo_$Rf{Z_+}(v&|<_mqA+a zogE$`JdgiD!6Rm8MUMdGi+uZG{n7Icd`3!YF}V=_&8odO<1r$j`&DlZA)FA~aw7yc zS^3&)ackw*N`irq!}7Z)&#UixJ>0S%4Au_+`qvws3UL@HAHQQ#O+y#VavDW16}WL4+!h&S!V2eV4rEf1!Hfc|)VGL~A% z1dr`8GD1DZmumTVFhw2wr;|MO&Z^Ef9`u!CPr|^y*cq!K1a{F}xi4SM@yfCuR()+ zFPck<|Af#U>^xklo(yO5FLtGyli?75J4wFjkA69`RsCN6wq-={Cf<^ko;r{8U1?ok zd(BqJ1@H3W{t_OVt)A{wFT77kB6*)0RXRKVR<$mP+AINuwe-}wU9FSN-E{6v7^%{jG4 zr*C*y4iJsD<*!RDv$Ags+lc$4A*FXDC8l!AKCbjYc*6v@PMF1zn<34EBONT}eXb39 zn9u%Jp)LVF3B$s5nVh4U`IYj``<2Al_L#~WXrR`m^H_5u`Dtz(F+>a5$Hh0~mOdl$ zJ8m0P8mz`P+`}{eptDq+;9d@7=ZsH-GUL!mY#cQRDaI+(Jv_?4W3;j>9fxPOa6pK& z%!~mCTrx!XMhD=FhmLTm;~>4@*fx8&e`WIYe>CSF4=Sb^+oC{hkM>{tB@i4P3wC{I zRd1LKodMJ3_BN7wBi@+wySv2#kv=6H#Ck~g`ng0Vn`GxMXALH}v30&3w7%uzc;@>N|0`t%Bf(hiM zNt`&fT7i;dDKh-{bVkc!kcSS{)0LQVe z@4nxSqR#bcbsg%m@<#Zpr52uD_N;;8>c8hI=x+5=cTrPhzDMRVsLYozn$D>BrwHkf zX4#)lw|4>EPWACwx%OGe z$*4JX>wi&*>iXx^&G}q$H;EaqMvyo~Jl}fDHiG#t_V%@?$??Ixj`ZSKg-_;s_txjO z7&biP`l2tqn@5gl8`85;$Xtj%%SKVJ3;e}+w7@XpT^muFf>4cZU*3L|4#~X@R*9m< zf3ElDETho@k8sPad0IyAgCKlqAeelJx!dm?1;zLo{cM7GuhAZPw$G(MZcR>5mZ$7=?mP3;p0xF-gx{tq|vc<{`o()%(M(IfC>Rs^Dc`ey>xRlwPu<9$A0+$v-ixMzyF6axgg|a->+}|{dsDqo3Cj3c)j;@=YC$jmX*>ofm?l}^EB-C&K)0BN@3MU%boAnpKUyRwDkZr&@#K>>VWO+uJ3O3QVmIt z|7f(A`uK6{$-}2VZagGf&_{lQHpbC9I|2vl_+~H4U);H!!^n+QD*NJYQHDKCDtqws z1@{;H5B>V~Bg*ZP9Lj#><$3RJo2rJ`@@$6WlgkH4C}yA&B!GW!a0KToEGX(L7wVs{!ud$wEF&J&j<64g z7_DGMCu7Nxgz6wrkKn*BTDrXa%RnEll33i?bq98d^o74q8Ch8JBZc|2Z{kn z%QWHy!l%$SA32=RE&x5zj~_4P=qd)h!N{oi<;IHy9c0E!RH&uA63BGA%hIL*$H+x0 z>0^NypV_VO?z>ks)Dt)ZFanA)H2Rhb?WJ1yXaY5;ENSwjU*Vx3@4x`-$gY)S7e69@ zSYy)I(w%EjG~Zd5a=SN`3sPm;wxby*>*I$CEpnElOrEJJIDVSVA!@u zQi*X*N@QaWU<+UE{>l5N2fKXLL!yA~Z@lGtbYy>nys{sOkuXv8bDYgHRm*l4cKM0? z$k#2LKuri_tpzg?-sPSU!98C}vIgm``d@YU-;7ApI3h&K>#bOEx~RMkcNR{O3YC+u zt>9&$W2f^WOt{t1@(XGQ#%)HvjDj`?u)gIj*R~Z=TqRsa0S;_hMR+WMss+d{f>Z9I ze||&P9=!^EDcQrPi=ia7tZkWmJh-oqknm_(BA9tI9eXFkw3Co}H561916uyLCrh?$ zUCT+Yw8&Rb*4y#Je;bG^k#vD1!^p}aBH6;xDCCLoTr!W8ylM&uC?U-eo>en(S+q2X z;p_l3HB^!e=S;u_F%_!%NT#2Qr5HK&mBbQpf>|kpxw1`N=obaNsM8|i4YloJTo8+? z50{%FlFOZ7BirkWH|EKvt&_|D-ddP8pWM~7${I+*EqyjF@PA=C&T)c z^bBwF0pp$QUw<q z|B{uR`O9y3-WFwL#B>^#Wr-+_lf1aaD$4oNxVFZTvM3>tGI^xc`PPxp7YV%(Kr0CR z5}UjDYRDx{q*=xpndjMBifocqYaa|GFFaujXR5-*bh%9R9%S@@QB;?FvS+Szw;-$+ zVx_5kayY#dEX~UwDQMgZB5vFSzzAe~>)N|FkY&}V`sRN1sg4hpQnOzu8kOYp%h9XY z8DL4ItVMBY8wH!<2e{||j$To2Fq4A%<`r&@MMpHaEeatTwZ3Rfl%`#opR(l}v-Bt)Rq6aEm8ql4HC9BbL z*rn)%3`0k#ZRz~c4DMZ$ZRC@t80cUx>w}|-?0jrP!Q;0Cr2SPgmBU#=L6*WYWJbR& zv1Qy6RLCrS0Dm!F1(VhGhzRvH{2XB0TkIKK-L$_MLOyYRX4*Tg?DOL|gi{=}X*@HxJcxrjQr!RlTuM%f{ zxFQ;y?HwZ>?7sbNF>9m@oE|G>Xt-Hy(~?)4wXny)!e){=KWBIAh~%b+nNTp4Ii>x~ z9s;_#P_|B=n_ZuGea@INRz)oV+m$kcB&S2cdQRZWid9fIiJAA(Naa3)Q+OzCQ65i2kfJ*oUaNvS+?L5M6?;u0S(ibUb!tyl$4N{*nY7owOjkK{sY5P< zPK6R8fK#85I(&f073}gIWBEe7*25C`OA%9{>D6vri-}Tb*bmZ~=BCGA4z-v&)Bg^La6Y2L0Wv|QCg(TmmwD=g0X{2y@;~K*l&=V@dLI33KDf&w{Y%{(v#8H% z#V1TT|Lp<>^@Nf_13RCB1N>>70p7P#A+C$0DJ(FE`Ot_WIgnDpUl*v5FjyIQaOI)4 zwAbU8jF$sOw)+(N?pb+&ZD=??jsZJ*E((dwl6|Au$ayG^TT?U#eC!36aoI4@! zp#{0JnQ_Ew*trmx?Pu6EpL1ru7b67Ba-_GVGr~_jfH$-{RBXAvB^097@+EOn`0oz)8ZH_LRs z?W@U=N*Vf>^Q>Z+6(MB$E@k95rGn2`CnLTC-I9behMftz*v4H3QpelIiJSn8)Boei zcsv8tq=alLNDbm&3mV`Nk82|QHIK?#rJJJJg&2`5LRCM5UtFp-$v&h>PU*BSCwM=g zKNvE;W(CdR+QZusfex;|3};5XQj*Y{Rn92Rn`g?5dp3hh6EzXSmd&TAHB^QPuS>{= z)?Z|JlGl{z>g44=7>x?;Js<(GJb$fjIbq=l`XC#Z89p^}C<_YD?;7k+HBq&RRzUsY zt~efJJVt+=4mmo*myP^wbyGWGJ=i}8@+SM{6%PqR=lWl8a>)%Gy0KaaTrB_)^gy?9 zS(gb-5=Xx3Qsrkn0)Tg6IbKfaKXm2gWCUa0@{N0DqBiFagwz=KNG|FV(C^hmPNDu6t*Ek=gnJ z-CO_imGp-Z;;ZL5&c3`y5^Ut$2qfEPL|@iY`~B5RV$6L;GCSxy9S2LJ0Wzq{j({im z0C;26Jh;TGrEgjjv`38TfRrt^=BpOpL=&1&85&iKVO+@E;LI7M=4%rajq{a9bEG=Kf;THriys~_uattv30f8mXnc;BHQ zllWfmAqq%w@x#{278+|OE0suCRzJu-Y&kB75gaxtPVf*nT<1V9gJ^8hz;t}Z-!=)U zF7zqEGpJs6fSL(XDT<%$JAUZ6zE9Dx8fqw!uK^yP)&qDP&mcWGJ5psUkVXrswxC&} z3ILIQ*zDUWsorNIID^FyMMOB(v_o5ZEilBHG-aoyYEUt_%Kawo3YBWWQydU1em@Sp zrVo*Uw5RVzvp2Y~Gb_DNE@$$+UO^7hK~i{yWn|!?ZDvxUb#Bh6^q>U?M6hR8Wi}-h zWv{4r#aqQ1!rX=p_Xna}_cy4}Oets`i^HD*ISEZZg8DjYqXHJT6l}YC^xvUV()75= z=jw0)L<{3z@e%N20d-y=z3co{qRIUEr}3$1CV+y|Cp?KX6H^9+BMC0?s^RIWt&TdJ zRbSci%@v~_W!WZ2Q>3RmDhMv0#hb2X&lc%~3}lBVVn7i$27OAX^);JxjYOv^C^7%h zLWP{83f&3y*Eu2f8FpKQ&V2FBw@{6ZZA1hf*7MTTx!xLfBD-AwWt+wjpluNm&`Q|-5^LFB#8*7u zp32Fj;v1GM=)l1X*L&`5V-H@S-ODPlWe~iiNK*H!nepQPKpnJ}0YU>RhpR`0UAy6| zB;iJ|3=t%gJ0s<&+^GW{&|}R}5|ai67RS<@v_Qhju`W)mu3F7~W0hN^kqs6qT775U zITautXo3C7^jJ7KbLJ6A=51YRu1Ib)s-^tDOg(Uo+@VHXIayu4Vctq`s*r+dGWHY| zkWT>|AH~ZoD3y^BHB|_vBvh~*Yo%6ZnV^s?-?Bb2M&UHWSFRILS-?TUmMO3T32wDq zEPNI|aF+9>b!?Zl*&FpB5!5t{U7{;y<_L!zw@URn4q+67E5pDNG{OXi3S$_q0~wm9 z!JC;c8?=C(y6W+K=0~9sm!* zHo{W~Ezq42i1ia28e#>YSfD2BOLLvqOZ?_}1oRoFsXwvuxYZ6%qoBcM0RIg-tBnb` zFB*@+I2$9mKuK~r{gZeu5?O#c((>2a7eIefw|&ria-;dO$dKhq*;E%e$_&WVHu>P{ zgF-9dp1+P9Jne(a@q<#PqL&n=bqh*u?G%1kkWhH!qfZVP0fnei=9I(-p15mH$@`J5 z09Sl)y6(9OlF_2E7E(gnhXiH+;ljgIqJboTBAXgkrcr^|W`Q2$cte{Y3)GTwPpcIe zFQQzQvxzkBOnoe2BMI=MJN?#5RVHZ&ULjNBV10aaCf85FGuDH#qQqe3lfYTsDo;Jg zmZZv`foSDS4zGaQ@wszJ6H<+HF?u3^H(m2ZT|@w}Km&ZJYb6k^b-@eO(OLsQ7c3B? z#Kf~xe9TtFIE}ru7{&AO&GiWfrUwcEc00v0xmOHTB3XnF=7^g0r5CHkf`N$gB(<8A zy&D2vLiiF*&BJC*3NkbHwozJw-$sv)J1yZx|^BA7{ z7(bn|+y~?oEy5!-F)!OiG{Q`i`f25%CJP}lE`zS%8*zjYkR)b|7N?iv9wTWLJSw$Y zp{kl-F~pQ`SraJEO5SqGK7HDt)$g zK+=#MK0uC+2)-B4%I0s=tMhxxC=OJxf9@VNVy2ct8KwUA2E_nzqP7iYq>?~lL1d3( zIH%O&pUx0ycOfWgy)TBw1gPs$5%fXwKf8`qXN$6vLM~2dy~V?e0fNOw2|kFINOo91 zZ?ei19LhmKg@Jv22qh643ZNi`%*?eg{rCh&p@`D2eowzqAxkGpqpa)6L zi1Z=I*Q_g^NaEB`Qap-FNxH+g)d7;z2+_lo$)yDB2o;$MhJLw$my6JhXE2*_V z+<%6bh|ea2A>8fi#%=AhH$Ht|cG;iy(Ipr+pzTjj>x1<4EL8h;QbQg`BxVb0TYzuR zd-=AXyaaZ_(oJ>dktK{b&+S`Ocw!qejm(FhM5Frsx-7MmS78E6Q?lKA~2{Y|=lO z!eEi3Jw1uR;TaEPg5%pfPEC@hODH@zf}wDNVsT;N%H#Gm%x@r_f|FC(=0|ilemC4- z$7y=45sK!wOQ#>TR*yz|cuwwpAT4B2e|+vRMd8-r!s6#E*Tu%$B&tpv*ss;@7d9$>0?9=6(+0n!AU&cHjk|F zh!hAF69Pj4v9WQ&ysSGr8!CEbZqq3ReUxab7L@SgImpjjqh>*i-poj7C zXx0^0@1E*+RBS4*?o*`BjPFTpb)Pb;q}SgGh1GqEG?>?#s;WyhmFXg1%DD@Q(NV5hT=ON=ouCHX#@_WD+ysC{Asg4mPFH$lZB4dg%h>=XY|1!pNfU0w6ex6d z?ZF0E>i&4N((NM6OIHI5?jz|aLWR`$FU~B{^Nm$MLSvn!&Qfv4)P~JGc+82qiAyK@ z1w?)9*0T<&`rH`{Wc#sL)Trt*^oMgpIb-n)KI4-kYyoSQMrc(Yl1-f~6$NadrmGZU z7A4xP_s(>*hYE+xAxO7AA7u*{I$LHwCF#gFy8O`;A(2i@u&v;-rk#70AjoMNOKV3d zY8P=Y6&t4Z6GQLWZ@yqNCB|GqjNV(Pi`-G5ECJjP;uDRLYgxn-g%Zrbltvx^Pu}`+ zn37$|Xc|`PvP@amW)7rL*D}4@DYcKQJ?Lb?wl;vSo`gwVG=h|05?2XDW?W=utE&z$ z2+)@AQOPp+$p0Yr@hfF@lcMu;FUoW1v8W&E`uh_Pg>?%CxtzjIk-ph^_xL{+%mNEW znQ#z#894kHdO2JAlnuzUEL@Wc=a;+mVjvQV^hVN}7yR^z<2SoNLK4Qji^E*<2? zI-*mOv3_AsH50z`PIbdC0bgV{qzWSolKhMAV;x+aS`s4I;kp60P z-ZuA(x<`+Sxd2f&DdoIdd#OX_@Gx<>ojU7)<&$>r%Z+G#01$qP3D4Pivmu1GM zwRYfHG_(DVE~0F2WZ8cljUEo)>ZqxTtOZD;!ZxPrZhf|lbd*oO>%HE3(z{W8wv6cU z?;mb#GeN)60(t&XR734rHP{Mxrh~5~P?*1bDG%@r|5+`6hC3X1Rt=p#-1y<|Tf5ua zy&E@H_!v!vZ?b)(%}yl^l1TY08ohFChnp&8}BUak5%$)-W- zB86;mV@K9bb4jtOSyv2;(j2BOTFk~=v?&d1JD)n|CT(-0TXhXqQ59vYQ$<_NvmyM< zNVZmK>M~NxW~nrKbE`9t|7_Zl$;xQ%kTQiicjhg-noG^SzNNXuSS@>-7>X*K+`#|v z%oJbus0K_jk5}XHQ~)Ud4ff;k;qsapoLhKfV~i}vc#36!3w(H!?HCDfxZi`_ih|Kp zct)O0d4trHZlV&evI46Y?VK7|Z*Eg8U#|OU?JlemjO>(kc03pSu>F#^|Km1HKEm7` z6Yxcw&4O|-yHP5#^~x?TV`BQeec#i<#tst9E3c)NpxP78NnlO?Q|}x3uUDlc^6tD? zm;VB$U9E4Jw3l+nUXvl%2_rCMz91om+v#%LMYZ$1=&6WAw@C6Vl2y~mwVLir-AA&; zea%GftH}OsFB>cBng;YddBDZ~m~&{`<@rudL5#gzXQvj(?!H-ULj1TX!xT3k^4Z^T zR{9VhgdI+0wc~SHJJB}jDIF6ky=z_UyI2kTRN3&zn0nFO{!Fx;Hp+6INf6mDcTpBL zodyiAgQbm%BT)?&~$!33fX2Dxu zqZ8y0v47L*ds>8GdDO`K8D5`JjC1DvP^OBCS7l%`2O)~4%h}(HU@PJy^EPwg>vXsD zaf^^P3`o2xsNfqnm(}z#%)6+r$#poIqrQ;pC(f|P)4CS`U*;TBN2BpOux9Q#7{8m- z#D_tJ}ZB9Ek8+L(53*~;mi?wfZw z4i%$UpJ;?tOEVXy0#2>ug|YlQ9+ed6FCnCCK7WRRuR~pA-(MX$<5Q%8IzA}ReHPhb z2FQg*%%#z1qWa%M#Ov%b3H`@O_@(X^UuuKfn$gbrxkwXrAyV~JeR@(Hyz5Wr%cx?; zoqD{%%2vU%JzPVxIGsfCulbQE%jR-7B&4|e`0qAPx5?~m;l5m+MmMGHi~Ujm@IED3 z%L(&~f1ZtIQkaPvhoWIFyL3{9Z*?6ccv{Y6q%hp30Jp_$`eM+%f6;L!>okuu9qbml za9O}(?+=ca_~Vdx1*A=9g$w{gvHN21*BpGc99nvlBial4ktr6ohYV8+d7E{Mi1JC( z6lg$DcnJyt9#ff?(kYGYLqZtQ9awUJIn}rwm_~dZT9DKMh*xGG$>zYXWN=7PSR8bl z7Ok#sZ(N!KF6G$AegJ-)Cu0PO`Jp>qm{?0FIC~;jpUK>L(t{I6pE+J_GYtwl&M{N7 z5dKuhGM&a^vAE%r1Jep*)8gO~HsqLMSCyPmLqT|ThepFnHV1bImPPu~ArPwlgZ!Tz ztV`#W`(40dG>|+7q~T_3oh#xC8sQ(8nO2L83&bvv&ThkA1%)k=C5F19Xwh~QlP+66 z5NQ!+(U5D4!zdhp-|H1rQg+6m3=F5Z5=Hy&*K0Y+w30+rx{9mL$o>CvS6$5F5Hy`nz}U0r(X8Ys*KjSqC-ZdHB34Y#9lVkyMmy2&W$2ET&9n zxE&kf$fK8ngdxii;~U|>_?djY{2_0}J+imyv@?HTn5Gjuqkoal9`flptsz?pAMTo1 zNm3Q26)TV5NnKPIIONJB`f^g#t4pq^<7qS8ut3}E*H;+`uCZ*42h#f^37x4}3{Q^X zILU^&5U(Ey;tV*QClBl$~7!Xx3K&YMM%0 z4b5Q!TR4zKz!jwE22Z^sD9;S$->x+uv2DY!uGH((<)v@_>-_krvd7TxBSiluA45eO zoVefbJm1~ye$`>d#gqO15iT0s@4O%48pVHoi-W$v#kV72Ii2huktFKRfy7aYBBg8Df7bO>Z z;z$5_YcZmYuUeICFR?DjN+ii!V_9prq4+lIlDx6|7PGn4!CaOUA-6Hz?TnLoM#A~7 zk}$7NIctF$&xpui9-hav)cJ+axLlRzv5_lQa?%6T-@!-^hfEkUjRd?gQnkjB1RIyZ z3kJ#Y!k+}(yw4bn(^|86abdat$7e3?TC8r+#M(llVB1d=;fXXMMSS7Y$7J27ZqXbix8wz1RU zkU)>#ak4%K_0AZ_E9gbc!CC(hQDoGQR5&fuDu(Ixd;}1SS=#JL_EboMw%z+)j=%$Q zb{*?>VfT5cpatr4*@6mw z{45rFJzoIn0alLj?_JCkHOI5zYc1hrLp{80rDSeBp&Aa2m`#*UBwlN2$$XO2{|(;z zlvM*>O|GzijziH*^c7WvrI5vq28;Ydrzy_27|o>zmv7}IZuAbe!5vkZmsZVM{Etu1 zZ?1p6#PBYcT%Ti-W4p}Y?=|(0UJs7emtE0xSM*3LGF)6{z zmA;j_v@@O{H7(8_Bzoo;@0lVD4Qnv57&PSOJUvCyYdM>cUO2@@z}mE8dPwcW$I?)c zFk($OUqm%fN4X3IMI-_2bVHe@O8(>72qrk|7Q!Y(o7+)siLYdq7fZ~?I!w9r&1flWz7}&et!Id%RS2AJA?75(Q{d8MiTZb3X zkAQvWoI52U4RPNoN(2NqY7mbwNQZGST{X-WRvfhrul=V)3X;0Jdy8fd<+m|$^czW_ znP%YCDsmA{##5xIR_C8Egt-JrxqKtS9R~T$|B4IEX+Pl0J)~&@f`A3Dow2BYN*VNP z+A+%o0=%a_Ttkvqb|pDu%^>v2am8w41>lkWY*qBNVO4%;gp|jx`)9MU2;GQ_NT1Xi zGR%4Ba%Z>}gaug-9ES|zIgLxoY;+pB5Q?u+oa^6O|H7cClB}q#3ytr8ozJ5cNUb;3 zZd9}~&8qI;vi%<@=H^P3wuktQoHel{#LwIK>3c%_yaSJTiBtBA>EN!jKqA9Ppe6U9 zuR;J`k}rTpS;7{lWU?|cgbeWJz-;(%ctBB5D9=Wvm{o>+DsnEH8wgv+6sOq!t`IM` z$~EX2b0jinvy8&kK_iy41?nbeuCOjdq&qZ4z4}LYz9m0g37(kV|{V*!g^fz8wv16Qb<}q=>bP^%u^EK0d~F zXewEepjowWJk=x^MQN^ZRlD0`))p@HvN}a*#7HwD&)P>Gn?dUqK!&vXTe*i1z zl0?&(4p9YEit(%#0VkQ+>9QRPo21&!5eRPjVQJkTexG z0MF1a;q7Ma`M&N)TDlKX!gU<+P!R8RKR2s^?EcMt-1LNhZ0|PF_fdS?hP|49Te`O* zS!z1YKaPhxNG7?R-IxFR-Sl+z_?LFyv{yn#UED=3fpQX<=hAQUgZso6JHqEdBU=zU z@0nYx9pI>Pu_wJ;&CB}H&t?bkqnBQDa>VO!o>ouHQ{1T@BFhui^!?828a&5>L~-Y4 z8w~ojWj{+VwmOR`%j2_cBv&xA%&ujzAu~_z&W^yac}HkhxW@lbSNrJxeQZ`b|G>!t zx5CIGByNYQ^1XhBoNf4Tscn27ooZbi>6r%NbQ*4U%0TlM`~EkZa(%BZ6m0l-neF#q z{rhd&mw+ZwkdON~tvpXg!sT?H=5-VbNaqiv6OAJDES9466@N8q;Z{iU*7G}+nWEpF z1iqAjGH4y!ROGq0uCuk>8REq|+(XktCXzh+a#zF!qzwHCRPetRs?iajpf{lt+iEL` z`zWS*rIYMbqX4#Moe=kHHRKZxRmvrUd(-UbgR&$eLRts>WOT|m^0HF?Opai$+dK{_ zo+316*WIUj{MnDX{`l7_LMeIpHBg7gkSIbwqkCK3JWr5Vp-k z3Rx(52SykcUMAt~74O#B;=wbx1yQl~5oKMQyY6Vsm+d@7P6 z4A&OIoh0QCHG54~K|D<4ksZImy{kSZJ^ob>6X#70K@5 zj8mBi3^%7R&PvQ*);##KP!9&bX0p4Gf{B&janvq#VGmEvD*CV<^1201l=SO&Po7tY z`+Ir`17AB;K?Y<%xL~X!JljLs%^i5iYY90Q@xKhpNUH^o(-@

    gn0+^lYX+Rj$ky<@zzwt<%}+B3o@Ib2F&b z+2P94>##mKJmYEAR4Y-3!}VQjx=m;)Jbr}YfCL-tVh~;)A8Ip^xEA-IOR`cazU5z? zJw5es z3g%)pWpFIU*E}+A_olRXp3G>$nr&&;30k<-5B;OF!d6K({$hWPd7#}(lX~CAqpDb$ z;S`VSUZ(rZo+=!!S6h(_{H!_7)uZ?^F&-3fS?6oQmT9@#S~SlU=P$kr7OB*RnQo{fW?%SncNL#1s+U8f)strQKgg|W+>mlh3aGma_=G!5Q!fD6XMGp z>CtN@@6gyvl~r;QsC!cv5Ceo68PMQZvCs;f(>EEfHkFJAV>;QlIGjlfaz)0>*Q7op zv0jQp|5>jq-KDz4&wAY*sOO_0HGXQ){8n%E*dFDy*kpLo zQ|tL<^nE9IB4! zitZmhW5%Ykl*pHsiKM)*^ra4-wQv%S2L7R_|IOM00MIn|e-Jj(P@(AVYnTkUJCZOHOrnq3erbk9B!iY01CjT(& zs*W7uZht6_727C#jZY*?3lvU%)sIiK+9%a^_Q3(?&*W37=Xr74eaO@klvc~!npi>% zi4+vg;zyiNY^Z0$H3cn>-Oq-C6;re)$l5bQ3Hn^R3*RFg}X~YoH*}cQ*+1_&J zr=O^Lf5LxIzfnW~uqu_-;P#@u!u4gXfq&;#LDDu3bN$BLDxaZrd3m*aLu#S+XV;gn z-?9d?v&jh(O$jcY-W&cEF39Tvvg0$+TH_&ClI->AJ!~<>^yXu{Oijgn`zl<2n*H~1 z@Mes?%jtUv4&-mcRa$H+(Beik(W;{ZCXvJG=IDIov*n%dHy%CO{m1skjT^?uKh5xU z>(R!O-5b^5wCWx_Lnk`2j+ow;C0LC1YikKWs^nYaY!bW?c)1S!>c4okPGU!;b%H@d!<5qjR3;cX1U6etz^mshY)PNhhmGs( z!hhM5L5C183#Bqq(Rpk*)8_*Gg$S7-(a4+womC<>68zVt9}v%))8*OTks~=oh6=7B zFZvH=tN|8hZ3qNn;g=POOE~Q_PmVScr0btAf8m>extJ5FUz2i}VbC}MUCp!EKqn#M z5*Uzkb{2bSvKVza8hMte%<=}Vo>VG_0#>S$TTt$@1QBGRnzhV>=+;3XTt!2-!}E_x z)n9P#ekiNddclnDw8vb-#h1%ijh&E(a6<&^v;A~u>%~g-cy#jJkGOw=;QZeE!*?TQ zxB(jetjlJgnck<1ubk2Eh5KprMDjr1Unb$VV?Hv1F7$~K{Be4MNSDC&#(O0F6d)Hx=Hev?H95f&Q0$-40StCTG0A4c zzE$?~zL*P1SUU(HV69KFFPc<;`Y|z5&H`RXll&6$hDj?{Ql|Ka=W^kp7~Y`Re)jZ# zZuE9{s(bg<=upLjs&twss7ig5D_tO66%#m^UUePbx?kP?{^^r{+^Z0TiF~Nog$r_E zkomZ716qC5yVqW7%H{&)&zXnWnxLmWKp+9)rRJBdL1VYoK3_M7JNNNlC0+wH1(`ir z5f5({3weVv;E|<5+s}SwD!Sj0a|G{voKEn3OBZ&gM(S4G9_hGypbM1Es(!yNH@9>U zH-eC^IkN|}i}?~Vts%`I;#Ah|9u`TKp}Hv6g-xz7DPDXhi+# zuBP*xoP1AYM)gwH?>;H$RrONOzh3d7jiO28L+|O6&8_dAKUNAk%s|%1p8ZCnB>)rZV!@@EJVBDp%fqNHhISJs+A%Jk0o521iRvKix#xlGp3P40 zt*s%(0B)Q*CuHK3+4Ku!cjb!7q4m39dJS%)vf!c|mo+?BKSrw%YQ$Ud2d3 z6i7N~<DDw9`AKqymckU#e-TnJnFrKb-w)i2i~ z1rcg4^MBF>8VIz{meKLUt!FnFD>$yub(_fY^CoR?9wvtjz<@oLaIg32^Jl#c(Yqf2 zBKCRNo#KUXqU!H~G~6|`5RPFkPi+e7*MLI@-fKJyHn@Smo<82$-oV=cR;8+n*5U!O zBH$zZ657++-sl9q@m>Qt4}KK;B7NMrYNs}i8z5?YfQt5b>5eqVJ0eyI|6osmr_e{! zWo+yRPj_Cx)96>KTf+h3uG*5BEGhs=9I#)EOgKz29*VRcE74izzuE4__AiH9kVkDr z{Em1?MAZUT*=3N5K5S_AU}_yY+BBc#R9JF=ZqN+-uJ^soh9)BaeDn}cO2}V9!M@mT z0r6-wykK=hCpr4i*VdE2_Z~k??O_!@-PwKceCyFeeBbc`TO@~!s3OoV5hyZWC%0TD zuLo}l@e~WPxSg#U8hto5%wJYVbW4r2x?U+;qcFWV6Gw87w)7kpCm9hJO`Pge&L4oRpF8E@MwOi^_~MTze|JYMm0GmGp$XlwSP9d z_F4{jCVA|Wv#DdBqi;Xkm`8~wJZiO#oO7~;uH;2Qx{If(o6W$XX8CYM6iXp$$b9ro z)48UHa#baoO?ks9D*X4KeM2fB=pwpc`tYE7*>xkEnr8Ey6j}xw1nx?`7G$cEIVj4D zX^9mHJ51v1?Ca~6)%OmWGKyqIzEDv;`e(UD8Ai) z0wee&g_2LN;C?VH8aN1n-W$gW4on0&`GJ-C-&POU4AY=&+Uwcxs_OO7LOdsM0MYy- zCKt4P@gg;S@gi?~jS6eay@$fko_#^CX0=duCm|J9VK(bUg|N8 z>6x^O4m;lXBH)W*ry(32#xS~OYVXbMAT6Lb9fI+NQB|*NAH!Jr@ij?%e{<%R*#-PW(rR8VK>#*dzlfiUu zOX`Wat$FM`XH;|u9@gz2p;>>XW;Pc~ZEVv;NE$LXbR1cmfW+PlY*dmtUs;S^l^ZXZ zB+xkjhP0oZg>Cul>_kjUENNGFFJ=R{r1@zkf>%AM9>mCXbUVuH142S6!3-xq;X+^z zDn!zdXYGo7Wgr6Xc2o&BiORc8Cy;FG222h%YeUCth@FkG2112} zXOh-?6b(-u21-ufkUcza4Yh9nHCj{0*PA25c-9(<-T$k%rkZDC{$E&mEmBwsxwpM7 z>}zr!{A~(^tnErbBV-u$3z;pq6PlT{v6OL|0^C@q(k(nKHcFBo8B1E9%Aa#HtAJmH zyFC#{ZM+vR(ljuhiX^qTiX#-&f3*xPIpmKXI_Ry6uK^`wHdJ}8kaUQ};q4{#kgqxP zZ7U#Ci8uR-DK$XKwL1(h`*~v}nmg&#|5eB{EiPIeU1Xo23@JPDvAz-wg2P@i*YU=6 zS;j>X!v5R6=@^T<<8MbmQP$Fk(dXunGXtc47{*x=L+aZvFau|zsU3K@Qjf*H`f%{3 zun`3xux@A@$|}YjQ*X|d!lZnW)m#r%xq)mmK^J%5Dt-V!=2@Wh!48X&cJQJCQ{gaG zKb{<`;%jI_J?N@!`?Z&g!u7goXN`D0?5Ja=)_b;P$vrve3^%OS9x_aC?SEnOo%x7X z;CF!7C_gy@QF80sld~i5-gbx-!Xm>=)zinaTDxYaD-8tZd&&l96}=#@n>a}9h{kW> z&=|8KT*ie=lxKELGJ;n4>BS35Wc;J@GLW4R#*xjtH1{5kLCje1wzn10lnP!Cnld~4zy&%fhEo1fs-jGXyW#7?=e^~>3^7FNUJlf`!G>Rx4??Q=b z-Z+0=18B{Ud=-QJllS;8avJ~6KMRxdDXpw4bPd%x1WhZ3`Z*Yw`o+61HWpaCHN&{w zF)5fVR7H$aoRYPyIF}h+7nekXD%930Mt)hi>g!AD6ik488Ox|fqcfL{{8!PctReV! z^be2shWq|2pm`LQb!Ts1@f`_sWHf$o#OaQd?9+oU45^AEp~#WB!0{N) z6k=&2*x7j=`MD4_FVXV?ujccHPN6&z$%G1^GaNn@-AcV**`-xPb_1yq5e;CX8fP_F z7R@2~(rcudyCfNC=!XLJJ`XEp1PPH|w(eI~JFELgN7!$lot)y?XmQL>VeEj0SO-nb zKvU$Xh(~Xi=R_L`eQFmUugSjC zfznQlmdYRIIXAt1H3$07O%J(~x7nK@o!kmBlMUMmJ__)`PVt@0E56gya6%JDu!~M% zAxv-`Ky+8DF_eLUebaXvPi*$$YR1p|(3=RCtl3^{g-^z19)?IlupCJ+O%?>3Sgj)T zGbQ|~y&CLWey}Q&7g-EEgh(!_%kU9VRu0Oc>2O?k;SmPScWh^-h+M&6AVkEiP zV;nNIzd|z)KSTYB_)@ebsHmjmHl*9&X}1su`A38`M>7%cvp) z6{xVz1rIiAebC<1?SJT)KyQQs>AL$ZC82Y<>j8pQ+fB{ES1kZ&Q=J@5nz>!MyuF|g z<8=O0g!BA=HyDUhy;N+?XUmCXWaH;+d4pn5ywJ|&zVS9vi_hGbXNLi0e+ahOc#6nLF5kuAPjJ#)so-4e9jmefHnzOn096BQY*P%f^66)7Xsb*H@5ZUuhM)Q1}h9 z;T>QJhR8kKUQnCKpAnbCh4~ZWVSI5+GOzvx_zO0r@0Nly7tb!&RKMoS^l_tS0wA#L zaBdV$ss zoXMxv_HfcwJIJ#F!tfqpYfNp0R6&SU0%wy1E;g{(V{$rXp_|vI5GFbbBRBKdBlIe} zTQ^UjhA%~LXs6oFtvWU8pv2@lu1Yc5I=ri#RC~?lc8&ijFD|#v+R0Em%rtMIF0Tf} zrs@%O`f{m~e{2YRyABayz-h z*q)~ShtU)d#^E&>frvG$Cy?4*I8fRzk#C%z4ksg~{X?_IBfcm!KA2T4{dkBd^)z2C z9qVJI;!fcIz>UX>l#MdW>qR19qD~FlqlylWf;sjtY<#J^(3`jOL5PSfKi*6f;+i1Ru z?2MBIeXv;P!Z@_~y}cdOfO$IrFy|#cE^1x}rrt*aMjh~Nx7mF`WDnUVB;Jb@C& z7FZf6RBrmCRWTUGT3tz?_4eeAxM}p5R7M9o?WTmiU?g&6m;}%g9bkzA73Wa}B2$&UEYe zv$y>m6S#IfI)^_>Sn;v^x$WnREY%b*QmV8AR{iP=?*@O8ckkTx4_2pYGWhn+9j}Bx z(TZ%|#_?mRTB;VsRNG#IqC`G;LPZ5hpWX67KRlga5 z<&dBt(oFfl@vW#2>_vfG#|~V68}v>YqC*+V&5@x&H5tr2ITpe)UYOsxEz~W%Dviz= zrF!WBK+marU-%4I;cvxRfJUupD?>-tp#4ldFEwNsf&T_ zHy({v_K?3!wt(cPw`iQbfyC@@1*z%zZ>k7SLMbjIUt1Bxv;OoKd#bG|zGZk9f>11ODC!YGlCGKJc0EfyBy$D~2oFOT4xgab zh7wF0roe(y-672FKzAXFi!akfY#-)yW$u%Or3=S79qn_?T4y@lKR{8d_7wE1A7NQ6 zo2&=n5<%o?t?yJ)A2lmE;tPHWo>cM{w`ixc)!{jld$v_T2@-0a;6koEs@Dp*^I&1V z(u?l}xvkyagPMX~KR28G8s>U=-#~9yLor>%fD@GKIql#%w{?^-g@KyJ#2Y1)m4lj{NJ^EIRp}^3-fr#yltFMpe_0Grl-mm2HP940a0>vzTpT9fl=q4DdB-GVO|3(kNTPCyLEu8c))LR$9ox0WxWsN)I0y- zREvfVLX$1^yd$bR|KZf~Wa>YhD#wPGdvqJ!;$~t$lnvy@h9lcf`JxU zw?)O@!I9T~y@uSdeDBt_ma@6D6VpqvB)s~IS+c%Uy=vUXpT6D1vmH97B;^sjz>$3o zxpnv-ecE`!<6jYG_5T~q=&>2Di0!c5j$s$`VG)@1ym z=j}wjJR1B_Th~u~nl3W1VM4^lZ6V~#Mt7z*b9zgTcdHs3FFjGfGxI~_jk{kh{WSUM zWa%1etr|dfiIj(__0H8XDtAon?3Gc@^E_EQZ9Kzh-=!MnIHXUXT9nS4u`A7 z%5UrE<<76yr@!GC8|OWERDg#L^1t#Gmpy#x!h@-ojp*{`UkaOkJ3AZUIz7>}ak6jS z+tmVo{O)MH*SG7l$oa27cM!G%6fHXfdwF6~0)=()GDG1=uKJ44JzcZl)b*s?-&FCN zkhfQsw9_X5dG$KeM#vT0QPt%QWH_*J?8g&npi@G0{39Sy;b)MKWFu9Wn5%RPRx_6 zz8o#(0FV%C43}Pb=gl{lmAD>bS=1~b#gAu#>EAjcny@tD zI-8l~U$RXS#VX{Y9?t3AHRR%u5Yl9T@C%gz(oIb9(j!tW{fff?yi?#EWP+-7Gm8J+UU)z1IaKNF}{@B7`y zkGAmu)}#J=AJw6x1@dt`j$ zEfB?F(|qE=@}ew3^K3kxaq*@|y(H*&faa}W8!Ad@kkhz1>eCY;$DOmmU^s;|3o{hB z1Lh{Pv(u-0)CC#%AX<_yjXFr_d^gdOHb*h>jarmS;*fWBx=dmYJ*o_Mfx3Q#v|i6o zru~EA1IY7VWc?Hyp3z$Fh^}fK@F%aRkxzAzl~XC1k#`Fw5)`>~ar>*!Z{NE8#h15j zQBb4zW;pm|b3Azpm3APb?&}`~$zVpTo9`3Y05mq07@4{{Uf290x=hmAh1DhBqJ8h6rWGVKlbs^xG{+_0-8KMosEu1 z|2yM>az;_E)Tr6)SN-b_Teg>+4u{x1%p(?+2Bn_QmyBeZi_+RfZ~*>nc!;NKh7-^e z67_8%J>F!@x7?EK(TP8k&^ngG5h)ZXs}~YVYwhwqaAFAW^i0>M8;}Mfe5wN>SJcR*((W#@>TuEhm>)G&NhzCs}H(VMZ+8AMr+4jyc22-oZ;gluv z*X!`0aylF^8syG5(eoU6fk6u7yFKlUVmg^~a(&Du;U2*1Y$Kx`pI6PQ__k3T4XCet z2Y3P*wvFXfs5UP#(f6Q$W06H?M@O{at~ODz`Dh(Oba6!F-P55%Cb-J33DkVIk+lJb zdY3`4sn0yMDwhIi`X0Hkhi%9NQ#gSHn1|E_&U~Ly9q69tl_r&if8@h1VNsP8;PW8-`hF)j>DpoL~ ziEp`2DT$)cXAUkX1j;Pv4>y{@0@&q)Qx57FDJApADskf+5?8n)J^q;YGnWuqZf-q?W}}OPfxUfA#Xop_mV% zHfm+G&s(}gM~9RCaZAbbXOCLG{y3iSxxR<-+He!fAK|9i+F;v!j=7X|o_4CsIH4gd zo?;I@vFUn!RT>Z-NXqlx${xat!W|6_r|}W2x(xWT=JS(*6Sv{0ET?6mdotghpxj3J zVKjWlj_s#Npwx+d-JLMMBWihj2t5&%nD>?Clq*=*U3!lmy{D^LR)lZ0%I1`bCbeQ* z_T%MNs|Di}$u3hTpPRGWici&Hl$YBlt3YQ_Dun_WW>3@VNa0S1i;i`Vg4H`e#tIIO z`pCXO&;5;S_WiA-%P4#eDuk`vBgoC~m6@x4sVdtraVd83+)qP|6d%n_W#wW+5GGM< zkkp~pvOzN76v1|Opz-onLVHA>KoavtbY?LY`6Gj4ttfO&N(e)G=O5Qvzs9T$h65_) zSQn?%sAV6_scj4^#9V$_taVkrg;L$)Bg8n2K7;oOYZce^=3RZ{zCfx&$Lv0PzCp8V zbN$iI2JdGu#@D=}dA-_JF&wA?gw4N3a^_)^1zGy$zfj7gyF6;U-=UKT_mBqTeMrLl zydT9ZD&1SRKfm4iFJG&A|8q$fm|bdfqN$Jrie0L}XLi4%CQa4*>t88$40dBg0}$-; z`kaD>7UO;MPttCneJK-4oqqRx>*4({p_5B%5$8zXh4-R4NTOEwm)?yh`(A}h!(nto z|5z0*meKy|ak5-ixsND6)DQ;9^DtXudZW~BzZ1x2`7LZJM^9mYG4CqHvOSu)49>e# zMh3ok@iQ-&zT~f0;i@8AJ5ai|P%HTovAPQYQ5S8!X?mWZV&_xuSoogEuajSk@IhO` zR0tCScFz4^4wz3{`yds`q}_QBmmkbgivH3@)arEot22_1r%S`t*qQifx)%?l!ihzD zj&b&WzF?fQlhHrVhS+bSo`I;dk-hmba~dW(F`7b0M8dw?m=6YlYhe=NrOGR#f3ssR^aKV%DCN@^X?J*oI z*o`=UveV7w42>wVuHx(W7#=Py*lp>A!B3cy-5G}E zN_CTq0j?>A+1dDB(BUmxwij6FmOwb=JEfX~Gq{js1k{N(fYd3KNK+BrF)?z<7DzyG zJLC!QZ8{Aa7w3TQeTA(vk)B)>@fU4c^n$p?AHnB3XWE!#%Nmn}$pxC2NEpD9!6+B7 zEVtgI2Gc|-%F!uns5(}7c6K)M<1vwf? z`dkwyv_QOhH15wf`|xpOl(=;aN%M9nWkN|1doV4hJRvz5#9|0ZiC?IVt)w+c5vP$K z*movAWlLD#x)t&Q=Lo-QBHx=0?#p0=Hm3 zJ4qLesZjdLWs=CLRO!q*Z;sj`Ru&B#i>E>?5wa%v`H{wBJ_SA3;@8)+^{Hv~+^TJv zOxEf6cXe9>wvO(_Pe?*oz>?mc49%X}|9;qqW6>9Z!pyOr_+_Pn1x|w+I}dcwXubPp zGCn(eP62DR*S}s-#l|DpJ;b8W~-3O!D_856mH0}~k z1DppOmqu0D*ORd{QiVx51UP)T#2x++6Jjs{-Ct_GBVGU540hLzpMFBTDl>XuUp0S+ z>&JPnbj15l4yM5byL40jaGaPSFx8WNF}4E3kg5`>SLS{*MIy9O!3{3&Hm&EoD$c2G zUvUXbUe$bV7(;cd;VkJY%;e|Jeju_%Adanod_OjrA@oTQ1MiV9HN($UbaWl=qPD zi2lUg$iIde{kR6=HsdJy+Rjb18;2jXLx+`(mSiO3cI7$WeqV8a?mV5~VXwiEW>nky z{m^@$JM*%3*wKp}6LZ>{IuK_WwidoG*x6m*-ReEsdZ0?7P#RChFc~4XVXfyXW9#r_ zJQ+q&ZphbFhnZI53?M>(w=W>;Bqw~b6(typ7kC;x!gqjec}=oQOIzurY}D&X9Ye8^ z>6gX2MO{dj!?+p`j{rDa2Oihuz){cpN|`DfAa7KvNU#O!3T6X5g{CSSg1|OhHMc~l zunVX{NgtjF9zj9V7$^}WFQkl@Du+zNg=u@uY=Z!+9S_kw3=fCmR5$omUFo|8iZF^6#iyx|Fxx#c)DH`*|rMA{Zhai}}j-qXhq*LQh% zFMILWnqnXlVe-Uh(0JruK&ppv!+nB!qs51U^2dCtF(aOh6C^bhH=V{#-tX{1$KJDD ziMcpC&D<#k7&~zwpuH&_^O+TUy){S~h7wsR9f0`jEu|UVkcir&o@XS+KyQtMj%&rR zvZ)YLP1{=dj&Czk-NN>5mASPuon}*^AT@L>a0OIUoH`Va5C(BezU=DOmr0_utJe$F zn&Kz7SLPb3NBebqlq+HyL%8q{w46Y}AF4nKe|2Vf6MFOGipL|@S86@|>$FQ)OdnZM zlmd65eAcSi3NpBfyE$&iR4b63wfGr)A!9}!?{lwbf#Y^Cr8U@c<9s-fi?`UyGs<5= z0Ah;mlQA`Q#o=Bz33rzNleNI@Wzx9?k5;}5L`J{^{;)Wwi_Mzm&E{B-B!+KiFP(6Wo4VzPyMxn$ZBoZO7HfMWAV-?UVkp;(x z$Od?zkA@HMaSUj!52E2VdJoOWw<0FAAJ)W;mYn5v_! zVC;v|Xks@w1U>DHYDK*(e3)uZpCT_m?6HIXQyyiB;2TG3^*T{hByCANhVXwE>o}-s z9lbCq)|yHwvV!XMmE;W84iV@({e(mDl&N61_F?CR=aROPP6J>QKEX~X)@UvCx(CK< z#oCFwi+W#`9xJ+N*2r{ZB}N(!;nd)heo*~joErr4a|DXCkWI|TJ=nD)iWZRg>@4Us zkLf^KA-+STaQ{%qf@9K`Br+YNKD%hsr~HIptW{tG>;bPUM9a5Du_7b-r1O9w?cH5$ zeDqJAnt9t7km&$WA|VHk8n@g~TPOj-<8A*S0^-x#x2Paa1tNhhbRXdS-Y0{dBi!Ow zsJD20(mm*6?|NLx2yIe;Z9xO`!0+YA{iiqYkP#?7rEqV+kRlF_o!bNi$?>&>_BOp{ zENuQ##^)-@Eb>L9jf^oW7T+B1-ro5_IHkTQuzy*!GQFh?1NA`wbnL%^Hkk`nSG;No z{Fm`E1$GVkt0y?i5i7ub^D*wZ-0!A*u+Dgz7RX41Ov%)o5%?5B0O22ab~ar*<~+0i z1*d!Zeg15faaT)MzeBBOrHGN36G;LM>EDDx}}NikUH?IR8kiM4O01s$+6q zy#8HkRn^N%CpE5Ol`^TrI_b!&RLnXhnosMLz8fIww3~NV|IQ9Gt{@|<*9!U(P%1$s z1W}3sfA(m28Dl&$)=MlKwuil4l&-30^lrxk7HX$hN|tb`Ry7d|57E>UupqjrxBCcs ztsHXlek4JPBtRKy7&&yw(Iae5^1LOAs#@bO?@R6hclb&^6g79CWX3XD^L;;u7C%_D zF4Mc&XimBeE1f);1#L5Fpp;LhX&#oNB@P6sTCk!1xU&I8(q~iA6J>Jncks0ujIlb0 zVav+(foC~JUh|y7JR)=$<}5W@KZh+48k}DLIwvFNR>^5RlL|vDiebW&d+<12*iuJm zd2twAKi%Ojt7{e{*}8*&5%JMv0z^q~ooSdWEm z0|}oIA6JAG=A5>QM@BUGxbT>c*!LS0b@U8$hHXGZMY8uJvZc6|8bXZ+GO*O?81hbA zj7Q}`>%G;1*&Od{as>3vRZK9Obdfx|kEA|ApDsw>))fc zQ>q(5?EA!sj63m%MK25Rh4;zVdcmSWxr#+rM@JLf!AraHA@52 zVmEa7tt_tJn22FVy0cHn0vZu-s;hz-DzQ8NlI=HtDGpvGxp-284W_s!O|p}sLBNX( zrGyfo8}?aDkCQlLS1qn5Tv6p8^WdJd>{S-oTAn{U+d6+9+s(W?dzzq_1keB(qf^w(~f{lZ@j2NPM};8)fww#hM6YF8rhkL3{+WM3}DW8G&S@-f^xXGc$)gy9UG8L^XlsH_moUG=S}b zN&13@31&UJTx;C0AnIYel_O;00SwUs`Qn`G!)chaG?K`)$^>hqEmU13xRM1 z5{;b7MNz4J6EB2v?a(70I16*4DU!>JOfv{Yu)6B%pzh)O=U8s9lHrZKL^+)12?Z(` zE=A6{#V${(%2XgtR+Am`F?D3n86F={<-H)<4-(_Z$>ii<8gWxLoqZ2a&n^o?zoV_< z3O9GtSZkMkEeeI1>Zn!$2M59Zuy~~k%z#v@fzyhHRfZ2bmE!DyNT9)nJsRJH5!Pi7 zk*Yn0uh@W-V76*ulP7NbaimqOF{ThtJ1g$Eb+5?*u`shp4mgWs=S&tzBMr|N{rN3E zUyI+b@%bG*!*B!F$7y4@AM~{M8$&qz=UY5KXl~xml}S{`m4@#UBzb(R<>m6_#zo>i zppLB_QDu*(t?Wb<{m48~B~sf~Nf+9gjv!Why}yEUZi~G=2qtL8$C3$4?(#N$q=vmz zi!U&0MoI+~ZNs}j*JSo3x)vp5L%y+wAGj7wmQyVd_pPlv%Xi*Ib|_vWiGg>AttYTi zIfWLibnLku@9(!B_K}_M0QQ<5^RlTa(mO5UY^>pDY4yd#?u?Y}S$$`B@=dN9w^F>? z+?kEN8p?N_nqFgGUB^cf4kM-IiP)mV>S6WdjJh{6_7HisDNTAdgie7$ zD1$-|qgN-(zd0w%S7ER|XM*HcemOmcJ3gUBWNF{ld-DU>F0VEE6q^$wnj<8sfI9cQUwQX0_lxlRK&tTNz)_jT1M_ z5O^KnAyn6(S4;2yme30hA-nV2SpZIn@RSQK!KQK$^Pq@(N!(6+S9eUIC(GWVaPJP) zmBqZy93K;JME9Nm&%5kF1snz!1H1Op^mlj^*<@d$IKOQC5UO+85a@l&JBkS@eB}fc zG9HhG%vLsK|T7@waTeO(GXA6Fz!s3O9Y^qCW+7?Ng#3OMhnRdKlUQx+hDL@R>#qC03-AZUQp(FC(o?+afI3MnMeZ7XDgmk`jOoG6NYZdmiPJ}u8LC?;fV$hU zX+D%-J+RSfbESaO$+Q#yXY;Jb_(5$amjqq$7-g^_Jd&;e4M}}Ed;dOm3KS|nqPk~9 zz_n3!tvKXT;MaQ2Jtd(#ucJx|C`x<^f(U|#qG6DKbM&ddf#~)sgNu5KqVWp!dzHaO z)CfzV0@m+}l+x`_e+C!l`WeR+I;rvFSNU7u2F*`Fs^^)IQhaDgkb;wCQ|E?xmA^%= zw}H!!s!)XOtNblhmwL3Cg;sYTspmFTAIe&HRJz<#TFT$zQhHbIFw6e(Dt`<191|ji zmQw}d*OR}+mMfh2n<9UUD0pz{c(xWQNtqK^ybod!Ko^j((C5nGa@yQ2YAyr=q;6x} z3MT|g_JtY!vKdUxPNg)qd^6Q1^|rWFFG@qPHDZt4f7RH@*t7X4nF3Iwc>F2J51FzVX9nziIIl$?T zbmuzl+YBfPH=qdeN>WEgNoqY|EXlDanO}8wdpydbFl(5%$R1v8J#1V?@0OL&fcEqFQ(U3qH0+u zUzW?4Os;F&<_b;fg4r(IUR?TUZGGk4Pp`erxb0}T6a1J3KpWzN?O zB0gN-A`$AAj+mbz-*(BjPq^}FySk4AS2;g8llV%L=)Jf_l%Z8RnQu-Ky(*bkaL?C> zw4LE$J{!?1BL_@e#m!j$Q{a`(W}Je8IA~sJ3&c%@%vYnp=t?!2WfE(oMUtIVe>eWHkPTfFY8l3)6fc~=XbKhXl;Z3au12dWCb5{>oR0+dHR_&I zDNByMTj2wXViR?Co5pg!l-nT39m5>L(egqBPG1@5N}gL}+*p`Ma{E0P8H!|2JV7$aQskhKnT@s0Et8U?SxDA@8A8>DQ3oh{oG1^7zK(n+oFALSG+RI(ZGFwwHFqa8?ieW%pU@p$LRlr~C6q zsfOq``HG5(g76aXhM4EM%2#5zzox5v4HO%GPp<+9T8M{}B=?@U-N1-*YFJ`_**Ort zTgYCT$;A)Zd6Pe=S~meWitZ84h>7?!vL z%GqoMkkJv?$kTa%57(^qhTw*ByLMYT4Mh2hIx!3r45p&G9mjl#>_V27YgRMV?h)SYwijEp7e7gZ_h^ zgY?Zp{t9C+h+m(<88x0Q(-y347s2+%jB6cF{c~GCSg9kG(6QKCo^rpI+``p`Z5(A9 zAa8<6#eTa3zXDjU>p)v0R&v`cD=QRPw$*BlqBt;uQSJ0%rISBrZsVLdx21cXoCk?S_-IB8jYbPFug& z{pTur?CTzLWWWtZz@SO#z8MQ0HR?mcm&)=xpnUzSYFxv(&=C92dLUFz=#fjQy)k7Q zT0qgJZc7tJ@#{j?o(>Nk8W-~7$^sOH!#m>egyd1mz!k+Cg+;k~!r-dW70bjvG(22Jww2qR!NZu*4sc3(ly3=WVXfHU%1|obh3e|I)-%OpjiOR+%00Hg8!#_reGu!#n~yD3GmD> z5g}sh2n^LK-{cU8Y^78`#7(LugvX`PAl&xD;qik!RE1M`a1^+3oIr~*%c9Pxb=p-#+G04?L-x>PmC7h_q5 zb``j%lMNe$XDZ4@dw9^ZBvw3nJ)LS2>ol|$7r=@l@nf$8U7|CG7g%>!Iy8^wS-h+! z(1;q1f6)jvmEc2d2dguCySqE+5BvM0mgP87pGRx6e;{`&wWy@bxAa=v*2kKAtHne^ zU~kMWi@X@BKv;yF)e}v^#G3TR>yi{cd`lU{G3M&EJi<^82^2XqR-zV#JZ?x;wTH=D zv-=pCFk@vR?rxczdG^NeOC(o=QU>_~`q6*oEe^_gDNs#<+8_{B%B3t|_Wo!?#rvji^32)ea#Ek8J%TN2pA5EO z{b(+6BCv5$%D8k)UcgDADt|CFd~S2h@vji;h0-g%y?h|(#TY1Lq<>3Zs#=a0+M7Q5 zBpg994NImm==ird4bV0LoJ@sFtJrAzWInMs2yDsAWmUyqXB%doQ0AV3f$k_5h|TC=Q8?EkOzPTgd{ z4kMEWfxs+=rxggSQx*ts8RHx}PmTrsRl-`qWMWGNdlrNTk@Z%PDKy#et}a#twwEry zbN}MCtM@Oya}iVay5=UAYEz=PcSAYg%^WFT4A!(`iLQ6jpHDL*x9Fgjaa05 z8IgZW6P$5%g@ZEW?Wc1$fp1cgYc9LZP3BfmPARp_1jdMr2D?7dA+UJvZra|JU8JB=2=~a0dh@tYhE8GDm*-U` zsnYxmU&c)DWf|^Mz(bJ`p&dsZIlJX%AM(QWN4?G{)#Kus^f6zha;_VIT21eqc?oJHAQerUe1f}dUfJTxJpA7?}9v~>|qTqT8m^dC%g zNhF96l_u>&eB9n0?xjj+GyUwUBdQB$@c;%N$=CsLivFKAyi%6MHP^r{&B4=o2CRx0 z2g<5kJ=HIf)b%+t>Zyz2hM;Z_T>8y7Tc7L7W6Uzp1 z>g6-UlKrE-aSI692%qaHk1U_T?XOSQJ5NAUTGwZ`-tTqvO<)hkgMu$PKmig-MOLbu zSZR8Lo-^6MFLXKSf9dv0M=0k~ffuOU1^d)n?Df0e=?J0Y)r8~lypb$c3=8vtF!ex| zai1{@qB1L{JM)zN8Bh@XNl(#QBU_cW#Mi}D_u9f-1^gkPY?guf6T8lBsR8(V|p&h-UsXx$&&0Mq%DJC)44AKqSH2!C1}l*}3xZ|w|6_@?oHH(;-OPmnj)7xJ%wVY%^8ez>aaLe8(uf))=XOt6#aL zR74=ZtfA%8>YS2l^0ko(xMQ(ADcDS|J&fk-ze z0{uqG%VRi8K&-(pUa$i-8QSU?BEPsFIa{Da=Zb)I- z0hq0PztTp|1D^E(sH!pc$(215?lw9e?VrCk^IZ>EBbi(`s|So>xwF56Yti&rC}O%q z2cBsmP_c)nN2Afvy9*0LTwZ**Gi)DvPylvl4;S`2k2?o+4J{lFML}PH9(#F)a82Nm zY(x;k4KT&^%yLm|3e++{5n|AO>%!GbS2M`ss-pI#ix)0k%HYYemoHqsa9N7B*H&n|v$aSFnD-2$t1?;q+t`xkav6}6Eqa^8E#yCcIs8FS?o>Kn|HMRT@#eN&LY zt6yqg029exB|O*>>_Y?{+@O#3`huaHybBC^m~K~2Ij>JgFdTLc9~?YghaM`8ET%8U zwqZuq05zW=gp=w7&}Kh8!?0zBIp+jC&p|$e8^NGWkXPUu=I(*0y0MZU#8I}VWG<=u z*@Z9WWAfLAZy0iDP1$0?jgm3s9Q=BvH7o-ax*JOeU8s_^&ir$_9u(V)2e9@SZF=La zi8Gbs&YrOZ1*sCQ`DyGGdQ1slo96UOAb998W8w!0F=G~}ZtWbY zBOnuX`KO#?XS+Y@ktl?W#}=xK0GuM6G;BA!c`@)G3Ffs=H<-_uDgokq{Z)!P@^VE-C%sp*7Eq}{fK^wmC z`cDuuXGfyep#4-lC{x^k=9BP9c_a=1f+>4Kyrf2eC;SQWzT1O3+#8N|5X3F5RNtYg z38B|)!|(4+8ebU<`h&Y2x{GcAgAR{C>FK+4iOlVEi%P_eE7upYXB5mZ;$CmKvmb-E zm6_piL;s0>xe4C+#n7;#{+^4DWz3pf-9h4A>vULUUc3q0zby`B3f}rw@tgH9mKWK_ zwNd9V=pLjS#B~iixE{RM>K^SNV+e#=*nZ%lH}k2@AnFN^4<&R_bBWHJ^PPEx2v{ID zU&4u;% zU&t1?wCKhL6Ay>uO|j}B>8WLF%gj`_H$_Xo+3k_?&)vTtf_2+Vn~!z|N9_@!p^-df zhGTXhUjGj7eC@Xm`+ME}r>&>`<3UTf1z;~12E!cMgOiuhtNuWFKUdFKy2zr=Z`R!8IZ`gA74^E||h?r=2U z8g@FZWcX+dxBgi_u|ZQOTErIEC><=irj~%U5$0zaO!7v>qt#m6A9V%-xUrSapZ5j= z&hZ5o*p8U#@`-wOI^R2wB!wWM7jwW@%_tY@atck2sH$Wqj=5g`V)k8tIB+soxm1M( z{n9p%Ihaz97#NJF7WYZaJw696A%1n%BS+eKAn_&=#~nD5q)lFstjVZ>74d<9p#+*0 zVMu*8e?u0-w&PGT5$8h&SCDI=;ysqs4ePq40Ml)nfFI5rd^3h82*k2aVm|#rW2*>-XP985eOMx`){Go- zym+Clfsm|b-h^}h1&oF=B2%W#$LpQyAyCC&02vWX*ENlH$^buJQpz53v2*@+bOfKB zxHQ`6?Z{bRrk~0nO3_I+2nC*npBs)d7Lo7`g4Hc|D9_+WTu?e-3jf|x8h6(IX^ zKY}%!L2$Ze97vGYqN9pCMuDaNySQNLs*xoM=(c-cTaCJMRv4a5h`3$oz_JaQeWOIr zUWkB{gfq7MHY5@9l`%ORuzp0m2ja1pwn%|D4MPE+YfajZM|KmHQPM}mEMt{X&N!sP zP=IMzHc{wI_&Kwd+u1WJ*C8k`zW!Z!4&96N{>(*qCBUe6p>p&dzCV+=B9%?;W!^{f z5!oQs7F8*)6|qBdz@S51c{p41VEWlnsw#n8gXDwDGk3z$aq?o~kh?ai6IDB{!pl~^ z#QS{d-7s+CvlYmz$ihuYJ|}vSW`XNwnk}_-7g@^ts7V_w>B;EaH!4o9U7H zD7+oLQPcebk7`z0OlO@b+$4%S#;D^#y-R zk~JqsTKJQ0@A9R3Ni|(qFn4&064mdIsB{mHc6K{lCQgdjA>=L)&w$qibw#TNk!tv# zHH27dUx;kIu^d2FQKG2QWNaVpa28ql;7+c;%^JcT;oBp)o^zCg_!C!>rkREW6SS?r zMN=chiShJqu--8`G+MvYQ@wuC+jV<&DMJjjerNyo{;qeW59lHHF;#AIv^%3{)-FHA z0(Ey`)z-ZpB}`npb$9dlNSrq6R!d$O^LNO?xWpECX8_eic|iK2HpF|qE;v6JNzmxfE(@ zX5s^GAETV>n?N+*Hxe6nILFI5T5#qNAiUze6bv|Q|MvlaPyq|Zt`qyEpDwX-CDbu;r%V>UIHZ8(PK3crHvdocGuWnRa0NrO}EL?|XPRG)h*>mp+1uBFA zeK=%kbye+9YAWs2S*vmzzFy!R;Bf!`^#ywX0JNRpAdNT0`=ma-d51ZsY~Z1-qvH{` zRBpUJr)`}hf5)Hxp0E}Fj`4S5kd6Go4~ip?sB+xv{^D^5PDzw=4yqlm^^!^011BLx z!2q^4tl}a#|k~(~fRf5wgK+A7k0UwmC=h^Ba@T7ghx?Js>;04j4 z`~?6NoCTUv^mBpRM}B!H3Cwhj@^IGsqkBUL#zO1P=>ZJZ&9(q!W8jUw>c&7-3}V3t zJMOBVZ(W&h@g$>YU+SD|62ldW&)NxC!BK4<;wC`cEdu3W=}~9*3nTd2YeNd-d5UP| zO$N4_ZX?(ZgEd_GVr>T_vIAMT+Zhh~gJ^?_f!c;CB6~CLa)C=%tmd7AdOCA1r0yDZ zHPtz&7is*gmpyK-Med)?%XjFUYf4$Q$mCvTUQI4L&&oh(3KMg{{36e&h?ln0H|30C zQt=MGlz+9cWhZ7q>9RfY0q;222yEE);bfCTSV#5(wG04#-QUwxT>w=BURklup7;uc z`(^mE3LiQ5Qv{(Y&_D~e)WuJvQ-uK7B{a%mch}4L9#r9jVTi)}u-ij6x`Vq|!S2Bx zpiZ`OWV=d%AW8$rg7Uig(*LTg>2}_U)g*7IV1swObk#XrWqcl^z{Sa1bq-v4TOzgf zzSvS5++D!FL)zw@!|o{k=wPhBj}7~v$3iRZWK*>N4Fq___08YK#t9_b>K*~TcJChd zu&*5VHwg%PXBXTEo>pD~Q)v>^Mk?Ts$mlvZ?m_PCAP#$(bR9Hte_ON`*83|byB&}L zwu>`}hSwiq*=52eD(fFOYYl!(X1(&!gyt59PkX!AJofHGKP4beebIITSF-apsJ4z_ z2HWtu*bmm~ap#jI7(LnWm1Fbu_Goc<6Ertk>#?PbqnEyyfV19TKXpF_{pNv`rXzR1 zuOi|#n~b~#3JW3KhWU1IgJlqWbI`}QvJa))a*pmC!i3ILR}l7BZdPUi(#s;A7a<7u7AT2IhbieXbbByHD4Sh{%URX-C z=8~mb^zmD5goLO5f3`hAuhN~u$v4<|JCk*;N{fm5rTQ4gpS*+O;WIA`zBGTZWZTEE ziqtzeQ$>#9@dGy-gIB3)8ZX^h-@J2cWpQHzII;u`>*L54{)7{8um1#xv|LL;l=`NG zREUgDg}F$uVYM_+Z#;ENg-{#Bh--xV@*IJkcqABu<;EfEF5TUN^K>veJ|erV z6tK0bO_&hp(t;2o@Tv|rS+o?wf%+aKY$gR!rBNqyz|MJIwGZLm>5gP5@MO?MCcuY` zY@Kf%Ai72<;x+yirGxdL?ocTUl$PYTWWt94tB|7qP0FKeMRsdkE3?;`V{707+qGI2q$p#I1nbh;78{Yr#6 zvS<>ZCp9&KQQd&hHVnS+-$!;vT#znD)ugjp{0?j5#=HZ%rhtK*FOa*u30MLK@QBBd zOA9wW9DorZ6*()j{mVnxg zcqxR6sSyl&?cf+T<|=}J1uMDlqMJ&!Ph&RnxLiOj?lr>CsOlPpgG|%LQIG)YE=|V+ zmSfAj_YsZX0mrk%2;Q=bH28in`)q5GBQgvV0UXxG+4Sj9ubFJ)qD&&endBZVaD^fkPSi#HvT}c_P2RP&v#O!I1G%QDCOW~D@;|RA?BeNqiRSNrC!{`Uc zU{``p+PX^~3?d62tX0C!wBCs_ubFs*)(Bof5lbwjyWJj131K?iVz&bnJUrrZ(N%Zs z{$RrJ{Py?ai0Sno$}FKHHFV z;3L`PGqV@-R0alrgQg`u%fAqFi4+@yVP|fHq}I>Q;^awZXCE!OIw$9cebpcB=m|@~ zNR+`n83@?aOeYg!|E4DlIaQu=c|$7Uv^4}%!l(?4tp4l+@YgSdTN)qF3duT|PT9k@ z`A9X^VLRbCILHQFGdK=q^Qk-BJv!njl7rPchGJtbmK&S0be%G3?oC)0hjL?vI_1V- ztcyco>cLg;Ep7E|sehtsC}e`@OVxNRY+BLpGx_;kK<{YeTAX=dqPZFZ4;4XhVp>T} zoi)JPaE6+e8xUVbjFhYRn(&cJ1mtyJ52~|SnoC;M#A9~8!IVO@nCOITKgkqm`W>65 z#)Ed#vnqTSL)WZxE(0frmS~u$X1Sr%7^Xj2rbW%tc&9Z{Kj4Cn;sF=Y4ywI97lVvu z;j}5)Vw*OPWTSveODGHWZ1RmQ0m$}}aF)hZ{UcQ? zF`kvTC?5L%bt&uG5S1@g(3;%rVOHv5@H?hp zfjE6Hb5y1uGjC=3fr3x^&{1-vRl13*U_7AW&%ho`x_3$~EP0Vkmk~TIZm{NL63|(# zVWGZCn_h_o&;TeFX@paK;5BH~i)1jXeuW!wzRL|VX!km`meK?3ccfq&tqNu1PA8) zS#_6p_6i@7*uy}BF?_}qqieVxN}AE$g=)xNDjq zP#WrzUuYsn3Je3Vl9N7sFsgNqhl^&F&%tXkKPd7vVt31cSCD1#5Fenau z^1%pJ5i`;qm%@+5bmk}J&dw*D6R~NHb^Yd?18I(Etx!RC->`BU9<6O(Yg|8RTwxZg z?1AvpOZXDKDPtX;hOsKgk0}*uoOR9w2c@6$){w~2`E|xz3pIqj)@s%GYpJF%(t6eB zV6nR?Zvj(?2PxEgGx8N8nJ^r6 z2G57RG=7RIT3{RqX%>mC3fb6mI1GuaA&kh-WtYD5mS82zuOb6ZkF&^F(-*Vz`3W39 z-V#r@7CZ}z*p#obS1ht?IN06R zZCwjp4sV?S1w7Xi93OH!d|E7b(y&8AL~|ccS%4C0w4d~N`svU5%%lmYzUEUy1(6Gn zh9Aq>roTiOOW-Sp=N{K$C(%Hvra_tvy@iT!BzQxU)GHZ2DQf@ z4Jys|VGjvLwh;z^%qy7jgXRe{16nX0ZNiGr!$1qbhm;HjK9Egvr!m zrz;^wIzw$P+xWoPz*V?x{fsM)mNRMN<%{pMFJ50Lm9V`-y$~te_fi9+& zzym!rK+ptFgT8Wmm1obvc>=pp(`3T2D6vhfZB(YpqYzTBm&M74=!?v-fn_eod;L&> z=xp2$sJ~slb&Gog+{b)Loz?r%F2Fn8PhsFGaC}G%Y_&6vXK&kf1_iEq5C#%1k3xLu z2lM>MQy7JYtB^6Obsfi-e4&AF+hQaLp_1tj=8ZX!SB4OjJw0?br+I(q8PHupqL@2v z!VV9R*~-Z&#ZY^h?iD$d#wY}C+iaA5IODuDxn`!jrV#fYo>cCYKm+|r!lJnQQv^?R$QQO+s#{z2BH0E+{d1N1jN5YKN+!cqUz^{$-3S4A z0A&jt9swaDWlARH@74qEL2dyZ5G$m3q(D+A+B<6jxxBP}1k8{|eLuCb4jn%&WFfkl z0aiTAMA=|mur>rU){_F(CFAR zPE8AY4Q{^)2b~Ioc(N-en$+Iv_DbV{OXjEhKvZGc$k$w$>QD5H513W9?xFLa%=xCW z*L&a2e{D+wM+K3H$84x_nCqwYP+0*RWbH?Jz$@T8~b*y|N2 z0i{_u9}!jHxd%MlHLowTt-OK;9lS=my(^12{egKgm$2;l(5o9g#J-z5ILU89SrSPM zZzx|Ux6~Kc7Yc=_bO2Hrmwjp3DqJt-0D0(^$9pH9U^h&%xu{S6sX({#3eX)SR;oBF z*wgCiQz8JHi~@55ZA!4zQ;QT*j;Fw=SGZhFMN(Lomz?jTs?bKYu&A2_&7~x&tAZ>8 z+|>CzZ0X^*^H>aEY=>s5ICYZTLKAayoORQ6l9Q)~{Vy}sgR^y)8yRn3$e26FQ4vK* zUf&ySKkE09q+N{|697lm<7dI_BdY@xX)0`F2iMFmYJ%zz%uYyZNlyS^AKn=%IlYAm z+o3$N!CH^t{d9@&KRcxtoP`VZo(;$%z0i^FvDo2*;@H!}d@nlmN`GTVUhTIsaBfdv zO$okX!??MrAm<8SeAsDk6Gol&%0U;5RsflDpCu;I5HMyosU*)rt%a`yoi=4wO{OPr~Awv*&mcD!Y%B)<8 z73xXsoIiaYj9_|VPC#brqqY`>rt&xRqWQhIc~i>a3-iK3+rw@6n0#+Ylm=3vpQ4`) zF@m#UJoM~BSQ^&Zwt;6~OE_mGD;t{?a#T24lt}?qE*Ve@Ft<?h1RV0<07n5&nt;ep^57*666K#Eg+fq> ze7m4(DG6*EKcds1yb|K(r~m0ri%_E+iw%hgpGNR+r|U)0sYlwxZ{AE&f}eGof=W~l zNH?t~8g8cZV$aWW8(^jK0|@mZnU}Wy84@1n%i__$NnTn|8#h|vn|*He+ zxHuh*GHwZ3ybjp;xUjV9jt01&1Ok!sg9aS=>rR{UMnzqmTML4dfyLCceV3;^)>fGU zWri>egw4R1H$)CQ9i>!{gZJi|)7yZa-@}AxRdK{8hs%E4wc&Z^7Fx0J{ z=M?Oh5~|L@Fhtq;6E<%orxWjZ<2S*q)?T0E6228rYx1+|EIPvMfMYV;b{MMW8vyv! z4IbOGjoDMQXnSGh79AI40#i3y*@{Y=&JS;?2|Y!-5sfl9E`a2U}8GECf#Rb(S$q=GL3lpK?M-lQlN0*TaCIe|}x!ycL|2P#4GWw+r9&?CJX$Fi~VP+9!~oLSn!);s^ixk;I!^b5}| zB{z84%fAN4uGSwL2xzYh3bt9y)*yC?cg3`v@ z&yj{KzbdRqGZffOT=uKra3GH zq-9-lYj`6)qT=UE7&4#TGbUM_n*)oxMbpM0M%vDGAdG@oAJRYM;mN1P8l$cJ0uF7Y z46iM_j?)}TssP9m1!f||i9?ApPB$I`CE3IprlCAy&og)g+ZAuXqj3G!*O|csgGl8Y zBz{PF0D|JDVg?US-(fo?mGvu#zKYPcZiDUx_^MD+0B3j7Q*xqwe&o;BBH)ZKilK4+ zoFe5xb;V@Y4Q`sSJ49u|Uj~g-Z|}Xu6cOS9eApR$g6r9#V7Z4$y`^$xdZkSgx>%&e%V?0(U-;9=t0Jmdu@WM=N18Z^cP?CUY=BccgS_x`0 z)occ#FDz+@X=ns_r}sGS$OSO)t!Rbf=93oXRqDB+0+5YvrT4fy=<6-?Zw%@7ZTvht zUmi9)Atv@<_f!s%$s(YO;aU&Z<#tEN7}k4zuBnG}v-7i9g5Z-^k8fyW87Jp&cW|9d zz^vMArHn*q@HZ3Y-7umk7~l+ci}WQ{3=k@AR1>m!s! z_-2hcK*<v>VH%OKpOX7W1}f}7GSI@FlmI3%`66*JkA%!1kKOGWsDnmQ+ibyF1AOKnf)#rSL38o3Z+y3{7mlT z^tP&{LXJtu`3VgMFV5tmb>Hcvwqxc>v_2JE^BFZjN0$zgsn_9kLZUO6q#=dY60QPgl`bN1~G>(ISQWZjvgEeuHVPEs=w-iZuXtAaSeObF>va?hS5f27W= zZ1FO5$scaj$qOo;<(A0cm64=xlsF}*Pgn3}ts5?jVxvs0v< zTEfLuSwjhdus_j2#loqMz?T9mp(=s_$wNDf13P7waly0GWE#gH!Nt0JGM3bXuOGyT z-uf~+>QQ*Ve+tRMM-B()Ac>wfN( zuWb!KV+o7s%3s9}E|F?io9W$xY+g2LSEj%%p5RAT(g@4wRH1$!c&Io*$rY}yGScPu|p{oZ=f#p3p>IFzsoytn`WRQ;s6Jl^6c~$ z)re>z-OUmu$aD#o7N@NI0Z~GGUV>;vQgsG{{$LK52Px^yYNW4a+vE1;%xnvusA206 zDSIG$c6zeSt9vvpw)38bO6e8%uwNcLRe}WUF6geA^c*{OIX;gJty8gxD?q147Qv6x zvWP3MSVZI*Uq6d@ISe6?GkAcL^Al|E;5wb%&H@MmcTbLnpz-i>Z)dbqrR*#1@Oj%? z3`E&PkIoysLV>csMvmg68^eCWod3`=AoIS71ORO~%;Y(^VBk_qzU4kODM<}n&vYSC z*F$RIdc%e?Y-CO0OKcOPm1k!^n`!UNFc4}cq$M4KiQ)CGzTT8%AO5cR5-N$bkQY5U zDZJf#ict1)fBORj^b!ZkpAQSI9hP3I4LsE1t})v9d)|5F{Yk_7?ryK#&{6MUy@QbB zJHl9uS}sV(Z=Fr9G^wQj4vVL9Q%<%(KDyV3&sZl)O#Vr$Ox)qFCAj*b3Pd|9X*XcX zi+HsbH!WOMhC_qJ9ek}Y6&NF(5wenG zD99H9`-oBgKVYGTY*F8C?*auC6O%HPB1cDUToq%*1P`^Xam9vQ(ol>m)8559?MkpV zd`w4^c2&XECj*2?b_VVES{i%U-A{YM@%D$EHebruN8y{;A8A+ZM^)^0@7gCmtw_HD7n!sc@h{Sul57|Z5v|R4^3mv4zM>n2yu75IXJ{*E*hHXoWt{t* zDewjC>hG!JH;8W!_e_sL@g+SA2D?qBv)eyx16k-x)vD)NS8i;<&~;}n+#t|UnDzbI z)bzT7aUFo|@&I0YD8?bW3MM0f1Q0cJ<<;zVTGXq6Pu%LR#WyiDRnVsg(tQp`6125p z6hAuOZ+A{QyT`JzcOR#mt8j8m919q^&zPxf*9<@U3CN-WCKpkk=I%#oA2Wg7?(Fi6mo#Gam~e1P4H1AtR@)|?%v zqH%{eHhT#CO+}UZT+gA za)ewcxC3iAvKx;_I}asJL$=Sfv75Yec+=ubR!&fMh`bC|OtmYckn`tT*sPx&wd8VR z_@p%^Mf#@7R=cA4$~-Q-!3gKz!A6rIOp0Nz$q^OS^Ajp>VH!$CPOh#Tgu95$-HXkmv63lxi4a}T|kPDa3lc=`wv=cID4VqI(9ATlsS z*;jk6zrPRo7)G3W%2*X|K;Q(8n}>LtmPoo!*D2Ia*C3*&m;iNX$6OH#PJsLe6_Drc zC7@3~6qX?UJkLGDALvq~@2y(8B-PIpall|%8qh^Enbj)-!NP3{qvJs@z%qe#T1$al z5o~%+1(J5&BU z3Gcp)pEY?wta;_F>bImS!#(Q=+1|MM=}oeqRVWC!LDWY4X6t4LrQUo|4h=KRumZw-1#IBGzHx}XE-p!-|xvz z2O_BPK2&*g;k_210q=dchEwfIX&GXk8Zquocjn5XH~Q)9#)?20NT#ndL9l_1FI-%hub+3oMQ}~B zN3B-7Rk06Xpdsme3+4=(xD?w*ENXw$`S76sVCP_Mc~dk<>4b>kgD05XbD=<&FL5f` z3bUJ{E?LJEwK+}!1wiRUc`B%?mhp`Ns`DMd`bB{18kS?pO93qzS5A&~oXaU9q02JY zBf|?vGK!opE0MQe=6>aimxcR{3>SgXsX`|l+1aCPRq+}KBeyIlA>n#J(a0jRLB7{w za87r(D;FUcu^^uaxU1xiUhAzfl@S`afW0hLfCSrx_#E|daQt|%+u73i%A5DrZf$LE z+`Y4WZ)t0DdwK1ya$Q%y6YhxwOX6Dtzf~-VMtN4MPU&OSemlNzEWu*L_(K~r;c*IB zRY@!c3{&#X!eOCUqs_A1f^|+|0cgr1!dEBqDVKnIfZyx&pY*siwgxlqL^yhI9;-`! zG&A)IY~HzdcWGt&?wvbZDd;U+F32x?=CbDV(KiBzAM}xa*kwGiiQ7Bcp!{_-~XbW~^zPZeQ_(ps7T(V0G4unKn*tM7C!%-XT$Vy^N z^&jH|?lA1aQuYP+#L#3h29LE5qtJQj%bA7Er$fkNq7e{ekV+am3)1XamZELKUdvpY=Umy(eX%effoXoQo1UJ(B;Fq&|aC%NxK;DpljjdmpIXMBIipV^pbZ)H!2K*tRQ?hJ4Ud;zEhax`FH9 z%Q|bRV6C43)>zu~PiPLxBKS|)?fnz@I3ISR<`9&i*h(B+R8vItU6c@^+dD%V zsFyBYxq9W=<+ra~jim@ywbttjcJ!s;1lThKWR#^10H`*9P^;s>Fg+Uef~uyA+Y=E) z7YurDRk#I3^(*cdLx=7mE(ZM*DPQm4wEb#-u-rk+=~D(cG2tXQD6fyeX&k`uf`Kp5 z!e%k|71i3~Z<T1>TQkmfw~V1ff9Wj$2)ks``J z5iIzgsd_WlW#u6PFkM9#F>F``2M{#A8}AePlGV-0fCWqnJJLrMu0ecTa*Vx5S80K~ z-ElT<&ZrY_psiz~^YM*Mt^udrf&oZ{EmjaZ9bv?4;ioW4;_bY*;8O+YwG-h!mhQwd zFto&3%UMCRrH#sJfma6`6naC5?@fm!eTo!xp#dC9JPTmldH&tZ!2nWv=j{tu7gsJK zFa6TBx2~?db>YI&^2N(n-=PltItlBW-C=1eoBoe(kkZS7XhM`>5pT?m2(RZy1j6JxG=S>Zn9@x zs*E;$vwEnz=vc!em5vHa6KQKbAm+irMv)z6CD%do3CB$7&DsiHgFxM&@q}C}GBIo2 z?Ll)f1$)_=jyiRX0i&6O?`HhMm;=V3e7l+bLY~p~EOK7^mNQ-S3Z>z~wbh$fufB76 zb>-TXi*LQPymaBx;^NYUtI8)do>raF7z3d4OveGl32K0~J_W4{$W`@=pJ-OPowMHqww38T=-$|urD@o z8<%$0FE*=pNYN9kQ@E8pePDv1!;A5Qg_g&dLnfZMyqi-qVlT; z?I0??1Zzw*7h!_bJOcel4}IuU&}WiWQm!=(912Yyfnfp2ZK%?e!m^ z_!o0Bd+_b~){{rwU67t>e1jkC9^xQb>WBYKN__5dM6Sl8h-6|C7c}B(SP$z7(lIoJ z-k0Mjwhm!U4HIh)MXWpg<^51{`iC2>*Q{yP0kz9+4-prmIkzYf--0@ywPs#_wsdEG zb?w7@cNe$T?yP?~L&+jZ4+AFY7(`;Bk8_#@vGw_T(mWUe$IjEuq1&I6gU&u4gi|#P z!AjtyvI@P1Vzc{QlZwO-nW_UcYMCDsIZS*M2Z}#D$UsOXv5CH9a3T7 zxZ(Ubh=5{mFTxL$-zSvT?cv%B>QN^C-!qZGBK|iQ4=bd?MpQxnf-A-+SD%`gz11NJ z&vZLlHw(i@$!O%Ok|nXt>;PSTARCxgf~PnOj!a+gO4JdOZvt^~I2_6OIm=Z3aCMwg zXPS(9hQqi~&%dkA0YouX+Nc}Z)&`AiYa%t(3oX=aV`;%{V`;-5oIKGAFuH<pyM&rMcT-0w7OXbbKkbI3k5#YfytgT7c#4)1i9?7XX zninCZsyaB%w~yrr4DkVjg$kn8rqd``<8;4nv1%h}T2$hIvD`Y^e7rO0?)215DjLyg zfgD-N057Mn5eg7JH#ku;$G?(4crbW-%88{)MNz3BQ98hgKV`2x&vhpvS-mqBtCU!g z$vC*StR;r8{2>gtYS!tPa>g8uEd8o)RilMo zW|I#ruc8B*@J+DZAdjjRWTsOjAzE{}YE&9lguQTBj}Mln&z+UA)Pskw*w9U^F}PSJ zY_;jySiJSg;`cYVH&+(#E`79pZ*%4D_QvAYN1JGP{SKD~BQ$n1lH-4xx6bcz6uCR5 zdHCw?eYm~0zIx~GZBe4P^)EC(v-f0Yuz&tZcl7A|-tg%mTsGDlR|-T$cnN>QQT;Tp z1h>ujO#q>w8Eszj}g`N+0_5OC`lJ?AF#dw-#^R5&~mw zT8rr<d{&TS-15}#;2>4mt-8PmoLa&B?h=UQPmE(xAY7b3?U!ua*(M;g!DGRQs zJtc0n4c1Qwr*Kh0sh7w-AsX2BPmX=+*cphgc&3{xSV5rBI=I@$E8D_77nio~E#6{+ z9cG}>qmA9m*WTs}Mh2iAuG-7+|J|9{u?}=jEJmJ=CE*!R2Zg043z@>yY|AV|aU)Ix! z@TEH&-{0Q&XmN7|xOsPN1Mp2Wg9$4_aj~?0YjOR;09J-Hu);J6?pCKw4QBVZOAnvAy!?(#i(CbrlUJ(J8!>yIWgpAKi)yA}e-fMgn}ujB|i{*iZa|2_vucVs8%;3`wMqEv-)ktO@l&%l-zQ|F)X^n zoiC7xMU3-ycPM%5#paWX4CZICR=A~N{SMC$K(GgTGgXu6<5XY!Z07v_K2BYnXIg-e zBt+D)NPepa{hiS&N->8A%JcF35P3v9v4$qVQEo2fd7f<7YV;4gqx1VbD{%e@$0(4| z5*5=L>wSqZ+t80xvvj1=9!fsLv46UZ`3%;<@zc9@w1Xv{lSkd_BKFHi!S!roNSZ<_ zXtWR`Ijh*CHDsU7$`c9#*}e*0-tv2A>m&FAmR4^qeh4t51U9qKtU%NTigUfdq{IX0 zYsT{myx~^wjhY$Cd5W2H;uFN^xf`W}N>7ZSDLYtOn$pbq137%bQlb@+I(R#feK>-b*`OFY2^e5bEoE*#wQIG*xUI}V0H&3HF4g4CAMVUk6yAkbGP5A zcV4Ul&^$qBcp;SgDBUT_mO5|r8FFa_Q9;&v)!TD5U$ds!CS98r3{V@W$s9g9Dh4eW`;FU;K#)TlXy716*%75g|y5qY)n zH?)X>TPoRXTx-LRyTk4Sqy&y9U>b_9>;AX<@=KjZLSVj@+V-+8(@TuY^mWTaGj*f$ z>sz42?^FU3R+0xKl`;YABn;teT_LPaNN4FAV z`H1dB#Prr-l48Qanf@o_N>XCA!y76wjN!Q(t*NGBlb5OlG+_vdTBV(6c2yu8$AioW zI17uekclU76CHSXY%9N$yhhraCPCr^tao*)awkui5?fB%^F7E~3*08Nf#77IL~vO+ zRfM9Hh*}!~-L9nu8MD*v8!R!0SlnuD}Ym07Yk9rtD)mZz6++7n zc3P*_oZdRm5$O6!_YA0g>{&Hk#lglbR$S~K$)$^K!dTPvt{M{ulp#bNvzccsqPD=) zXopIC0(-AewlJ`W`^UN?WY&fvgOF{UHXo5~tM`R$Y%2bzmWZN2U78PBB!R6yd-q& zKm)$%D3yO|YnT=WfLnKt03Po^fr|GG9UoVXMPfZ=)LyNr9!r(#DeRm3V?C5XcS;x} z!;*YK8Rio#WbsqnMWqzm9Si|qD0qn1IvYJ4kz;+Ogp;kN70_YfU!e=52h3Mcuucsn zV(`*V3MG+axa69S9lhpT#3xli&$kJ?0FsKHQHgXDE-nqo*J3Nc7Ws%pAjM;LmKXz1 zLq^ zkQ8Mif=Sf5qaE`>)%D*=@v8OA;-}BGZ)(zW^fOu9wU5z1_=SrUz_5+%O& zC*h^B4Lbg3MVkTvhK6TnTas2GeHT8%<-fr1YH$M_yitp^qVR#^$onFIM1H@EaC+R; zl{A5tf1p}1eWq#)@pFK&T(rnmCqpUReF1-2ykkdk66iq<-i<}QrALt`xo*R7gBljb zl`6fni*Wa4I7SIW_N8zBE97@JHT~bISE;1Ro^H1ERSfH>J?{zD8w2VjgfU&@sIF#u+IV z6c2F0`oZ2XvivrLGGbPdJ&17N24=!&gM=W*Rq^djd5mp>T)z=u58Wdbm8Qcq$lUK)kg^X3+rfGlfaJ;?bbj#| ztOp7TpaZN0)`WulogL&g@3cd{obhA!dhVS_w*dSbM63U)B#;9aYwWU7;FKVP%2dax zZCmbbW>uL}av@I;q)MN4Rdi9c7%nq~Tdyw+Fjf>;E}*$ycfT_n37xrz^Kl}(tqqaf z4UI^2%Hv4kj+w>|0RA}(5j~e)PclTD;vC3`(Ivd!-Ka|9s*eDbImU>rg&)C7t=dSB8pl^RJ;S%#LMi<^*{NBp;$18U? z5!)JkCKnx@lLm#?#MYE7!K|L}1K5KtYOG4Ma){`9Np#L!U~mm}8YXPlcdqxDnT(NR z2B_BDOuHRn)^5X(CU=Q{2V(A$u9va=$ZKrT!gXW9uFLBrgC~QJY=&ztC=3kr$O(w}N+g z#kPfY*4q}&DOc=b9f$_c*Ib38M_h911u~twd0q1v@nA7wr|tszE^3?0#Wo}Cf$cqP z1j5F0q)}9Rz+gd<_}at}b8P^HnI$Z7T4>10h3Q0!Gk_p%IKt4i_y}AB5FqT&%^=E* zQLF)l-WVbrvJJE`d^EE(>fes1kalzRGN9)tlXclU+@3-eqZNv#>)S`J^xWF_b=`FPye|O?9EsE^J9biq+T{`eP8|R zy1atJD>#s5UN#=E&Gdhrf2Dl%cYaTQ|HnUhQ$GLR&*<;p{#pI~7k^2A|K4}>_q%iY z`#0wG_ZP0}?_c|Q{r&s*_4hye75)A8kM#Ff{wMwY>;G7P|Kk6uzyJKl`uofOOn(o5 zM}Pm@Kd~g^`KNzIfB)8B(BJ>`lK%d>{r>DVeLh*z-;GuM{hg2W_tDSm?|=Te{{E{S z{rzaDzdK**@ArRMfB%QSrN969zt`XY`k(0UZ~Zg<{lEUT{{F}Rum1jjUoOiyf9XHb z-@pDh^!M-lm-_n)|DFE+@K^QspUB7ag zFT8!>oik_J!$$~|f~WNi0%Ni3d~~J_uRy20cysMM?p(1a94l8Z!1?apnKqx0rTNjB zHtvu{jv4(O4fKmSyRwIEd}AB~E7)I02P1ab#lO4{{7f5%UAy?!-^0n%Gwsf!Z3)%X zGTS?Y!Ol}H31Oez5ieM)(3b)y+?k|{BM6mfB%^NoN+zF9?#ssAB2I|cYWxZDM-I- z`V1dAcdzey3AG<~;q_g=y6~s)69033N}se1|C_(-_>a1b*LVHpPn*K^e_LT6znAmh z&+whPkw3eBbmq@%#UEOIj-Rme@!RV&Kd|>+-}SK{T7B2YynnCn^CuFr-J8~+>vz9v z^<5uieZH#J|EqXMxEi?6T=>ohc!Hiv#K8altp0?5tLy(1U()(fu4t8i=?z;8KU4Yr zuu9yGV>N{aN8u<8qU4Em||Bua{`SGvm z{Jk8C$^X2*|NhT-n~vY@q2IRpKlFh$)c-#!^&kCcRZ2ekk@o+aibhsD(vQFRKk*00 z;@w>PM_T{dKhpYhUeJDh-2VEX;170j!C%;~*MG0_-iMR^df#c$q4n?l%fER&fBydg DCj`Ho literal 0 HcmV?d00001 From 41df15a46401a53772bcb651288312ae463c9020 Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Sun, 19 Mar 2017 00:19:04 +0300 Subject: [PATCH 57/66] MJCF: fix B3_PI, fix colors, fix capsule without 'fromto' --- .../ImportMJCFDemo/BulletMJCFImporter.cpp | 27 ++++++++-- .../Importers/ImportURDFDemo/UrdfParser.cpp | 18 +++---- .../Importers/ImportURDFDemo/UrdfParser.h | 13 +++-- .../TinyRendererVisualShapeConverter.cpp | 50 ++++++++++++------- 4 files changed, 75 insertions(+), 33 deletions(-) diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index 0fb20ad28..b1cbdb5d3 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -155,6 +155,9 @@ struct BulletMJCFImporterInternalData // joint defaults std::string m_defaultJointLimited; + // geom defaults + std::string m_defaultGeomRgba; + //those collision shapes are deleted by caller (todo: make sure this happens!) btAlignedObjectArray m_allocatedCollisionShapes; @@ -270,6 +273,11 @@ struct BulletMJCFImporterInternalData { m_defaultCollisionMask = urdfLexicalCast(conAffinityStr); } + const char* rgba = child_xml->Attribute("rgba"); + if (rgba) + { + m_defaultGeomRgba = rgba; + } } } handled=true; @@ -404,8 +412,8 @@ struct BulletMJCFImporterInternalData if (sizes.size()==2) { // TODO angle units are in " - range[0] = sizes[0] * M_PI / 180; - range[1] = sizes[1] * M_PI / 180; + range[0] = sizes[0] * B3_PI / 180; + range[1] = sizes[1] * B3_PI / 180; } else { logger->reportWarning("Expected range[2] in joint with limits"); @@ -526,10 +534,23 @@ struct BulletMJCFImporterInternalData -// const char* rgba = link_xml->Attribute("rgba"); const char* gType = link_xml->Attribute("type"); const char* sz = link_xml->Attribute("size"); const char* posS = link_xml->Attribute("pos"); + + std::string rgba = m_defaultGeomRgba; + if (const char* rgbattr = link_xml->Attribute("rgba")) + { + rgba = rgbattr; + } + if (!rgba.empty()) + { + // "0 0.7 0.7 1" + parseVector4(geom.m_localMaterial.m_rgbaColor, rgba); + geom.m_hasLocalMaterial = true; + geom.m_localMaterial.m_name = rgba; + } + if (posS) { btVector3 pos(0,0,0); diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index ad5247710..cc188e74d 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -575,7 +575,7 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* if (name_char) visual.m_name = name_char; - visual.m_hasLocalMaterial = false; + visual.m_geometry.m_hasLocalMaterial = false; // Material TiXmlElement *mat = config->FirstChildElement("material"); @@ -597,7 +597,7 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* matPtr->m_rgbaColor = rgba; visual.m_materialName = matPtr->m_name; - visual.m_hasLocalMaterial = true; + visual.m_geometry.m_hasLocalMaterial = true; } } else @@ -616,11 +616,11 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* TiXmlElement *c = mat->FirstChildElement("color"); if (t||c) { - if (parseMaterial(visual.m_localMaterial, mat,logger)) + if (parseMaterial(visual.m_geometry.m_localMaterial, mat,logger)) { - UrdfMaterial* matPtr = new UrdfMaterial(visual.m_localMaterial); + UrdfMaterial* matPtr = new UrdfMaterial(visual.m_geometry.m_localMaterial); model.m_materials.insert(matPtr->m_name.c_str(),matPtr); - visual.m_hasLocalMaterial = true; + visual.m_geometry.m_hasLocalMaterial = true; } } } @@ -1408,12 +1408,12 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF for (int i=0;im_visualArray.size();i++) { UrdfVisual& vis = link->m_visualArray.at(i); - if (!vis.m_hasLocalMaterial && vis.m_materialName.c_str()) + if (!vis.m_geometry.m_hasLocalMaterial && vis.m_materialName.c_str()) { UrdfMaterial** mat = m_urdf2Model.m_materials.find(vis.m_materialName.c_str()); if (mat && *mat) { - vis.m_localMaterial = **mat; + vis.m_geometry.m_localMaterial = **mat; } else { //logger->reportError("Cannot find material with name:"); @@ -1603,12 +1603,12 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger) for (int i=0;im_visualArray.size();i++) { UrdfVisual& vis = link->m_visualArray.at(i); - if (!vis.m_hasLocalMaterial && vis.m_materialName.c_str()) + if (!vis.m_geometry.m_hasLocalMaterial && vis.m_materialName.c_str()) { UrdfMaterial** mat = localModel->m_materials.find(vis.m_materialName.c_str()); if (mat && *mat) { - vis.m_localMaterial = **mat; + vis.m_geometry.m_localMaterial = **mat; } else { //logger->reportError("Cannot find material with name:"); diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 6c2e0e090..1967cd729 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -18,9 +18,13 @@ struct ErrorLogger struct UrdfMaterial { - std::string m_name; + std::string m_name; std::string m_textureFilename; - btVector4 m_rgbaColor; + btVector4 m_rgbaColor; // [0]==r [1]==g [2]==b [3]==a + UrdfMaterial(): + m_rgbaColor(0.8, 0.8, 0.8, 1) + { + } }; struct UrdfInertia @@ -79,6 +83,9 @@ struct UrdfGeometry int m_meshFileType; std::string m_meshFileName; btVector3 m_meshScale; + + UrdfMaterial m_localMaterial; + bool m_hasLocalMaterial; }; bool findExistingMeshFile(const std::string& urdf_path, std::string fn, @@ -96,8 +103,6 @@ struct UrdfShape struct UrdfVisual: UrdfShape { std::string m_materialName; - bool m_hasLocalMaterial; - UrdfMaterial m_localMaterial; }; struct UrdfCollision: UrdfShape diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 58fd7f13e..a3631e9e2 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -178,6 +178,12 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi visualShapeOut.m_dimensions[1] = 0; visualShapeOut.m_dimensions[2] = 0; visualShapeOut.m_meshAssetFileName[0] = 0; + if (visual->m_geometry.m_hasLocalMaterial) { + visualShapeOut.m_rgbaColor[0] = visual->m_geometry.m_localMaterial.m_rgbaColor[0]; + visualShapeOut.m_rgbaColor[1] = visual->m_geometry.m_localMaterial.m_rgbaColor[1]; + visualShapeOut.m_rgbaColor[2] = visual->m_geometry.m_localMaterial.m_rgbaColor[2]; + visualShapeOut.m_rgbaColor[3] = visual->m_geometry.m_localMaterial.m_rgbaColor[3]; + } GLInstanceGraphicsShape* glmesh = 0; @@ -215,23 +221,33 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi { btVector3 p1 = visual->m_geometry.m_capsuleFrom; btVector3 p2 = visual->m_geometry.m_capsuleTo; - btVector3 v = p2 - p1; - btVector3 center = (p2 + p1) * 0.5; - btScalar rad = visual->m_geometry.m_capsuleRadius; - btVector3 up_vector(0,0,1); - btVector3 dir = v.normalized(); - btVector3 axis = dir.cross(up_vector); - if (axis.fuzzyZero()) - { - axis = btVector3(0,0,1); + btTransform tr; + tr.setIdentity(); + btScalar rad, len; + if (visual->m_geometry.m_hasFromTo) { + btVector3 v = p2 - p1; + btVector3 center = (p2 + p1) * 0.5; + btVector3 up_vector(0,0,1); + btVector3 dir = v.normalized(); + btVector3 axis = dir.cross(up_vector); + if (axis.fuzzyZero()) + { + axis = btVector3(0,0,1); + } + else + { + axis.normalize(); + } + btQuaternion q(axis, -acos(dir.dot(up_vector))); + btTransform capsule_orient(q, center); + tr = visual->m_linkLocalFrame * capsule_orient; + len = v.length(); + rad = visual->m_geometry.m_capsuleRadius; + } else { + tr = visual->m_linkLocalFrame; + len = visual->m_geometry.m_capsuleHalfHeight; + rad = visual->m_geometry.m_capsuleRadius; } - else - { - axis.normalize(); - } - btQuaternion q(axis, -acos(dir.dot(up_vector))); - btTransform capsule_orient(q, center); - btTransform tr = visual->m_linkLocalFrame * capsule_orient; visualShapeOut.m_localVisualFrame[0] = tr.getOrigin()[0]; visualShapeOut.m_localVisualFrame[1] = tr.getOrigin()[1]; visualShapeOut.m_localVisualFrame[2] = tr.getOrigin()[2]; @@ -239,7 +255,7 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi visualShapeOut.m_localVisualFrame[4] = tr.getRotation()[1]; visualShapeOut.m_localVisualFrame[5] = tr.getRotation()[2]; visualShapeOut.m_localVisualFrame[6] = tr.getRotation()[3]; - visualShapeOut.m_dimensions[0] = v.length(); + visualShapeOut.m_dimensions[0] = len; visualShapeOut.m_dimensions[1] = rad; break; } From 6695268fbaa5f987d2c44bf43f988c3749ea3820 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Mon, 20 Mar 2017 09:52:24 -0700 Subject: [PATCH 58/66] Fix the issue with indentation in pr2 setup. --- examples/pybullet/vr_kuka_pr2_move.py | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/examples/pybullet/vr_kuka_pr2_move.py b/examples/pybullet/vr_kuka_pr2_move.py index 22e5730c1..53dbe844d 100644 --- a/examples/pybullet/vr_kuka_pr2_move.py +++ b/examples/pybullet/vr_kuka_pr2_move.py @@ -15,14 +15,8 @@ BUTTONS=6 gripper_max_joint = 0.550569 while True: events = p.getVREvents() - - for e in (events): - if e[CONTROLLER_ID] == 3: # To make sure we only get the value for one of the remotes - p.changeConstraint(pr2_cid, e[POSITION], e[ORIENTATION], maxForce=500) - p.setJointMotorControl2(pr2_gripper, 0, controlMode=p.POSITION_CONTROL, - targetPosition=gripper_max_joint - e[ANALOG] * gripper_max_joint, - force=1.0) - p.setJointMotorControl2(pr2_gripper, 2, controlMode=p.POSITION_CONTROL, - targetPosition=gripper_max_joint - e[ANALOG] * gripper_max_joint, - force=1.1) - \ No newline at end of file + for e in (events): + if e[CONTROLLER_ID] == 3: # To make sure we only get the value for one of the remotes + p.changeConstraint(pr2_cid, e[POSITION], e[ORIENTATION], maxForce=500) + p.setJointMotorControl2(pr2_gripper, 0, controlMode=p.POSITION_CONTROL,targetPosition=gripper_max_joint - e[ANALOG] * gripper_max_joint,force=1.0) + p.setJointMotorControl2(pr2_gripper, 2, controlMode=p.POSITION_CONTROL,targetPosition=gripper_max_joint - e[ANALOG] * gripper_max_joint,force=1.1) \ No newline at end of file From 753f1d3d2f447ba2435edbf677fb1e4e04338d23 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Mon, 20 Mar 2017 10:16:15 -0700 Subject: [PATCH 59/66] Add lateral and spinning friction coefficients to gripper sdf model. --- data/gripper/wsg50_with_r2d2_gripper.sdf | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/data/gripper/wsg50_with_r2d2_gripper.sdf b/data/gripper/wsg50_with_r2d2_gripper.sdf index b022faf00..d67959f19 100644 --- a/data/gripper/wsg50_with_r2d2_gripper.sdf +++ b/data/gripper/wsg50_with_r2d2_gripper.sdf @@ -215,6 +215,10 @@ + + 1.0 + 1.5 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -255,6 +259,10 @@ + + 1.0 + 1.5 + -0.062 0 0.145 0 0 4.71239 0.2 From 0b017b0f53be0e6926f6b86922248f5955656c90 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 20 Mar 2017 10:58:07 -0700 Subject: [PATCH 60/66] fix issue with btMultiBody friction in combination with soft contacts (friction should not re-use normal contact cfm/erp) implement friction anchors, position friction correction, disabled by default. Use colObj->setCollisionFlag(flag | CF_HAS_FRICTION_ANCHOR); See test/RobotClientAPI/SlopeFrictionMain.cpp. In URDF or SDF, add in section of to enable. PhysicsServer: properly restore old activation state after releasing picked object btMultiBodyConstraintSolver: disable flip/flop of contact/friction constraint solving by default (it breaks some internal flaky unit tests) --- data/cube_soft.urdf | 3 +- .../Importers/ImportURDFDemo/URDF2Bullet.cpp | 4 + .../Importers/ImportURDFDemo/URDFJointTypes.h | 3 +- .../Importers/ImportURDFDemo/UrdfParser.cpp | 7 ++ .../RobotSimulator/RobotSimulatorMain.cpp | 33 ++++-- .../b3RobotSimulatorClientAPI.cpp | 4 +- examples/SharedMemory/PhysicsClientC_API.cpp | 4 +- .../PhysicsServerCommandProcessor.cpp | 7 +- .../CollisionDispatch/btCollisionObject.h | 1 + .../CollisionDispatch/btManifoldResult.cpp | 8 +- .../NarrowPhaseCollision/btManifoldPoint.h | 1 + .../btPersistentManifold.cpp | 1 + .../btPersistentManifold.h | 55 +++++---- .../ConstraintSolver/btContactSolverInfo.h | 13 +- .../btSequentialImpulseConstraintSolver.cpp | 34 ++++-- .../btSequentialImpulseConstraintSolver.h | 3 +- .../btMultiBodyConstraintSolver.cpp | 98 ++++++++++------ test/RobotClientAPI/SlopeFrictionMain.cpp | 111 ++++++++++++++++++ 18 files changed, 299 insertions(+), 91 deletions(-) create mode 100644 test/RobotClientAPI/SlopeFrictionMain.cpp diff --git a/data/cube_soft.urdf b/data/cube_soft.urdf index af40dd379..6354ab3b6 100644 --- a/data/cube_soft.urdf +++ b/data/cube_soft.urdf @@ -2,7 +2,8 @@ - + + diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index 30f35963a..d4065b8fe 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -166,6 +166,10 @@ void processContactParameters(const URDFLinkContactInfo& contactInfo, btCollisio { col->setContactStiffnessAndDamping(contactInfo.m_contactStiffness, contactInfo.m_contactDamping); } + if ((contactInfo.m_flags & URDF_CONTACT_HAS_FRICTION_ANCHOR) != 0) + { + col->setCollisionFlags(col->getCollisionFlags() | btCollisionObject::CF_HAS_FRICTION_ANCHOR); + } } diff --git a/examples/Importers/ImportURDFDemo/URDFJointTypes.h b/examples/Importers/ImportURDFDemo/URDFJointTypes.h index cc39e8913..3a11d981e 100644 --- a/examples/Importers/ImportURDFDemo/URDFJointTypes.h +++ b/examples/Importers/ImportURDFDemo/URDFJointTypes.h @@ -23,7 +23,8 @@ enum URDF_LinkContactFlags URDF_CONTACT_HAS_ROLLING_FRICTION=32, URDF_CONTACT_HAS_SPINNING_FRICTION=64, URDF_CONTACT_HAS_RESTITUTION=128, - + URDF_CONTACT_HAS_FRICTION_ANCHOR=256, + }; struct URDFLinkContactInfo diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index ad5247710..c273a8d9c 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -767,6 +767,13 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi } } + } + { + TiXmlElement *friction_anchor = ci->FirstChildElement("friction_anchor"); + if (friction_anchor) + { + link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_FRICTION_ANCHOR; + } } { diff --git a/examples/RobotSimulator/RobotSimulatorMain.cpp b/examples/RobotSimulator/RobotSimulatorMain.cpp index 7ab3f3e70..558c5e9de 100644 --- a/examples/RobotSimulator/RobotSimulatorMain.cpp +++ b/examples/RobotSimulator/RobotSimulatorMain.cpp @@ -61,6 +61,7 @@ int main(int argc, char* argv[]) sim->setRealTimeSimulation(false); int vidLogId = -1; int minitaurLogId = -1; + int rotateCamera = 0; while (sim->canSubmitCommand()) { @@ -73,9 +74,11 @@ int main(int argc, char* argv[]) //m_keyState is a flag combination of eButtonIsDown,eButtonTriggered, eButtonReleased for (int i=0;istartStateLogging(STATE_LOGGING_MINITAUR,"simlog.bin"); } - if (minitaurLogId>=0 && keyEvents.m_keyboardEvents[i].m_keyState&eButtonReleased) + if (minitaurLogId>=0 && e.m_keyState&eButtonReleased) { sim->stopStateLogging(minitaurLogId); minitaurLogId=-1; } } + if (e.m_keyCode == 'r' && e.m_keyState&eButtonTriggered) + { + rotateCamera = 1-rotateCamera; + } + //printf("keyEvent[%d].m_keyCode = %d, state = %d\n", i,keyEvents.m_keyboardEvents[i].m_keyCode,keyEvents.m_keyboardEvents[i].m_keyState); } } sim->stepSimulation(); - static double yaw=0; - double distance = 10.5+9 * b3Sin(yaw); - yaw+=0.008; - sim->resetDebugVisualizerCamera(distance,yaw,20,b3MakeVector3(0,0,0.1)); + + if (rotateCamera) + { + static double yaw=0; + double distance = 1; + yaw+=0.1; + b3Vector3 basePos; + b3Quaternion baseOrn; + sim->getBasePositionAndOrientation(minitaurUid,basePos,baseOrn); + sim->resetDebugVisualizerCamera(distance,yaw,20,basePos); + } b3Clock::usleep(1000.*1000.*fixedTimeStep); } diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 8b2834a2f..64b062964 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -210,7 +210,7 @@ void b3RobotSimulatorClientAPI::stepSimulation() { statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitStepSimulationCommand(m_data->m_physicsClientHandle)); statusType = b3GetStatusType(statusHandle); - b3Assert(statusType == CMD_STEP_FORWARD_SIMULATION_COMPLETED); + //b3Assert(statusType == CMD_STEP_FORWARD_SIMULATION_COMPLETED); } } @@ -226,7 +226,7 @@ void b3RobotSimulatorClientAPI::setGravity(const b3Vector3& gravityAcceleration) b3SharedMemoryStatusHandle statusHandle; b3PhysicsParamSetGravity(command, gravityAcceleration[0], gravityAcceleration[1], gravityAcceleration[2]); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); - b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); +// b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); } b3Quaternion b3RobotSimulatorClientAPI::getQuaternionFromEuler(const b3Vector3& rollPitchYaw) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index a7d23f68c..5ac6ea74a 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -914,7 +914,7 @@ b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClien int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; - b3Assert(status); + //b3Assert(status); if (status) { return status->m_type; @@ -1063,7 +1063,7 @@ b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHan b3SubmitClientCommand(physClient, commandHandle); - while ((statusHandle == 0) && (clock.getTimeInSeconds()-startTime < timeOutInSeconds)) + while (cl->isConnected() && (statusHandle == 0) && (clock.getTimeInSeconds()-startTime < timeOutInSeconds)) { statusHandle = b3ProcessServerStatus(physClient); } diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 9fd045f9b..b729392d3 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -919,6 +919,7 @@ struct PhysicsServerCommandProcessorInternalData //data for picking objects class btRigidBody* m_pickedBody; + int m_savedActivationState; class btTypedConstraint* m_pickedConstraint; class btMultiBodyPoint2Point* m_pickingMultiBodyPoint2Point; btVector3 m_oldPickingPos; @@ -1146,7 +1147,8 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0)); m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08; - + + m_data->m_dynamicsWorld->getSolverInfo().m_frictionERP = 0.2;//need to check if there are artifacts with frictionERP m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001; m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50; m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7; @@ -4978,6 +4980,7 @@ bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, cons if (!(body->isStaticObject() || body->isKinematicObject())) { m_data->m_pickedBody = body; + m_data->m_savedActivationState = body->getActivationState(); m_data->m_pickedBody->setActivationState(DISABLE_DEACTIVATION); //printf("pickPos=%f,%f,%f\n",pickPos.getX(),pickPos.getY(),pickPos.getZ()); btVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos; @@ -5070,7 +5073,7 @@ void PhysicsServerCommandProcessor::removePickingConstraint() m_data->m_dynamicsWorld->removeConstraint(m_data->m_pickedConstraint); delete m_data->m_pickedConstraint; m_data->m_pickedConstraint = 0; - m_data->m_pickedBody->forceActivationState(ACTIVE_TAG); + m_data->m_pickedBody->forceActivationState(m_data->m_savedActivationState); m_data->m_pickedBody = 0; } if (m_data->m_pickingMultiBodyPoint2Point) diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObject.h b/src/BulletCollision/CollisionDispatch/btCollisionObject.h index 0cae21000..598ad2229 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObject.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionObject.h @@ -139,6 +139,7 @@ public: CF_DISABLE_SPU_COLLISION_PROCESSING = 64,//disable parallel/SPU processing CF_HAS_CONTACT_STIFFNESS_DAMPING = 128, CF_HAS_CUSTOM_DEBUG_RENDERING_COLOR = 256, + CF_HAS_FRICTION_ANCHOR = 512, }; enum CollisionObjectTypes diff --git a/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp b/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp index be8e51d52..621292e22 100644 --- a/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp +++ b/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp @@ -145,7 +145,13 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b newPt.m_combinedContactStiffness1 = calculateCombinedContactStiffness(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); newPt.m_contactPointFlags |= BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING; } - + + if ( (m_body0Wrap->getCollisionObject()->getCollisionFlags()& btCollisionObject::CF_HAS_FRICTION_ANCHOR) || + (m_body1Wrap->getCollisionObject()->getCollisionFlags()& btCollisionObject::CF_HAS_FRICTION_ANCHOR)) + { + newPt.m_contactPointFlags |= BT_CONTACT_FLAG_FRICTION_ANCHOR; + } + btPlaneSpace1(newPt.m_normalWorldOnB,newPt.m_lateralFrictionDir1,newPt.m_lateralFrictionDir2); diff --git a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h index 04ab54ed9..571ad2c5f 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h +++ b/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h @@ -41,6 +41,7 @@ enum btContactPointFlags BT_CONTACT_FLAG_HAS_CONTACT_CFM=2, BT_CONTACT_FLAG_HAS_CONTACT_ERP=4, BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING = 8, + BT_CONTACT_FLAG_FRICTION_ANCHOR = 16, }; /// ManifoldContactPoint collects and maintains persistent contactpoints. diff --git a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp index 4d92e853d..c5bd7c16f 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp @@ -279,6 +279,7 @@ void btPersistentManifold::refreshContactPoints(const btTransform& trA,const btT removeContactPoint(i); } else { + //todo: friction anchor may require the contact to be around a bit longer //contact also becomes invalid when relative movement orthogonal to normal exceeds margin projectedPoint = manifoldPoint.m_positionWorldOnA - manifoldPoint.m_normalWorldOnB * manifoldPoint.m_distance1; projectedDifference = manifoldPoint.m_positionWorldOnB - projectedPoint; diff --git a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h index 3b82be192..a351cb3c2 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h +++ b/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h @@ -172,39 +172,54 @@ public: btAssert(m_pointCache[lastUsedIndex].m_userPersistentData==0); m_cachedPoints--; } - void replaceContactPoint(const btManifoldPoint& newPoint,int insertIndex) + void replaceContactPoint(const btManifoldPoint& newPoint, int insertIndex) { btAssert(validContactDistance(newPoint)); #define MAINTAIN_PERSISTENCY 1 #ifdef MAINTAIN_PERSISTENCY - int lifeTime = m_pointCache[insertIndex].getLifeTime(); - btScalar appliedImpulse = m_pointCache[insertIndex].m_appliedImpulse; - btScalar appliedLateralImpulse1 = m_pointCache[insertIndex].m_appliedImpulseLateral1; - btScalar appliedLateralImpulse2 = m_pointCache[insertIndex].m_appliedImpulseLateral2; -// bool isLateralFrictionInitialized = m_pointCache[insertIndex].m_lateralFrictionInitialized; - - - - btAssert(lifeTime>=0); - void* cache = m_pointCache[insertIndex].m_userPersistentData; - - m_pointCache[insertIndex] = newPoint; - m_pointCache[insertIndex].m_userPersistentData = cache; - m_pointCache[insertIndex].m_appliedImpulse = appliedImpulse; - m_pointCache[insertIndex].m_appliedImpulseLateral1 = appliedLateralImpulse1; - m_pointCache[insertIndex].m_appliedImpulseLateral2 = appliedLateralImpulse2; - + int lifeTime = m_pointCache[insertIndex].getLifeTime(); + btScalar appliedImpulse = m_pointCache[insertIndex].m_appliedImpulse; + btScalar appliedLateralImpulse1 = m_pointCache[insertIndex].m_appliedImpulseLateral1; + btScalar appliedLateralImpulse2 = m_pointCache[insertIndex].m_appliedImpulseLateral2; + + bool replacePoint = true; + ///we keep existing contact points for friction anchors + ///if the friction force is within the Coulomb friction cone + if (newPoint.m_contactPointFlags & BT_CONTACT_FLAG_FRICTION_ANCHOR) + { + // printf("appliedImpulse=%f\n", appliedImpulse); + // printf("appliedLateralImpulse1=%f\n", appliedLateralImpulse1); + // printf("appliedLateralImpulse2=%f\n", appliedLateralImpulse2); + // printf("mu = %f\n", m_pointCache[insertIndex].m_combinedFriction); + btScalar mu = m_pointCache[insertIndex].m_combinedFriction; + btScalar eps = 0; //we could allow to enlarge or shrink the tolerance to check against the friction cone a bit, say 1e-7 + btScalar a = appliedLateralImpulse1 * appliedLateralImpulse1 + appliedLateralImpulse2 * appliedLateralImpulse2; + btScalar b = eps + mu * appliedImpulse; + b = b * b; + replacePoint = (a) > (b); + } + + if (replacePoint) + { + btAssert(lifeTime >= 0); + void* cache = m_pointCache[insertIndex].m_userPersistentData; + + m_pointCache[insertIndex] = newPoint; + m_pointCache[insertIndex].m_userPersistentData = cache; + m_pointCache[insertIndex].m_appliedImpulse = appliedImpulse; + m_pointCache[insertIndex].m_appliedImpulseLateral1 = appliedLateralImpulse1; + m_pointCache[insertIndex].m_appliedImpulseLateral2 = appliedLateralImpulse2; + } m_pointCache[insertIndex].m_lifeTime = lifeTime; #else clearUserCache(m_pointCache[insertIndex]); m_pointCache[insertIndex] = newPoint; - + #endif } - bool validContactDistance(const btManifoldPoint& pt) const { return pt.m_distance1 <= getContactBreakingThreshold(); diff --git a/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h b/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h index 739b066fe..f3d4d45af 100644 --- a/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h +++ b/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h @@ -43,10 +43,13 @@ struct btContactSolverInfoData btScalar m_restitution; int m_numIterations; btScalar m_maxErrorReduction; - btScalar m_sor; - btScalar m_erp;//used as Baumgarte factor - btScalar m_erp2;//used in Split Impulse - btScalar m_globalCfm;//constraint force mixing + btScalar m_sor;//successive over-relaxation term + btScalar m_erp;//error reduction for non-contact constraints + btScalar m_erp2;//error reduction for contact constraints + btScalar m_globalCfm;//constraint force mixing for contacts and non-contacts + btScalar m_frictionERP;//error reduction for friction constraints + btScalar m_frictionCFM;//constraint force mixing for friction constraints + int m_splitImpulse; btScalar m_splitImpulsePenetrationThreshold; btScalar m_splitImpulseTurnErp; @@ -79,6 +82,8 @@ struct btContactSolverInfo : public btContactSolverInfoData m_erp = btScalar(0.2); m_erp2 = btScalar(0.2); m_globalCfm = btScalar(0.); + m_frictionERP = btScalar(0.2);//positional friction 'anchors' are disabled by default + m_frictionCFM = btScalar(0.); m_sor = btScalar(1.); m_splitImpulse = true; m_splitImpulsePenetrationThreshold = -.04f; diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp index 982650da2..7a0ed924d 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp @@ -534,7 +534,7 @@ void btSequentialImpulseConstraintSolver::applyAnisotropicFriction(btCollisionOb -void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity, btScalar cfmSlip) +void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip) { @@ -612,7 +612,17 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr btScalar velocityError = desiredVelocity - rel_vel; btScalar velocityImpulse = velocityError * solverConstraint.m_jacDiagABInv; - solverConstraint.m_rhs = velocityImpulse; + + btScalar penetrationImpulse = btScalar(0); + + if (cp.m_contactPointFlags & BT_CONTACT_FLAG_FRICTION_ANCHOR) + { + btScalar distance = (cp.getPositionWorldOnA() - cp.getPositionWorldOnB()).dot(normalAxis); + btScalar positionalError = -distance * infoGlobal.m_frictionERP/infoGlobal.m_timeStep; + penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv; + } + + solverConstraint.m_rhs = penetrationImpulse + velocityImpulse; solverConstraint.m_rhsPenetration = 0.f; solverConstraint.m_cfm = cfmSlip; solverConstraint.m_lowerLimit = -solverConstraint.m_friction; @@ -621,12 +631,12 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr } } -btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity, btScalar cfmSlip) +btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip) { btSolverConstraint& solverConstraint = m_tmpSolverContactFrictionConstraintPool.expandNonInitializing(); solverConstraint.m_frictionIndex = frictionIndex; setupFrictionConstraint(solverConstraint, normalAxis, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, - colObj0, colObj1, relaxation, desiredVelocity, cfmSlip); + colObj0, colObj1, relaxation, infoGlobal, desiredVelocity, cfmSlip); return solverConstraint; } @@ -1168,6 +1178,7 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m ///In that case, you can set the target relative motion in each friction direction (cp.m_contactMotion1 and cp.m_contactMotion2) ///this will give a conveyor belt effect /// + if (!(infoGlobal.m_solverMode & SOLVER_ENABLE_FRICTION_DIRECTION_CACHING) || !(cp.m_contactPointFlags&BT_CONTACT_FLAG_LATERAL_FRICTION_INITIALIZED)) { cp.m_lateralFrictionDir1 = vel - cp.m_normalWorldOnB * rel_vel; @@ -1177,7 +1188,7 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m cp.m_lateralFrictionDir1 *= 1.f/btSqrt(lat_rel_vel); applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION); applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION); - addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); + addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation,infoGlobal); if((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS)) { @@ -1185,7 +1196,7 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m cp.m_lateralFrictionDir2.normalize();//?? applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION); applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION); - addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); + addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal); } } else @@ -1194,13 +1205,13 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION); applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION); - addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); + addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal); if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS)) { applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION); applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION); - addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); + addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal); } @@ -1212,10 +1223,10 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m } else { - addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation,cp.m_contactMotion1, cp.m_frictionCFM); + addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal, cp.m_contactMotion1, cp.m_frictionCFM); if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS)) - addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, cp.m_contactMotion2, cp.m_frictionCFM); + addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal, cp.m_contactMotion2, cp.m_frictionCFM); } setFrictionConstraintImpulse( solverConstraint, solverBodyIdA, solverBodyIdB, cp, infoGlobal); @@ -1526,7 +1537,8 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol sum += iMJaB.dot(solverConstraint.m_relpos2CrossNormal); btScalar fsum = btFabs(sum); btAssert(fsum > SIMD_EPSILON); - solverConstraint.m_jacDiagABInv = fsum>SIMD_EPSILON?btScalar(1.)/sum : 0.f; + btScalar sorRelaxation = 1.f;//todo: get from globalInfo? + solverConstraint.m_jacDiagABInv = fsum>SIMD_EPSILON?sorRelaxation/sum : 0.f; } diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h index 0dd31d142..b81537138 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h @@ -62,6 +62,7 @@ protected: void setupFrictionConstraint( btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB, btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2, btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, + const btContactSolverInfo& infoGlobal, btScalar desiredVelocity=0., btScalar cfmSlip=0.); void setupTorsionalFrictionConstraint( btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB, @@ -69,7 +70,7 @@ protected: btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0., btScalar cfmSlip=0.); - btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0., btScalar cfmSlip=0.); + btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity=0., btScalar cfmSlip=0.); btSolverConstraint& addTorsionalFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,btScalar torsionalFriction, const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0, btScalar cfmSlip=0.f); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp index e28809fd4..e6bbfb5d7 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp @@ -50,7 +50,7 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl //solve featherstone normal contact for (int j0=0;j00) + if (distance>0 && !isFriction) { positionalError = 0; - velocityError -= penetration / infoGlobal.m_timeStep; + velocityError -= distance / infoGlobal.m_timeStep; } else { - positionalError = -penetration * erp/infoGlobal.m_timeStep; + if (cp.m_contactPointFlags & BT_CONTACT_FLAG_FRICTION_ANCHOR) + { + positionalError = -distance * erp/infoGlobal.m_timeStep; + } } btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv; @@ -560,7 +578,7 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol } else { - solverConstraint.m_rhs = velocityImpulse; + solverConstraint.m_rhs = penetrationImpulse+velocityImpulse; solverConstraint.m_rhsPenetration = 0.f; solverConstraint.m_lowerLimit = -solverConstraint.m_friction; solverConstraint.m_upperLimit = solverConstraint.m_friction; @@ -1028,12 +1046,18 @@ void btMultiBodyConstraintSolver::convertMultiBodyContact(btPersistentManifold* applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION); addMultiBodyFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal); - if (rollingFriction > 0) + if (rollingFriction > 0 ) { - addMultiBodyTorsionalFrictionConstraint(cp.m_normalWorldOnB,manifold,frictionIndex,cp,cp.m_combinedSpinningFriction, colObj0,colObj1, relaxation,infoGlobal); - addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal); - addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir2,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal); - + if (cp.m_combinedSpinningFriction>0) + { + addMultiBodyTorsionalFrictionConstraint(cp.m_normalWorldOnB,manifold,frictionIndex,cp,cp.m_combinedSpinningFriction, colObj0,colObj1, relaxation,infoGlobal); + } + if (cp.m_combinedRollingFriction>0) + { + + addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal); + addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir2,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal); + } rollingFriction--; } diff --git a/test/RobotClientAPI/SlopeFrictionMain.cpp b/test/RobotClientAPI/SlopeFrictionMain.cpp new file mode 100644 index 000000000..f0d802667 --- /dev/null +++ b/test/RobotClientAPI/SlopeFrictionMain.cpp @@ -0,0 +1,111 @@ +//todo: turn this into a gtest, comparing maximal and reduced coordinates contact behavior etc + +#include "b3RobotSimulatorClientAPI.h" +#include "../Utils/b3Clock.h" + +#include +#include +#include +#define ASSERT_EQ(a,b) assert((a)==(b)); +#include "MinitaurSetup.h" +#define NUM_SIM 1 +int main(int argc, char* argv[]) +{ + b3RobotSimulatorClientAPI* sims[2]; + b3Scalar fixedTimeStep = 1./240.; + for (int i=0;iconnect(eCONNECT_GUI);//eCONNECT_GUI);//DIRECT); + //Can also use eCONNECT_DIRECT,eCONNECT_SHARED_MEMORY,eCONNECT_UDP,eCONNECT_TCP, for example: + //sim->connect(eCONNECT_UDP, "localhost", 1234); + sim->configureDebugVisualizer( COV_ENABLE_GUI, 0); + // sim->configureDebugVisualizer( COV_ENABLE_SHADOWS, 0);//COV_ENABLE_WIREFRAME + //sim->setTimeOut(3); + //syncBodies is only needed when connecting to an existing physics server that has already some bodies + sim->syncBodies(); + + + sim->setTimeStep(fixedTimeStep); + + b3Quaternion q = sim->getQuaternionFromEuler(b3MakeVector3(0.1,0.2,0.3)); + b3Vector3 rpy; + rpy = sim->getEulerFromQuaternion(q); + + sim->setGravity(b3MakeVector3(0,0,-9.8)); + + //int blockId = sim->loadURDF("cube.urdf"); + //b3BodyInfo bodyInfo; + //sim->getBodyInfo(blockId,&bodyInfo); + + b3Quaternion orn; + orn.setEulerZYX(0,B3_PI*0.23,0); + + b3RobotSimulatorLoadUrdfFileArgs args; + args.m_startPosition.setValue(0,0,0); + args.m_startOrientation = orn; + args.m_useMultiBody = i==0? false : true;//true : false;//false : true; + + sim->loadURDF("plane.urdf",args); + + args.m_startPosition.setValue(0,0,0.66); + args.m_startOrientation.setEulerZYX(0,B3_PI*0.23,0); + sim->loadURDF("cube_soft.urdf",args); + + + double distance = 1.5; + double yaw = 50; + sim->resetDebugVisualizerCamera(distance,yaw,20,b3MakeVector3(0,0,0.1)); + sim->setRealTimeSimulation(false); + + } + int enableSim = 1; + while (sims[0]->canSubmitCommand()) + { + #if 0 + b3KeyboardEventsData keyEvents; + sim->getKeyboardEvents(&keyEvents); + if (keyEvents.m_numKeyboardEvents) + { + + //printf("num key events = %d]\n", keyEvents.m_numKeyboardEvents); + //m_keyState is a flag combination of eButtonIsDown,eButtonTriggered, eButtonReleased + for (int i=0;isetGravity(b3MakeVector3(0,0,-10)); + //printf("."); + if (enableSim) + { + sims[i]->stepSimulation(); + } + } + b3Clock::usleep(1000.*1000.*fixedTimeStep); + } + + printf("sim->disconnect\n"); + + for (int i=0;idisconnect(); + printf("delete sim\n"); + delete sims[i]; + + } + + + printf("exit\n"); + +} + + From 0c874aa43a62dfc8d38e9e52d1d9435a508b5535 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 20 Mar 2017 19:38:59 -0700 Subject: [PATCH 61/66] fix issue introduced in previous commit, related to btMultiBodyConstraintSolver friction/penetration handling --- .../Featherstone/btMultiBodyConstraintSolver.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp index e6bbfb5d7..77a4901e5 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp @@ -442,7 +442,10 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol distance = cp.getDistance()+infoGlobal.m_linearSlop; } else { - distance = (cp.getPositionWorldOnA() - cp.getPositionWorldOnB()).dot(contactNormal); + if (cp.m_contactPointFlags & BT_CONTACT_FLAG_FRICTION_ANCHOR) + { + distance = (cp.getPositionWorldOnA() - cp.getPositionWorldOnB()).dot(contactNormal); + } } @@ -541,17 +544,14 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol btScalar positionalError = 0.f; btScalar velocityError = restitution - rel_vel;// * damping; //note for friction restitution is always set to 0 (check above) so it is acutally velocityError = -rel_vel for friction - if (distance>0 && !isFriction) + if (distance>0) { positionalError = 0; velocityError -= distance / infoGlobal.m_timeStep; } else { - if (cp.m_contactPointFlags & BT_CONTACT_FLAG_FRICTION_ANCHOR) - { - positionalError = -distance * erp/infoGlobal.m_timeStep; - } + positionalError = -distance * erp/infoGlobal.m_timeStep; } btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv; From 61b28621eaf73dbc861951769cb3228969e5ef73 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 21 Mar 2017 09:24:00 -0700 Subject: [PATCH 62/66] minor fix in friction anchors for btMultiBody --- .../btMultiBodyConstraintSolver.cpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp index 77a4901e5..dac631c08 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp @@ -543,15 +543,20 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol btScalar positionalError = 0.f; btScalar velocityError = restitution - rel_vel;// * damping; //note for friction restitution is always set to 0 (check above) so it is acutally velocityError = -rel_vel for friction - - if (distance>0) - { - positionalError = 0; - velocityError -= distance / infoGlobal.m_timeStep; - - } else + if (isFriction) { positionalError = -distance * erp/infoGlobal.m_timeStep; + } else + { + if (distance>0) + { + positionalError = 0; + velocityError -= distance / infoGlobal.m_timeStep; + + } else + { + positionalError = -distance * erp/infoGlobal.m_timeStep; + } } btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv; From 269909891a9bc57ddb383d4a94e0c2c4f8d193ef Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Tue, 21 Mar 2017 14:25:35 -0700 Subject: [PATCH 63/66] update pybullet quickstart guide to latest from https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit# --- docs/pybullet_quickstartguide.pdf | Bin 494544 -> 521178 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index 7151792ec2641551074153d9735d34af09352188..53eef4638aa4a3834434dfd96e668da571cbc88f 100644 GIT binary patch delta 196146 zcmZs>1yCGa6E=#wJBuyu?(Ul4AtAWCyDu6bIE%Y$aCdhS2#^55-QE2{@_zTPD_d00 zoS8n|Pd_b8&F*9}>7N}kOllP=8D@4CZY1iio4jWvKAt#CB2I1&c6MGqAgdfu8_37U z3FKtw0O|r+m4W$oZ=C0m#k4#>pS2?*+*l_s0{&1LR_RQlDZ6dVF-9yPDJqWr<$4By9ADs>L{Q~8@OFacO@V4o0x1ynKPEDB8q z$)8-44++Fn2XeCU16kjj+L^mp06920z_HLcAQm$NGlSKPL0~@wtN{-vG;-|7xqmdveI-A-^;1kA_FCZ1xIrUeNIg1N`8*^-IzSD~#SATSSYX^_CarKHIR zdXOC8YS;h_E*5Se&npe=9Itf;{1xmjKrsrX<(^hxxCnBp8N-0USpw31($t{&(bIfa2r_|HP66r*M*^y=~@Z|7(MTj}NR$ zED5$`2VlIGI*^m|wFUTjU!8Drfeo?5!KV0(kpJA=A_BnvNH~yuf9=?z0>DJ5SdiR* zS3C=D|>fLsbZ$Oi!1^WnU*^UoYDxC$Xf!(#R~3?0>zrbNs{d5tHFR{~!UvS2VC-HUZ?VjGapo+(HV#;^5^0^8HH|-y4PeTz~1;AZL2D_m&7jp;s*b%MLpS z_$P%p_!g1*KgP8n3B&>p=rP>sHETpcBWScZ|=*e>Hjl6$j9=ZYWZtoIPkFl z*2fq;3%C|f3hV)71jpfMy(S43tc{EMH)$R~Ks-6t-(0cs{PWGgi~7pSTb=}k{uKv1 z+bhT1Z#Dg2a4OsY@EkYJe`-f?05o0>AU7|^TV1nr@~|X}_rbA%F*v3F8cs)N{!f#Y zhYZ}xgYw@B2b&R`$0Y{lIT|*stnuVe;|=z#aTJ|3}pa z0|17^#QtA>ETO(J{)W4Sl;J;K713D!yXL}02!7yttH8HzI1ym{TbC_F^nX3QdHqI+ z_7|=SH{*W*8<7EEePmb+Ue33`UaR77_wjLqa~X8OHjMvhlO}kjjo{z;FC^ywimnlv z>D9=aD++pMNY1~o-jg!?O{x$A)89(B0Wke_9*)QGw`sKDng8ZVn&4l-w!DsnO5!)m z;$U71GIZWI6kNPqZzy=U|Fr=;@QvFZ`nTRE1V@r!|F!rL698Vq{9n7hwd^+(tpA8O z5%`y8A3@Z=6xaX&U=yN$_;Z*T{~~-(N(g==LH&C^L(B3yUEXMQ;bQ)ez9&Mazf>JF z1Hj45*#D6YqI|pmra3_VcJ`JueHJn_{=c|iJLnBQ+uzXR=~@0G1w{GUi{!7pNQv^_ z<_aMIm`xZC_3yO$H}UxY0U&stL`#_P;1WdCzjHE$695Ks!T+0U|1|$M*Kn`_;0$c6 zzx7oi1Vnl>#>vkE{Lj(^6(Ja%78a~UjsAb?$%~iaf77LmmF2GoJ5-kc(%6ai7E&C( z6!;j94B>AqufCE+`{3CA&hAdMzqJB>hyK>BZ;3adeH+VfbP%!qn*~x}0~Ug}{zm2G z`%B8(2>g!`9tr?>g&Y=x>u;9-oAm$7@;i<<18;nuP_q0Vz{nVH=-xbl1m4Q+-y|bL zdYfVFyzKv*VW#+RgBcc`^KD-KSH&FM|Au=RD*&v{it{(vP#VB1DLDT%1}Q2h$Ey{d zx2&;qaV0xCLb5>dvnQ*HL(xI8u_u!ULsCPtvvDM!Izr+C*x5M$Jrl^VzdjJ~{CECp zfGwH522%ZPW9}dv9f+Ne=l}7na-_Rpx7m#8d-Lhi+26twmmY{<;63z^(Jdwd9I?X~ zhnxHU0@8CmCWr9e_*-nhtBO}W8>5V>_pEsZ1l(qBy z>J3Qb@d!QiB{JKsC%aSdNzhM&ELs%wwCC^)+Pcvv^}CfP@w+=I4J~;H`q(Mzc6QNA zt7M6Nmi*=U^5{Mpnc9+*SZ~O)Yy+hC;&=;I zTYkPfy+45$cA?=rdfMu_xD(&~7XC+vlrKh0>a@EfgEY9346e!uNSagW!zWD8y4G90U`u%n8DAp( zVzMT}5n(yqnxgr~yu|~#9;s00&uMFW(EWjHy4`LAz-e&WQZj>w<@VWYyAgR5g0Pm0x}o?Vfjoi3?Ts+5G7Tm z#NrpY&;x&6>NC!|lUU5j)!5*ad@zAV=24#r5Qi55orWu|ERU1EVxr-6F{(U>7}I~IL59iz=KIO1nw)~1ZQ#MO@>>*o6nazQ`< zF57-(d>IF)j1=?zrI>exMhQ-d*GDuKjPIk?Yi@sH$$O?<-bdvhTn@`6#!|Ib3uMae zOH35YLtgxhx;CfY*spK~AA-0$XYHyF(3cyJTg$nwQolEb*@1C|Pr#{`)hisU(d_|y zUW5+5JbN9D5x>(!K6sss14+s8e%$8JfwVHaGi+XcHRMOCGiM?tTF6G`4Ii zsJ%MFJIW>OI4LrRJn9n($Bl)!?bw1k@_ccK+yI_hxupSTNImu9r(-qs8kTGH)rzBv zQA7n9yor=1qO2fXH!FiKGAQy8!>DiD-m*U)KsWi<*7mDSl0$lOIcj(yGS<7 zf=44}0w`>FRC2eU$Cm#5^(ZAw5S93{{CC6(R;ty(+iZ|h}oCArFVAcqT5~kQtp}ZWr&w0MB zn>NiCQ6PXmcnpA-uN{@;ij-t+%{ZxKdq9%2SzpxfuS1|QUhqp6r$ySne_0bibm-Fkt{m?oUQ1kTMV_rnRfN6zQ+SewFp4 zW^?`1oiCpLRhB#|R{)t3nXX4aOVB~tZKy`u^H1X3XSgx*eq(RCpjdr;Pq4%Imop6f z@iD62ot0wcfnb}j8@o(dulS8Q&Zg z59RXpe8w^Y2O*I;h94(MIS)Q%4T5)-N;$USn#D7Ey*R`j~ytdZ>n#3MFRp?bly{5BImFB#@^1h1&ta zQpckcKGe-$j37{BL&NZU5X(MZW$HIqSeC+j<8$jpD@&p2;J4+*Ta?$QJMQGvLwDxU z#C?g6aalfjMdx$b;3K7nR#Q=vPv$x6AI8<7tM{%eU-U#bvUgqO>w5tlRWvQGZr6Gc zx=Jwt%Q5Zj=by%H3Hsq)$ zV6oH3{_LE3O-pPGgH^k+<$`Yc4<3Aw@%cg{C;yU_+&SyUguN`|?IlN;K3UPMgpcr3 z(IDt(FKfBVe&z1|v?_#Grr<{M+xPbe>Nwwj;XAYD2ag_!aZ|MbWbPPC{>0}YA&oGf zdLDCM^+1ip9gN1TIxB=8ix;q_LnSUdnl|sk;hWB$WQ@{S;|L+0XZ<;V#MYpz zpPWxnFJ`vj*RG4?O2l{VxrJlvb*@g}u-%zyC9E1k)`WI4ptMZ$)k9FUd?p8o5sAUF z&jU-29(Rac|CBvJL~zc~yQSxVlokl(7H-3P+{_+l_5d5KAF}r@NTzBIja-1Yw_+L2AXQw8i`@ zu1EX$?WdN-D%sK;1bbpe;c2usxV;&zMY#m`?C>U}tljP&U(w+__DDa@Tij?;Y=-TT zK=QbH`6MoU^v|rSe}8YZ8`u5nrE1!ucTH%^qQ$!`$ykW}1q!=wlzjbX zL5|){V6|lENn}<3HQHj900`Aguqo6&Z2|KuP+uJDg$@UOh6vFA>1+3`8;=I^U7g}1 zP9+=P=Vu>5N^5;stNnWE0Kg;dx+o^Av=C@@9XXaMb3RQ>fgPP>D^tMMAnWJxw-k7O z-W)JK--trc9D1D;i+69cCQq2>ifHFpKrhu6$@)sQvTYywmMT)m)B_4BNJt;1iZ3{UoAZ>&ziSjc=jq3g;>e<4=|D za54HD25h(@>K%x_umJiEL1x1=B2A|WA@u1i_u^BiCVRKyIZYzXFryi3n{B;$mGba} zn1)rDqJ4VhG+npfKR_N_x4JRyTisnWv`$HVf$!!DablU=#7&q#VTLB(p)!kPtL7W- zqJ|{mN!TaGAl&V*jY;Eq5JOTjK|{|I1x7C$E)Bdx99>YP>~Yd@fUAJMoi$vnH?#`|Qp|@E%*OsRWcAi&@r5f+_h^vbO~M1>SE1yNM;M>1 zTI_DHl z*!tnrk%JZBX%)g-;e&q^c!uosy*Yf|R9 zg|In=wWx6F^WD0gBZup3Ac!2I9pDXgUv|J89Z1gVXE-9(LkvHD6n_?Y98F)O9v&9h zg_gP3N*zmDaFwbC0|*(#+xz8pU-Q(M!I?C{vL|jtC)o!QE%a(@{bMgnF zqol%AyX=&dkzmRdOEf9=!l#H2nBxh+@a1YS^+8kQpFnFMYD}-IC7WW0)Bf%RrU}?W z#+81*RmNZk#>0~*U8H#!9idQ6XSfpSWV${eQXolR2Vl6Raad=V&_F}~S9H2`L7Hcq$unT#m_9Crj@FoMK$FL5-L%ToP zr?V!o%+Ei&jd_0ICkz_~8Y6NbsKNH@!5HkUkGU0wFamdw_C*8BH=ymi5cRyf=j}nr zXF<6?ZrN_v$x=!J>>h&lu!cnu`&?C&EVzmxNOMw%-&+Kvj;xOgI(|e<+*Kp+!BfOD zq1nm(P0<`GSwUw{z-rv`J1&%-I>qujRlpX(9lf!&7+cT7Nax3=RKZHRq?uOz;`5`_ zo;Bxv;!c$z8+)!Y-pj^5|*; z0!L#ZXmC*7Yz!b(RaC{rw?;Ljs7A)yu2T`AX1%j_?u5H;vTr1NZ@w-4X0fhnxc*}v z4*>%~k%I&?4Dh>|9Q`TiRRI$wf`rjxbX!k<3<44R-un9Y^1UXiWb~)IDD@*H63`aK z-(z~W%`DREd?0%nn!pDW$m=;ioJ+Z^OBfd+d@Q{g-2-)SkmSzhOB%&0B-1H`zf^Ub6;!xbi;&AY?7WnsVFCCU{dB0jY0Kd2Zh#ZFVh zpwVJm=X}UNw~*uRklBJyyE|K$CU+R>Jtu%rxZ7Fv72JO3){DWkpkx+q?({axFNWI8 zfhDM?^zKNPUs%kVUFaug7nybZ?%uuMqP~5^MKa(E6YD`qRe=Fs^*X}lsHKE#ht|OE z2jAqxE5b46wGpG6t}n2qJVG=XFJ*?YfFy+aYw!(#joDxCM&!uy?t08@L=nz#@<{UV zDF_{j)_=3zQ+|!zfiOb8W)Hr}pE@zfc!XRGGln!mHKJQLbi@z}bhR$@As8HU{AM~A zia&i&^XO=a{B7`3;2Z0Pt;Xmbe9w2y6{KnO@Ss3(PyS&|xD>lVC!**VU^eHJ35XcP zkxncWvFCEwM*EvpN&sWe|J3Km>R#|ieq~~nBfE0GkD2kEm6T||TE8tF*^lfHAC_^} zAs3h*?;<|LuyOcH*{F-z!-!7(=JQKFZ57w$t=u?Ib9mm*cqY{;lKup>(?9D9cLupW ziR;{kH&)eavdd7feiKtQ@4qW2>JR!smkgnw?7?sg4{x=tsxwO(JS-!ojSADWDug^h zQjK;o9|naB4yZjy5DRNkPj(G=9_V%RJDixM-wOd4XZ93U`13zI}9fd=FxAUc3<< z&gs6GyM~EY9}h5Y{jmB+@&QRb4n%P+J>w|xfRTsrjVzSI7x9e2NHkj#`GYXBmRpzx?hRao~!q;d-xBd9x|osZ^={X)<&GZg*@a zCpx0_mqg2wVHYPKZr(3`VFuza8n2r=8&p{EE3FqvTNHyWM{uoeaU0`44rk}=3+x*q z+r|x;dSQ?bh``I2t15#6mk*J5ncLAj1_r_BDR&Znk3DZl@l`v>TnY%^U*Xc2_KfevEGJnKtsc#I@Lat0 zqAwN`rfrB*1j0dw4{FYWZ&4f;jbjRK3o-IU%|nW-904A1xyK850#m4k7BH|=pm@WO zHf!MMOn&C%WcX-`sI-FQuiDD1Uz$dgtBG%{1Bg-e)==(ch$BdQE+BgzWd9r>3AZZj zRQ@W&`;%8St5(UmctU|2Cop;JMtKeFMA#teZz_q|(0CZA3wSWU@)0A8(j=XlU7a7h z_k`d9>i*2jp53*)=f0=cFHfFT^J{c?smx-wDCUdVVm{b;j(Y&{9aFYsZODxqW}tN7lVsty@f9i;+4vv|LR#PdNiSksp>lJ@aMh!Dp4sDG zK+=QSd|W?fZY4RK?C5R9|E?wDwq?#K`s)ZA!{G#}#=`pTKEHt66*Ta>*aH!KU-in( zUCZc^%ACJj=y^ZrdAoLJmF1fGTW?Exux+l>Z!$0E?BOCqz}U~?i+cpaM6H#WC%9=% zKvA~jJ%J__VUc{5W7aCX)x3MIfF2FnmxdDeR2z07O1n_C&QCrh^}eUNoi`R2N{YBb zEYSO>O{a8i!Pa)&+?^FuLmzzC+Z%e``S?1?hGD|$kl6=;R)y9#R?)_cqZlIKG-P5* z1R`r!eHF6H&fvmiYo26M3V-(Gr{P>GcLk}-=;uW@kl6jAD_czU(tE)^+Mu1O38P7C_e@ZJTtwI zZ|vnLg}gcjv1P%AI6%a|+uPJ!_bw4`z z*!1n>41)M79gub&FqkCt)e7zqvyv8tD#>A7Ss{P&z;KJgvlG=Y!8D8$=k*8qj;oEy z_6oX0h^cmYK0#g!{aH3vp|XJ^AqqL`i(yMP>y^j_@$N5u7UG22>=UwvE$#hGhsRR3 zGa;c0?`b7Sl(kWu8=OcEf{rwJeK&$&^e5T_<_hz!Ux0uKZHVsx?T{8FEka0(E-uMP zfb$m0zBt;E-D1Ol6R5q_2DPuF-M#ZTgX`=EW9lus51q|gRF%P+eX!;EW#`uYLVb4R zL0Y5%^qrlw6#i@(<1)k|hgBC%8}rvCa%3No0ng{4o>916B_(p6;4_L#l|45p{oNmC zVCgU{7~{G%#Da>r=P{Q)UoB#b_7c zPl<=`cia7;&Zx)d5+SPd|6`0{b&C;w(wh}Sh|QdgR!Ufn zp~{hWW+|iMjO<-#%~>no9r;BeHp(E$pEkwjqqoEeq2QCEw#DWl;TtoD97A;8wdgp$ z|AEZ>FrBwEdyJlq?+v|>*`MMG!Bm>K>%Gl}LoZ+^8t_|<9fwtXR zxw?D7nsi&1ZjbUfc)8YG9CIKu-1b|?j^uqLC>M!xAHOl+7rUVFAAEvPl$=Cgt7zSm zW+DpPGbwnHnyay4QWJ^-sE(zn5J6{Ch=_ft(`=?C{v^P*!rZ^mPQRGV+COo}0y3)1=Y@Jx(HCT|Bi(${mlwuA zPRY0UfF$TapA#n?$D6wt_YAzR51>19f*s7R>VY1!NP1K5=t0eoQ7xX21VvWuzM4_A z^0%3J3Z94K8=pu8FK%)7;0i7Vg7~sW9FV(qEnS&(fByE_z zGlaie&68g93sU}$sEQE%xjMUQR}P2cj8Q zzMZypl5N9Y3_mt;Cvs0}%Y1-y4`>6om3s$zM?VnWnB5?g{>0v^@x&4y$>Pa^%n}re z@yL2t5U!R-|1*ssbN9UqbrFc#jOtpBIE`=WU58oK5WL9#^uu^3UG@_G&b#x5^Q~JX zANRX5p9`M|pD`cwyR6HO)$+5W>!YiVHSY=c$(xpwhs{6}>K11w>GRV~)e-kBJmm%D z6^H07>jgQYrKpxD*r-fE1fY%Q+LFmS<5zS2S=^w(boF-cwm!6CPZ7uQ{gV#YP@Kdpd+BbvXDuZw8)pRI8E2W{7JsDYlml|Y%IPmXOlP_ z(QrhADq4kl=b1O2v4siLqS0x!k~9|YjZf{4L+##YIuiAs)IF^vo^nT%QhcP4*G+7M zK1vtR#*1c^G2dL^C~d4hP4Ycc#YscQN!%~ni;6&crSKtmeAV$@L@OAP`&^tOb5Wj# zTf^9oX?9*r1}GehCpWO^%Z6RlqssANk=x6nQx|8Dm22odfS^mjL; zYDa}%mGnRdEr+77!V|!f^@#Jqu=ZHo!hidsyk>k0<9dbi2oqsQ92p|GW;e5Zrhi!QKW5NoG-}51XA6duG{? zYmXprN}prhGl|YCS;;Z$1oxRBepYac%{0OHOr61mW{>x(O-~6+)eOT`>gJ`2mx>cM zVGXC@sf|3Otcv|44?VA}N6Frgw$QCi+%K<3YagqLCA%&U36f=B8ddCj<9YL-_d4ibj7a>dpZR?inGLvj!?&o1LUzSX&|SNCfIX=)fiM{q#0CG ztxA&i<*WhXS2JQ!Gg9AYBr3S#W#V|a(*DSSXh!nbXOu{0uO_9Y zl1$WDEoH$aF*MUSX$sR80^f5Yc8z{AY3;K1KJ`NP`WWU`YihE5!y&~Y#r%yNvoUh_ z?X8e-6uC*!A-Q zbm{ID@GQpV?;;f&U@j7sGUo_#+Z&?JyTR0QSYdZAIk>zwM}yiha_(P9b?PJCw1s^p@%@h zei0+GI_0_ILpH%)kv{c(=WAHO!RR_x(EO)EYqvn(zE0DX8t@^`L)KHbQXS`^>^1g7 zYNqLnL07f&VfNvtYa+o3KiZWz@FCPgkgf@+_T4wkMoCm%2`2;E!@$`yw-3mItEef+ z4|m>-xiOQ`Zz6%wVB`UDVNU@{A6&;-=M8k5#`-6@bhII$q?J!SbBsNEy% zeW-vF8UMTI9-3PDLqDF+bl7mnO^8j%TQ;QWqeXRhHURBzv+58VOzrWc>OvdBwou{m zq&i$1>a5}NUz~UBjgZD^v~0DXhkn<6wxKLHQ(l*Us-M&w#`VL#EuO*>8-pK!p>)cb zZ6^7KlR`HFs9=$>XG#Teq-P zKk@w_79=?oNF<2MAf4Ifa`gMDh*a2~rL*wUi3qjt!xb5u!(>IFX^?$e$73`(uB74I zDJG?C6e*|MVy63&u%E+V)+}t4lY_FROh)p{w~ZqIZ|4aTC#g&jU3Z`hHheS951xhaSRi z?WBTwF(g$((X+-w2Q?d4bD*;>d_jh7o_I6#hO3M$7fWt;*p6%=pMOzmP9$oppmY z5SaT3=fmxi=FHPRkDq(UpK)K;cd**gtwn`cR;4<2^5e%)bQVjaOW#2U*PzK?2bGjT z4@pK|o}cVf7eF5sZ`7vCXX+uRNzpl)+vbN{Tp#2^+S0oo>e=75YPbv>H_Gm|dbCB( zG}yr|xMHS6b|;7qYPV$eyHHpK4!X1%3c^M~(r&qXwYgmgw(H)ZJO)-ROkzIAcNQ+S z4tfchR%qYJC$B9V`kjK@uG2YYXeOme23cLt#`f8cYkat?XF57G`r=Jp%?Lim<&v$D zuwP!Qb+Oe)#u$!tJGR{$n`PC%Bo6$j&{e?K`%J{hv}Z49Oc&d4ZJv7T#cMjvDSMd;Nk_rTO3Njyws|b9 zL$`eTj7g%(_mS;7#YHpQLK=%FwI+z!aZR)g!7IXxQJnNw>uCa~L&Ip*CLZuMU-V63 zS{^AKWC!mXbQzLBDfX*d87r*!Y*ISsg00s`C-d1=EQA1-IG^p60NR!;osZn#?ByRg zIUe`+bfh;~nv3~{l&m^^4?a%sTU0hp9m)i*2Vo@~P1X`|s6LXSudEijBBAs}c9q#% z(w%%Utl`cvF-y3!gsrl)C=Dkawl34MVyXM&p$c{{N$#`&bNz!_bRtSkkq8rx+V(@0=oFga!`Rda(DfYFLTrVofF#jeq zOqoCPa&1UTVH)X*73^OIQ?5XANZe z^mxh9Y&6}AG0=a?wIL&N|E&BX+$(8S2k*(sr&kP66jZW89X$L(Q89^V{X}rZ3%s=` zw*m{ANUGMxB7H{qDv=pf%KsR;8$z9;6}V6j18OouwEK>gF@P1z_Cqg{JEBIhhz*+| zWUm^j26GyvEwWM^@ppN6!OWpo5BZ!b*0wO6U|``7t%|sbaXsUx59#yPSA&PWzOSz} zgL3%p=o{Ft4-vhCU0mratd43ja%*MEWq%F?Uqcbv`k-GUI!XjGgnMW}JyYOsBc{OM zW4!+VAzh!!&7SP@0qu#8JKyW2_+b>0eX*zxAT1kEO%S+eFQ)yvzDs{-gYbmKWAt@O z_|kP);tQ(weM;xr3YqoILIA>+0*9{m-a8jYzM8!V?hz#>-%1|-5z{|GPnh>i znQGW4wRn5G;DUsVA(>we3F_5T#a8DYwB=UUt-4n(xVnXN7dY8dTJuyUcePsPwpgG= z5qE3%EN^hz@cU2xVZD+;h40Q%;qAWu2~xo*-(3eJ?XX%6a-X@Xmh_r8q?L7>7p6h^ zq_NIssjG*$h+K-R92)Z&q2(btin96qkXnprMrVJ=oEn(&H6{8uAB&$M?oDV!D{PiX zy@?O}48MLBQ}D^cI(-1X3eblVV%%ZXfH#rrbb9v@C>t`W8c0k%{3aM=5uFl%Z=&RX zS3(1ck(}s;b4&gmfT4MBtG9y*xh&qBNE(d`A^tr4CK&#AWlaW+*Qq(Kui{Na5!-D# zl)nkeP>}W(8)YaV|M;-s$2TE^#_5!zfmYWls*ahl0ppY*7L7gZD6z#CKujC^wpQU+ z0uCW=@`)GQ{S z%Llv(t*w%exb6&r&W{s`=b(1(OFy-;p1#D7aa@T%0dDn&fGz_F29b!u^WLvkpkycSaKdiLa6ePDpTT$T>SK z5?|IGoe73+(rajJxSU%F%qJ;*ECN$7cZ9S3nr=1lXbgBfEM<1fbaZy9>O@tkVDTcL#2}$wfarcHgl$!3%b$*aXac{wo3p@ob z`XE%F&Dwp8kSQ&Ot1Z1>oZjqc0t9DyE@Eme*BOAfsZPEkJR`wH#rQTQkI%4;O60 z-D?EQ%761?m(nY7JQ6?GiDHD8_f%9MqH6k8;IqoW5gPznHOg=mOSv9$b^cQ|$c>PG zRpD4jK2jntzg;oy2qgPm6sN`)K7+rlfE2Y^;pi$AuemY0Q^6hE%bO)Psg;=(w)&xD z0P#spS%FZMLdRSey~R)FI$Nc>gfzSDfFM4oQ-DM6XUlb?9~2ROi`7?`cHu1ag}#}I zJ*8Qi6{A^@@f`lykyC|xgJXq-ZgJ207T?LhJ_dJXiwEmmnN(|;&gV+{iq}_yZFX*` zu2;^957q61u5H$=*)$1pYOSux&{!&{z80=&|VUV(jx) zUFoqv4x>daBW~*5hjlem-w=e@d5?zD+%wO@10RX$L7fzNoz< z-Ex38eflD z+K<)k?~~as+ut2xB#z?aNEST#dfWt{smhPyL9TEOB$Vw-*ZIeGx=n3MRzzgostw;& z$#j0gal?7G*(oc1)b?B|NNA!c)N2x`;cB2vMozDHD^)}obhVOY$wS+ocq|WRT`YLo zqB;6i19Sd~=u?T}2dj7KB_C|SXI+ngdH$f8#!P_+*Jp{`-UVB#yxuOCKLl-ERw)Y| zzM$)w)ATQ!Uk&?)90XhnKxOVGpI&V2Kiyn6R=p@*9kjPrG#$8kbS(H!9aS+>w*9Wx z_~UkgcBJ)DTT?~L<(FmzYmA20DQ_n3=?{fF%@Apjx^90t@|~u%&o>H@kGX0k(Z6h& zW*_3GjsUwlU+^^(e@`Kh>^n$*EB;pZU1uH?&gkMR8{_MCXa~2+AJ%=)zPvDRFLqk? zTe>2`1NRSM6~}p#%o@YPVRY8q(q@Z8B4Gsc@{dUht<|WnPe%`U55iCI$xa$)jFK;Y z6EqjB4S&#<2HgfgDcN~YT~#)S;FoLb(G_3COaWI8(EINxC@P1_C;EpI0}nTDp9gb6 z46R9qpVN~##8t)`ts9p115q_o1HeG_TL+;;aSoNhuW0tV92H4rrlVCz>Qo2z7XO&ciUcxSsK5D-zIig1`30qO+0Y}Cj~+zqT+!e?^+rbJ(A`$S`Lm;4jOC? zy%z?XDT>Rnz)a#}*V;c%2}!7kiOOG8HdIUpXYh(j4e=VB%0>g_9eMjp=TID(2w7Dy zgysXg=T_zQhUlL#mt1@h)~Wy=kRp_&{iqF_SpD77>pjAU@ zYR!7cI2?2?t>GLEbW+?<;B=t*s*DFl7EUGsKozvx2^b(`E*ssn2WOF(1sR)s=%O0g3)>WR8 zPvSfrpBc>TWet1&6r>-Z<5#^$`c=T&e|vRKT8Wds&zFKPoN2;M-H z*dNqe<)Y+(cIp4jcb-m_)hy4U@QC0#Iq%YVidf(CD`~@~xL4+MBl_@*a5cKAGm26- zJ(jf5$afQh&x(G9UIKxnIHcHa2-zIHS+btqJ)s6?`2l$BUB zCsKdn+y+!>C*|piTQ14(*`oboy9RUgCt3HDFWtp)utIbU^G*v^@%MvYf8jAc9{-u> zchZ$%&}R&H8tr!ZLsk)5J6wJ233=ElgiN6Oj5U(!in^oNe&~7N-2DSsKdyl*j73@x?ax2(qDq>N=j+Synr#4nd?sweKu=*yo z4rFD(DBlf=mej*^t_xMBEdJD%3%uV+5&SNuS3=f6>JWk+xugZ-C(5C^oGs+ryoA{E=g!O{= zmKm2BmlaGSEl%O>n$I7e71ia}%TQNK$?l2;dglmxVsFcR=q`!L^anU)WEoUV6Rok80?`^j z6R>u^6RyVX0R3cWO+F^iG=yi)3EG8&9HtjKSIX^Nfkp=lj+o3T{D>zSW{Q{H?k=98 zxum_w0p8-6O1<-nclPJ>f0##T-Vg;9DV?wJWgrUmpd5-^D!W$0xnIKGrU{`ZhY>sy zcBK0+ThMu>nwFeg1bBBi)z|S`#GqXQ-R0p8;a}$ILHx@5{bs%Vx7a_z+Enue@@b#Q z*^-2NI+3?wwev%A6MLL3+>KXh>QmH9s2|uSoSX6s4pX4G19XCJ!pm?t_Q| z(P7MCXuG|Ky~FD%lI6Iyq)41_x&?1LutaFz{Y10BpE!7Q*AKv)gb>9NJd3lb53O70 za!hQN1}&0zQuqNIq%9|chE(#qq-}q%A${qSJ*9jU=W6Cfvw-F2TS4QyQEQG!LVUa}{L6KP-t?;4tj zm{pAljMtINE#j;#70GGi5)#g#C8}2iT*kEHEr_&`G{A3LdeH}(ngn9C07G%4j&IrCsS6$s_<+;y|vuqG+<`6ah+V2sZOcDM_K`e#6M24Y5 zqJUZ;2G1ahrr3T!YuX`fG+$n;In1#8l5M_6J4GWdimp_BW%{^K1GpXtDj_7Em71QI`- zA5TtnhFt%D{y_h($`T~J%ru6r0R2%i-Bqw+HwCmxqymSbpmt60fUA>oM*c|N@*Ec7 z*>gQvhMg*tI+F`NojISJA#sfUEC$CkekP3=TJM90gj2N3&6Qv4a@aCMeKhAQg4-Xd z3kFH3G^>|~$GSL?$g3C?q83O7EAfU?jmgtE1b~QYV;6GCguiD6NG99}%=_RWd1nf* zyl1*I7@4q7$K4B$j;G?M=H;Dei{zUsM*BfD7sNsl4b7SSskOKtm1r2m>Zx)HZ-ztE z9i}T%fU}aXU9j-Jaag-PJ&M(O<);k8QgnB$*gz$B0qwk0)?CB( z`=9=8(6QF~VV{M6{%4vu{rx(WJ|B2RG*B;IFtZp7sV_Y?(V!<}7a1$T>YM7PPy8 zB%D@5WkmtX7Qf}Ub$>CZxEMgLT)9EKkKqiX)iWJddSEg4J#0I)eIS1zA0jU*`oVsgS`0FHre+LQgIUB+9a%w z@Rx+d*}{n#b>S7kry@C3?-?^nUx!hpG40avPen^jL&cw{86R7dP|PMR#K#0k1= zO@o?k?00REPS2^r{qRIqOm{wL+%$=FGR`8?DHqaFu%*x4Ck{J;&mRS3 zu=$RFX-y(s9_m$Y0m!`bVFVUFDHbudtnIF=B$Pu-MDF)XWcmO-!Ed`h@*FGSdKTz4 z&DfTwaq%sSjY8XE^$zxnQ+%!RAP>Do;)Zu~%*S8vd!Gv>jUy;XGa(7W!|VSqy3Q%M zv!HAD6Wf?LnbYl^UOn_)plDSXmV6_RCASE7)Ce@Q(sa=L>7 zrZOq0oiCxTOa6))pTS;3pp$Hj3bo@TD)Q0q;(;=Fbb5+%)`dOjRYeRxw$3iU2 zanHPNzHIBca-AeBTMT_4Cyece290~~9h4K(p3e=1O#v&H?QM>Vm~ir40}&}iG-X9p zML4L^dx+5x5jQ&~;SyEzG%Us;Xo21#!5|T8#fmoHg}MNF&)yl~BuD3bB>WISIOv$R zZ<)c)ZL?=&+D5NGEF-NyWWroCt=2x|lB2}Xl*KfK_P%<|&nVEVUlO4Yp0xLm*?hXI z)C+J4up>VRymp-<1Rw>A;P#)sLym51%$K+(2qSvt=$~*i8kd^qm{*w8HEZ9sJIR`M zI3=4ImxTON=cUMvi!aWYim!Ozv=U8qU4=#qM`ln2>3DHcVI3*?JITRz) zERy2C>181hK5Xn@e|Q3%KZ2+b?#CHF1E8F|nRaW&Vc&#ZHnZw3X_#QjR_}`~Vl1oTtT4!G0Oa z8Q*-fA5$OGYhV#pGhZ6i7Mk_CpGQ2XKK=*8^6z=Z3rMkyc(y3tSn8@1Yx2abNg+*z z(>ot^?rDmvfaiitbSh%If9xEvF1Lq zJS>4=*LCeRg=xY-GTekzT53nHCbjrlMruX8ZYX+mQrr$u!s-M)+FZ0$_iBb>{)Hd< zXL0ok`miLXtKs$gwy|W8b9clPiVsxXG4vv}jq^tdS-ugdc~stS_M7I8vgjmQ@vxjh zySBL%nyn9h#SecBs*)Dj9%f?lmAOh;sCu%Te}T&fL_XtA3w@;fW2?d`s(F|>m<6kM z%)Z&rr1=2J6)6T-uW!t|WxMuK%x>guMEl#y;_1m*WCgpT8tU{7elhvm5H6C5=!)=* zJ7h?+GfnxYtPg}FiuCiKASc&+W*LG!+zLL16#Jy(zBiH{|1g8X;8Rn@~#j6ZZ85Sk>)`@W^=PcC>gj#p-npH5YeB_LCSDV|~8xHSACK3A`2OvoGD z7oY@mZ{NT^%k#$ul62yE7LPYknkN_3a@IwBhrRMTzc!qO=0v0&Y&aP zK4wGH=Db_BhHWLvdfr0v)1|KuFDO3*8bG~56#}F3Exp&t)+1-O@#7e{Jn^8 zGN-~ZT=)E6&H(p!T#rmt2ge)^RvyQY7Jt83bG&-)1rJVdA#M2LB5%)qq!a2p_%a2> zB)#j_49x;7%LpS60tCc*`|9$_j$P{Tl-NDoj_3_P?_NCapIb=K5gdw$csSs-u}h+~ooFTX`?qC&_h8i?SvoMcsHTM~ZS zI^8yd+AsSf)r>yy?_0b+hW_~&qE?J?pcBM<&m0Z3?EY2lL2Zj+9+G+4bQmy70S2#AdkP*(b3$OdJT%QjdF8JE_ zDfv9*Jhsk=x?cTO`U5aaWfrCuW>uvYWf8M6Y0wQw)hy!J*p^Z(WS+{&Pv3_%MLv?G}0B7W3L4bgllxc`bab?s?QUIo%8Xm?sJrh@N2hyjq zGKyc9e!u2E-bRWD-}Og2#DtE zLb3JA$?<;~!Z~fU!Fuj(XgF<9EqY42IuSAXw5-H$_Y}hY7@=V`mYPz%I^5tm>#YhH z{BAP!XQO%2j2ajvZ0-Y>D~3T^VCAEd+&?{eC{d${iWmV?Mw9KQy$Pmn?T4>X;isyl zjoq4rnpWCz0pEtXUq@Phez7O+B?!7Hw;SuF`ejgqiG8i)woC5%ySXFDj9h))uY_;X zL|}FPj2i^YD(YlSZrpI{n)@9pBu2Sx&e}CsBX7a#bQlb8}4mVEBuouPNe7EdRq%CpaduK{?y}qakZI?O5 z><@)#f)ntP6C}B&t}pXI;>g*7i*EUT7t)=zPTiJ38)Hf%-WE|2Uz(c5!R(cJPrx_9 z80KjXqX^6&K8(#c_fQ)3Qf(BclhUIuBAhjVP8(s{enAA@*=pR6J?Q` z7<;99&r9{pH7tgSlrVbggtLod*3t(d5x*9T9L7{*!@Ko}Hc(22;hBhF>K0?-m$0u_ z4&rFTYX038Ad>c#3=7>BTB*&A*4_C2*JAHB$9O4;NJ%m4hG#?xvi`J|EtY`6M<&6A!-%Pfs<5i4 zDj?$P-b5kY5xPf%ZpXQLAM!ENRK#7c37IduPX}^)VAG#*&~KCeWrxQkBO4zOU-f5+ z-CXPXOrBpu^V;Ey^IC6fP15n<)Ur)L1ZQ7_%pi^{x1;v8Jq?(jI(zK0lMY(^%xw7oWLY8yTy4S@(OX0 z=tX=&_o^|garqax`nTzLV|TZVYr2hOoU;11C1&OP8eACW*-pQ8x80i&wBi_8C@4lK zgGgrfxm|T>-0qVyM*PrqZD^8HM&d-zq<{f(-_iw2sx|_edQV;6nvepkgIQM#pn&cK z>m>0+{bb=Jj_>0Kue?Wr+F7{t)vUz{6p_|K;e`K3ZM+Rng#u@uVo>j$1>5*UK;173 zQH|ig(R|I}$6L>Bq*)9S5;=uZ3>F+(*UWbZAr2xl@7;6C{kG$mDHN`#M0{dEc)&wd zIbM~k*TLp@6IB-yoT$rVFTr#hJP^lIZlQP(3?r?}oxFg2)94=Q;K|F|g7p>So^pl4 ztW+ybw0yG7x&66)9EW)Y#VC$h1nUu=i#%6qA)ZBw(2V$cUdIp%gMX|$5Njgbp8qfW z_CRR@?5XYX@AVB9Md!}gO-te;ddCZ{qMF=^r{zhBtGQuDM}Rkl(y^AhvRg*+mn(t= z;Sw$s)zB=&8Cd^DmX_1eI-#(4NJ{n=n9)3S*-iW#Io82XP*i$(RwbG^l>36PW}1LM zV}T~i%?Ra&qO?$Fx6@_?$mL5~igxHn9x(Y0UAy!uhL-8C8L-&=u-gtNi-%rkDcxS) zaf0&mCck(VUf(#{XqocIUNY)g>~6|;v`H=U3Yz9CslS_OIuZ9**^2U*GEjcgMeA}l z=_p|I*F4p&z=4jR!I6_#W0Qy=Q!SEu!YR!6uN2x{NIrqagP}|UyoQb?wIzK93uEj# z1pI~H@j#oW2Y=am68lP6XLrU=(wCRogq*sP<>meycL?41UvY(Rc@`k*wSJ>v8A*2- zzQI0=K+?l#^BlsJ@V3A)r)1=$mtN0bv-Mcpg5BwYZOxkEAifV<9BTEGAmJEX>Q0`vJ$(T9S6WXBNj`U)(0| znW#=40h0>Aju$!YM&;lv&);u}*~#;*|DC|#u(<7sA;a%oq4#t7+b4~yM%89J70src z9rhTyY<;39P5a&p=liW;mM5i?tLdbc6-0gWNf{#vcT*o3v%14~C(Wc%aEM%AiL6uDL< zqKHypvUIQ#S|gSS!9HA`Lyuo`LgG|@|7*Y_O6+{taN^TMrE}bT`5UP7{^qDIZ}(>M zSi$6HZ3*|6C8{2#1`<@HO^Q5404!^HLF`+=Fu#y>r;T99&w7#wk-d#^s+_tyb9nWjm{jOUB3HWZXXCLco!SuO*C$hsS&5M&7oFC zgR_h0uv%3UO_l9ZR@C!GpU3Dhu0J@=@NtvD%Cw%tayc2SMiXm|9_swG2s*98^i$ z&4?s04CaMEp<6S1@OgP|!FAvtfTg|~D}DrrM28VCyu|BY1^CyDl&Ki{nrj>LdUSX2#R$%Ka-mILkoSL(!_(3zYe{u zJNdP_A^O@*G!|jH5+r2&NoJ25fI52h`#)K&CVk}%$HvzTvGziOqnU#6qUO6bAPr!tWmY1*Gs@$mj zSmR{ug_}_JMDzDh=>C71%!Y1Im%ZJ?>mW{#`?g7d;zJN2B#KRF0 z@;mA?nJ7#~j}T&xX(@-7ITI zOLpmWi?z$_bKJMzUxGJ}2g8fquke`bnFNO zxk$n(ZLYP`iZ)xFyi%ZsM`Gb;o^#X%Vtaq=Zxh&|f{=~i0Aw?Bph4_spuBL8`?Nil z^^UzO5n|ao3+qlnKSU~YCbQ>jwyxXYXeM=NUHx$tiqfc0#zgn`1cRoVMnZ4xV0PC@ zdE1wB^7~G1#f1E^tjy}hfUKy#x2Oz`qschs8FJdacNhzBA+)uXC54%+x;GT94zsP0 zHA>UYTRdsXsNw!5AoXnGOTxzVKM#tEj_z1Kt6nNcKEs(32cvaEBAhzhJ@hw8K-4v6 z&pfB>@8NM}%!7_yLMbEK4;xIAU|aSbjbr24s1Va$jsa8fBbiD*qG+@teJ-*fiP3bNsd{H$<#38=GqdN)6mebWt1<`mMCe`Mo`0(pP}xz zg>!}6;UOo7FcY=-%^IXyVk}~zJ@JVhid!VmZ+*}OIYnCT&Ul#*i_1^W#+xse3MYzA zNp34=2uBH$U`cUS+BPysc3MCfu6s|u&O4W}R?E=?q?vah2+K2kj5(5MZ8d^8=oG+p zi#6$NO_BJF6>N0Uaxv8Rm=eLNd()<<^f3CuyEMwq^35apf1OrMCui(4*8d>fEY41d z@>L=u{@19U$M;WtMJE=OXosj*&4awh4lZlPhk&TuBk`P1`NoR5Ffc9KpXp<+yIu5R zB0UdKS%j-wYXrB5@}Vf8UE;d>2>&xuvJ(3_ADuEOe`N)CfO(wISq)m}a8XERj91@4 zxi`Z)eMyn7O^i6XLD(x%cPO@P>sDGwYJuA{3Z|cpX~e*s{pF4}Drcr_)+uZi&o_=~iJ{WaRn*w@^s$8AaOI`6GGVcLTMwxdE3^>> zJ}#b$z8%*}TiMlIutgeP%jEqU-de`B&6nzj)Ty*|#m45-!@GEqococeuF4JqPrw#% z+QU#^V~>u;JHyZ5q&2ZE>=*EgvW&FiSznbsh56+hZ@g+^8+!8xU$Ku)i1Uwd1p7@% z(BRPvDN-GN%s8IJaG8S!T8rvIW@3Ormz{UE@qL82iG<*^K!K=h;Lzft&yWez`46uY zG1Q|-5c@{G$5V6QE0)A-_uW5}M1LKy0Lqgh>i29z^h-vvPC&$PiuLW(KAg<2JD|Iz znibY4Z))a=a?nkPS6$ODk2||Hm0cruY=mIqBn+`5Vk8CUgigh5+gM@ zs|xM7Q0%wdZUPUpoMwuLQWpC4;+LUT1CWla|_gUx*COjq~0PmT&?Kp zUFsLKNZ{iTNin8X=}y}e!A60b^<*(=b6(oLmTc=kR5YPH>^p8B4an^_+emtTCw9n^ zBJr%GFZpOFXp-A7yM}GB2<#l2<8k<1+a91Xw)3ja2KCwJ_kQ$Pjd1@OVSe(z=-%pl zlI4ToXjEj|%CzJdmZ@;u%U$E-{O)bj%{yFmbzu2!mJ>AjCIb22Ja~YZUz?)D3@i6M zA~BRhnR^#9ZC0%-ZQc*|-`Fa;8c8c??MznLX3f3g{fp{VuN3(b+({>3tx~Nhv~H|d zm#kFMcB95<`h631Xhw-B`S$GA5#3lpx`~jK=?qB;%gxREn1m5?rV5QZ2|X8d^rqnO zMKSK0a+AyZ&)oFssFDEft`tGi#r4jw(5wWGFEpn+ISl)1BLiMVhI5z&u*yHBWJaWw z?VDMs*bWRwmuLcM1`<^gNxw(%QP5GO^r{e)Y+=<0H||6_4UZx)W@io3?f&|go`3>M z^1K^hJC3Yh)*V!!K{nD7`BZ5zjV#ul_$I0gYzMX8e+x?L!mELLqxrP*OT`Vre{rAr zrRRiB!l8P&_uon>y6lB++b~J(uP)qg?0gcz}){@-E>yC8N`FeCwOyK{Ob_R#>_h-HyLf_SA^M5A;MG<#}P%@Iu#&xfK z7Bx_T*#mp6mrT{oC~+jPKND;jP+~C$WJ#$bTx~@P#dKk$wR3IhDo7auC~7Ev{;Eb$ zc8!;jW)s}ywAUeypbBTtnACFTt+8#X*{8&4a!SunRmkXLiy4Y9#kIimIF+y>TsT=) z+Vc6_%cfqF#&@cId;EOb`q&bB6n%bSlG%E{UjXV1czqtnzfNX~`w`Qd?GJt5@=nnd z%sk#&_4LVOz-$6ROW^O>G_H9-yK~wb+?8<<{YXzZO4t0+rL!0ESG5f}{Mq-xt>>0E z-$;~MYf0Nc5kqdPfiAYBNf11y957kX3BF~BF>1yxNj2DQyP%A6b;8a=C`wVUAWrxr zY5=@+M8;LzUk?& z6h*&p4yE}0^Dm?y`;UL~3Y_&HYR@~aMhU(|E)074eg3eWS%2~EQ@zV>U1+cAg=skn z9sdVom_ysd$%T2Q_f$63RjdF5l}M3jV;_)%ky9kf6uPe@aF%eM-!rv$GDH_|lAd2!X(K+)rQ4CDIGKmQ`b$R9jbZ zU9#}SM^Ew^cRgP{vDc$8OkC%tOTEu&@3mL4^N{CP>~(2rF(b#7H9Dk68Hf&*tLTcL z2bB-ha+!fI{fc6qLoe57aNWRl+s!jnRJn(dQjQ%)EcHn?95Pq)i%*z4Fu;yZe3LI4 zAhesWQjX0T(Wi9%FS#_Z=Jdb^2V!E^UqbqN-Q5LnFrT8lNuv2Kg5J75AEO)+!j}LT zx})OjetS&|P03{Lsz&3yuZr2b_T$;}=%W;MWM_Tye6qj`A8@^@2pGH>d7O0NBX8Lu z(%SG9bn$pTtqFb3_{??>`oXj=Aydomglsgezr0NOUeux3w;n9I#XjPvFHT;q`dwxD ze-iY4{(ZA(oZ{((eR(6sz{i9hgSZN5t=X>J?%~yR!H8TTlc&eCMwFfT%|JhJPL#ZK z0LsZb)4G?t|1s|m3D`49T+ATEz0=cAI|&b^UE_bL_J4fihu8#zri<;H&I2QxA*}O| z5QRw_>?`V1484%-rRoFF{ds(O&JA~7tI>%N$94{r_AEvrJ}+I!ri&bMMHP0+n0C!? z+I*{;|6Z8OK{(8C!F+i@;veTzqf*F`k-tDPsO{5i=8nv4u%deG41|B>(m(%N+38Jm z$)2jAGq?*Hi<`T2Y3uMOF2}L`<`Y>our~PWyLI~l#8mu=ov!2AN~dir2gF<(mSsXdZgU zdqRvo&@VdrKEX#65xM(lZc;`rV33yB+9`nT27UG^Y|RiLy!kd_a1nO@uwtK|+C^OM z3Ryv(A;-Ub@!Dw1chE}R!Pv3eO5oV6$KX7^azS9EyU`>IQvi|`Pi|8ECqg2PZlNsD zt5ogu_;c0Fe|Dgt3F2Y|c~R|KU2&N`5nYu7zSHS(b(?#$RP88ZpjQ3sPSUPRza{+Y zF-EN!aZ~Zj8|0C_P3e_6axR~t_PI^*D~#K_TaR{4QxL+qpCG2_R=am6O~jLII3*zZ zBd&unb>;ZboT!Pg-Seaj|8-aM0zELiRZ4Pw)9NnRjuX^(auo_fTDOe9aQF3?^@JQuL71Hj|6Rq%jCyV^GiNv# zOUcKWWwn1EHCM`8|2XK0(TR`WKxI5}gJJ1eLbp>h6E9!8qbh}G7T%z{yW0VnK2yYg za^5ac;Viv-Qfn13tA9S?GoJ~tcjxKQ0;ymg+!A`it6Qi&ewI%y-cng6zXh`r&sGpL zd+0QogiNZEk3Ff8G?0C9aV>Ei${lP&WT`nXyBz~z+Jz9NcEe=IR@SiUo0{C*W+d#C zR<*n(t(gRvYy5XBF?_C4>^lKB&r6euX`8^tPv0f?o9XolJESU@@u2t58eaOXzGo&Y zHjP}mUS_TYd$j847D6HO1B3O>wVT|ZX4vk&2HnWmF7I;P3fL}#kmtrsJTOq_<{6do z;E&Z)kdyGsbe{}P63at}f$31^7I!_NPy~*GN4~nJVpHU zvsLX!tQ${Iona1B1~9_F_LtyjWz0*W#{$hFl46dD38G^w=GdhM?7`UAH|z%pz34jlTezf;bUc;=<@ zXY3>ws{7LNmYxaV5v_lT*YVEr{1?v`h&FgP>l&{$OR~UAx1g2n)iYA;wMZ&}%QS`_ z>ls4Vf=~Zh1m5kbp7VnW5lV)2x|2BjLap+z5Dk(Vxhk;iUpzAHfaXkqG3wr%akthl zvE%Uj0nU;w(LM+pxA`iF6M-a1yy6i|07DSU9kG%o?i-97-k1hC%@+fxYPFv5y)(ma zP&$S_`6(tH{ZKY)y9t=}*Pl5D40U2?98y8|+PTG|(c;TiyT3G=AYtO!Gf*p8&%h%+ppp2A_Ue2v*Ddk4?N!bq^njvdKk^nGrR3$ z2md0@aFOIY;kt)9{0NrTrdWiRf813PFh^#O%d8V{_LIT2*+nmuRia|bE!7Wy=RXcX zYU)`=xUHwD(~Uz=s_Yf0x1IL3hD?i5y^{*4cUS`|{pM1wXG3BwM=4l()r_+DrR?zC z7Rpj(@NZN!g;;1$X6XfCPvD8SkFrX62*jic(7sb9{XfsZ=Ls&R?5iXoU^ZrKOGSq_scK7y2{AO%NI8%pzNuC0NoaQTLHMTPP{5T+ zI$HV?wq!m+M%xy;>QWMGA7@<_JJ?b*tmAb`F^0u3+FtX4zEEZw9=ILg7p6Ot`)C$E zHh+gHsy&)xw(_cZuuy}g-Javku?yJ^;zYW^=2+?Dk{I< z%FR{3Wmy2Sgz3 zIqPCIwn1xu8Z-l(F_(m2E%PqDY&^m*-bAOQ6&gAb7M}~sHEAw9Amc$bD~&wxrKsvg zn%jl9o6Dl*sfGRf1NF}7{;0ynqiY~mgd+UbRGXm9_0)m*(nY-AxRMf-^kRIa7+dg= zhE}G;c6M4}_|7%uO!i>H#PCD1{W>2{3t_Q^5f7goWAy{5Im$cqwnO;eS1VtGmA&|cmraL1 z-!1tbCJSVKTq`SmUBNb6mBdX0<;)pZnuTfeKPn2wVHZnKp`3@>xUF{=_by;f;`p<* zz`zm%+WucEvCUxb7rsObgwn`7`{s59zN{Toi@AJ>Df`f9PB??E3?BmEFIEoPIjbl+ z4y4UED`-?DCabfhQkmhs^0IYWV^wccO}lFK8s<@i@xB|6`je^lqpPl@2Dzt8NW#2r z*R~j}B#ltN-T$gLqkUsnr6ZVA!H}4ot(D5JE>EFl4|Mj^m$oYG{C%e0h~>(WM-C>t zki%+&$xfj+UdppkpI{2;FceE8;H4yGvSZOz9AXyhYD9U7!!W)CCe6mBS>ZvcD!b5# zL%j}|>dZjV2oz}z{3)bA(ZEZyQL@gj=IF)6^8D_D6-<+?Evqv*%h9a>u0&7&L}!Y= zm!hF0EKrtRqJdpnEnEvrn>IYoekd%5Zq%7F@lVNtlRK4~OK9MMczs1Oa@OIw}Q5SgMZ z;KJD(eR{!HAA;>L4v%@~aB)T}!kr*t#5&as%9X8W1UEl+fz4E3wm+KYnIh-k@-gKZ z1}aJj8FH%!$X5Y_RIcx4*|0L&NtwFe7ZC8CH&}gU^!nOgu!$5LYHX zbh+p@RK05rvx7KMWr%a-CeVE~QW<_e)ma;%x&6&vhOq;%Nf0^0xFcx43sf7dln;RX^ueCVpk2(3^OR#IYSgSFy9=f;f z#=o8{?7=nD%`^GUTnyu_yB`|CKm8Q-D=`h2Jv7L>)R z(O)rK*z6)X-Np3~p(5i`SPUdc#(2{xHkhZZV~3szBS+Eo6;a>2}7){qAZT<=->6#`T=nXtbOHzr_I zqS5AAxT(RWpl-$~Yq5J-s$#0<)IhSR{uw(q$9wt0V1G#;%r%TsIm$%GzyIr(1}mx0 z`JXD_|=j-7X%Dr2cljpSFnh2R|Dy@MXnCfAX_B~PP+^IC=_IGei(Pr zo$W&T8}1*HArc9(41IZhd0-B!wYMe^5VEqeA1k$c@e+-Vik72~fvv%fKN(>~zzX~Z z3GSz@hIOFxpY_l4p#)0GM*S0CL*Psn7bmVneMkU1Gd2iqx+3$2fO0Rb0sa}#uP*Z- z3I>RR)ljaUA}}M#Ui}(9R(V|%D4oC(I%|531aRi@u9jTa%);mfig@F;lEQKSu8*_F zI%bLV{HdBSPT|bHe(x}$(+J3 zqbi;1P0ewk^WFZ&4xuHBGG(~NclQ98V(XWRSML;^Ja;DE`u;jaK?T^HC5eAtCdnzo4=b6KDv08647nQ)BDy1m0KCx z6(trpHET(^KR(D>_$GINzsj#8UMlc&DPg+=*6%CAa5+;ny{mNI8RX{0A>f-9$wICJzS2`JWDDQ#v7-BMunX ze>zmjY@A@9VBE=UTwvcIIN8~fb9TVK0tzIoTqH~qR?aT2B&`1!r~fx6cR*V=er*xS z|Eg*`@1uIY#lW03ReP;wZ_%A!o6G8K1t#KacrLjLX31I=(|4KuSn2_NstPKTSlQh# z+}y;1U!od_Zm7Qz75y{pVSbtt<)K%un_yS@K-c<+-T1cK|DxfCD+_T>W0yD(1j(p&DhxX^;FG+>Vp^&xls?n z=8h1~z1dyYq1EVe%!ks#*C9SCELsD>R2)P2C(?ZbTmH{I_@c1h%^Fg1Nk#pGs?E6m|Sp)g6dRvjf+df4Wim_3-)w89_5MeyPxRPg(6VWuAnC zW7Jw2&$-d^O;1@#MnnZ;;auMM0aaEFU2nLy3wxzCfsNfkiZ4RRG_Zr2iI*C9vP}$K zzHg^SU6s27Yi4mi)c3Nu0~BdK?yOJi_#b$Rvu^5_9Trc@f-zZnAGs+*2#7>rAJK)1 zFX>HHn=sZZ;E?^-YCN-P3-`m)kB76O9z@eH|aUay6hW7vtk(Mdf=Ro+eq6eRVYASu`3{H6bvvj#FO&d5aL=UFD!$VZK?;m;o_VO5Bn(O% zQtLZl?H~LZv*HCJPyz!?7c`*;Zt}2hrc)5a%H;KQU--UIBFx>;L z7tAttr{7!LBuG^C=;)8c7js?}9&6YCrq+TTbpKfx(tihKp&eNPN3ECk{jMCJVs9U5 zNsn)Z*(lnY@awl`*^4Zar-0;++*^`%akR$|Is@teeDdvtK(l4?-b?av_^;Zdl`5X0 zXJsWaIRwn*X!kZQSiIM)(PJn#k9$C0h3&ysT1AK-k1iA8v;GThW=fT#U<7KG)_Edh z4}|3d#X!p#7-)XpLd%@++EJoTC?Ew2fed2ogDxe{6vpi0?z1 z&jG>)m=MYQJff2q5($z7<3fDza-Gb+zaw*kd>^WXC#~UIbO?#SZn#OCgZi@w(1t%P z*pEv^=bAs%-N0z~we4j~{fwE-6&z4LC>{#FOZ+?!8A+)}ZdsYA(hLzqSU>NC5X->h zAwk}Vn;}; zPKFoLwq$Jqh#s=8KadneVdtiMYTrxmko?O&ec#pm(ACpgfLwgGRB?93-dgKU#>^3C zDZ<4Oc)d`!KlV~uYdHv*abvL?=Z)@#k*-3KzgbQy{6?INU6Vp&e-0kaebb9iUo9_u z3tn;!f}bKZ8{9}xsnb!_pXDZa!Z`t-?#{#dk!Xf`(O44}X)e)Wre}izH5;+f8Ik^Y z@FVX6D##B<0Z3s$Rt{%rt#Ha5e{!pZ)3`g7&1fx{Nuy3*+)3*nNyO*{v3v~L$!H16 ziVbodAF_Zc)CShEt(X$n-&*xU;Y#RRuEHG_=GJ)&)Bf25VO2m7Dg7v7rS>S5qVjEH z)O-eHCMj~3j>(7A6Xx4!jlzjY6L4o`Lrl;Q&8IjY07~1!CtV9%N-vyvxB3yQkid71 z{XWrZ#xJtwPL^$-E_-Qw!Vzk`di159@~Xi#ogGiq2o@`8cdlKmq7@NsLzrwGaGad0 zXVG|+9l4h*1H8=I;ZPJdye9}>G2P7KU2E9y`pGG-))Ew$W;)t#tTQ8J_CwWB8fpbW z@rl^(fG%4j#*Pw2c0Ws&?P(OMPfC7|t0%Zz3q--0w6mU=z) ztu1dp0rEkeDi1^CP0l(IrH>9`1;Q@0TPqPLal`iO8;@~TR(g@ZW6{I;_duQ z`2g2fsRDlK2<~vV-q4f&0{8KvhSlg)sl5SPAmEURbv1m>HXh1Iqui_A3YyiqQoT7n z?c!D}nyw{v5lQ*Sc5ApES&9>3Trs~GTwm1TQJXU>#TqCabq`LuX|8jmleSqWaY4*} z99=n=i4z!9zWb>i8@l)7+85SeqBYOJl6MpHg?{v_b&4_pZ@j{haluRPp)ET0n^D6K zFv|OQcf!hWU^ zo1&Mv_D{Uigh42Q-)RrI^!__e8)vkSoLB?KKDaLD!Lw!R)~r1@(z9E6-Swut7JL?? zP{it_dKqrd9d*Gy7IJN&_D{O)F?F6E@Y|YKc4?$mg_{hy6e4kO8*&nOcNG^SJJ#ug8^b>ac-}2EB=()Zwr<3v}J?B4)++Ve=;2IEczzrBot{-rqhbP zQfF19H9Dm`&X)m#hPM}NZfg!*^)Vwz?u2-STjsIa-Y~IR)8*bjvv4|npWsZ=;0e6R z^WVYt{?W22lO6h?HCW6%jqDt4&0LsN9E=@YRjusYY>iwUoSBT-{(C^w*2>J@Rai+n znYkC53XPlXe+ky?tR!qK|KRi-|A)t%d@Kw`{SU(Y|InE6|GzZmfBg0v0hQ!d5ilBn zljpyGhc7bL?8%$ZLarV#T?o7Fh~BH&@ z$_8FVEp~OAeMFIQ&8dZY%`uAo`^zKMe))k~ zTrqFNB(P|uNKq4>LtJ$K+C6I(*Mci@ZHI>lkzVMKXA#yy6I!bkQxnOFvIl(RM#p~Y zYs*#=e3%^&6p3H2_$)mf1qx}r23pgo{vv{(y^|HT6|w)2;uHnr;9$_U{&5ugKWv>- zkS1ZbrOUQ$S9RI8-DTUhzp`!Hwr$($vTgVDKW8E)=FGXuh`h*%H{P3E&suA5diOL| z4GdZ9jw{kOz}o59FLIpZFc3Q!sSw|O3(J&x>*BrPtwB160n7SF%dP-%o@@>yUSGn@ z+Nm0u{S`~hCS2?6F2Bqew&BaBT)^vrViQk9=seh(`$UL(SGvhYqjjNjgRW8MtXxxQ zWC6x7Rz6TgLK%$j?PhWS$H{Uyqq!D@mcl{td#&9PKr@?slQMNjFJAb%!^D497c;s$ ze}oPt9(n^;!gTL8&^)&Ql43cVqx0os)#=((01ali5&c-oeiW=7L6C2AQMQ|F>1lRM zy{oiiVb*9ipKE*(tOH9+xRQi&LGieQPw(#y!@^b-R3$FpupI>UL(=w14o^pWO}tyw z>HZ!Oki8Wb@-I`dRM9U81_5K&7!ZIMOR6M-Y%^%dNK;(XLwrXjz0X?jtht)e`hB18 z?V1oea&Hq6BzcvD*I52X*zho1amZa!u-~$mcCuCsZDJC+ynt3hG$9xRR#Z_Ip#e1) zuJo|i+9^+105d2!YH% zY1E24MMqLs%>?8KU4@?2t~gwY9l9_81kMYa{d%ag=?XpHSMe*GOCi{bD3X+Hq)03U zFhbjYqQT8kt09YujF4fG(T|T?M@xXqSV(+rml{78+D`n7rrO|Jb#=}N!GyTkq2ajS z_RtV^ICX%OO*DFd7cYX+o)#Hctw*G4i(67TyAei;PhzAor{72MIzPY+09U2fDsWpUzVz`zHy9?lP}}TKp`=t7EH2y1 zr1N(z@eGmd;=t1+onOTc$0Gl|hJkp`oe}Zj=zeBmDxQfk+MNSBx70bXu1OM*0<06Vv$DbmV0xBp{u8mPXjZc+I8vwi035 z68ZOju7A-X;co%%YZ!qPpJWPhfDSh^EGjoa@9}S14$}mZR-7A1n)cHMUipUYUMW%x zx7olVlg_X)P0HH2rkbDXNY|*L@_1t_POx+PCkTT%fk8!grusq}7Mu-t_tL0K{~L{u zT8L{Dw{GKZ2fW#f8qOJFCq+v0eXpdYOi}^HJ5l&xlfL$7O_$3!tcd_;0MVb6f#D{a zAHyc!a`DXz6!9D(4`C0^Fw#e?LTDwJv$DrAZ-ric8?E2CQSs1Qv-JLnBjCm?W83KB z>4V5}ZqVR z3PmX^_89Qxt#REpoOfj_F<IIGdS;7#6GkNPbIf3KmQ(`M}oHW$ys{ z3k!NXp38c#rmR&jBg!DO7GnC%B3uf{LiCiR_y(x5rmH5H^i6&aUD<}of^^J)Kc@X# z+aaoE8tG{U1RbB92-Km~aG*LI2{6MEC(PYTHGdHQ+)-?j0?^h`h^K=Tsa(TuTpGw= zL0ar!gV~E=D#N21w^@X3Nwn>ITbog(*YDLR=wVQoe}%DfaHiY3J7+ggcTaVL47DI0m9 z?rW^gLBAUnGVcxCER3SVN(D|P8Gim|Gxrt7#Y59nV!IA!&$3f74>=xd8l}3`GI~zW z)jejl9IF<+?;F$CmPr5ytKz=5VSmh@(pI^ZzPxSS1Loo72m@~y?^8mu6bP4}tU49h z!$#r+<+=XWl6SAWVGwm?TOF6EfY}rzHaRcZO2IMIldUc{-~`vzOwCu6p>JQU(r{s} ztP22o@Hen4GWCDG^fTiZ-*^cwVU=cY(`}Kn9PiNU6l(j=YaAO&14ZRT$*rAqx~zNd zXMaO&0FY?ty%O1MMADvob>}{MmQ~Y?Y%}1VIElIP?NmwrDmQ5!?8$PJnRHS88BI$m zBiH<>yt96O2Em4_U|v6=YCLu%BQoQvdN9R;{oXy84YJT$-e?@WZl`E4*jH(}%ZQ?d zYkC-w?hFx{)oFE`i(MI6c+6$@<2xO9>$PHv1*l5Wa{-sm!plvjQ1@(xIAb6Silqv^ z3zJ~lq#p_Qn%osEx%S}tTRmDDtwQ;l_gW^F`~%$R!HJ~NOy%Tps4mrgO8pS(uo@t= zX%pAsxANucD@T&uFf)${x)-jU4xk=QUD)LYHywsO;jotQCs`aCkchlN-deGY0%@F%8lFn%3nu!6WNvRWVkmkpubE1EIl zJp)?;8JDu8DJM$or5j@7)=0Z1@YNa^fyDi*P9m0RW%Fbx7J)Oj5AWBz8WL9prfas? zrg!(*Q|hw6TXYf0c2|oFp|Q720V`$}t+%zX>{Ug2%G6@hufsTgsE0=%!md9VQRhvO)Woj@N z`$QXN*&kg8?$jgdbbyr3z;dEfWbPe>*(0lBtZ|+g9pU%Jm1&bPc1F?zemS0D7c!DLM~3SG@c56%H;q>YI@uGCCk8&vs#~u|EDV zwQ2;wF4?|w<`(;!qS>@TjVsbH=nHgI<9&JLYb;-45`sK}H15DBxlW4T% zAB*AV+b*)-PgvpO2tmtaIJ&+<7Cy(`?)EUYfjGj_0;H{&$jed z5{iPc9x4!9E*e$|ca4gc)D+-o1=hk1ZDgzPcWc?e@y;_G>CXEYPYt?jub!hnoJGla zc2tL^vx4iV;*cs~i%W%e09R7zTuik6f_y@mcszZtXkT%at&@Hh4@j50^_P#d7tDA* zc$D7NymU0~zjysZ-s`QsPDOa=1aDIUCBXw=n9*Gn_v#Vp@;%9}y326p{y79C3J!@T z>X}xwmgJ1$F13zr2$URKSli^z`&K2CuGo$ryUP$S9q2oKIC(}ii82HyotrotU@O3;izsE-;vvGY8w;q&_)?jXIAjF83BjNB&O5_Q3o$jz%(@oW zkznL3wOw?f4nt+H0P4mFGOES|HO>LaW+Uuy?aUWqJA$zAn_Qj21H=-%NxDK+VJ)TK zle2ubT}Po5+b}hq8>8*!42W3e!%Ekry78AL`TejAd8&ne1c?RR^c)A22TN^=d{m0r zlhO;PC!wbAX0X=}&7b=jO8h~6BgmnY;cQ636Q{ACG{zv+0PdFf>R1ODj#z(o`9ZGN+Ve-n2zIYFq&sd2r0c$cpE~fD z-vMdB?5iGSX9QyNVPjmlfp#P$TW12iu6+gLY?ar=shiszd_3=Vt&CTeZZ(1ckICd7 z<}0;j$5q{TEZ~*oeyTE41YaxVJ9T@cFW0YkLQ!=l(6m8$VEO-F)FLu5F%vNoDgSeG zn27!f-2W|PYZZX00Ibaa&4|0!-HJV8NASI^D?bHtbV-Aw!#KN0)R_SFH&q}e=dnO!7f=Df$iplilLmT$@T~F8VsII>@Pi`0N+H4Y)Nvr4<5JO zw8QhgKpFtba9ey!8wGowUxBb=&nBRP=%chR14fWsH%#Db zX%* zf;6z^HaA8us2u9jkhpa)BzNQYe)MC2}R22!idG)*C3BWG^0liaJn}&w0^eIOs#v74M4I|A_0fdEdyT!pz6O^`EIBt58#3QPdf8Yi)%F$;R zh5MrB2x>V|`u5&sm@_SELAsWVp`k`647I*BphmqcB;e}hjV6bm0~PI za_R)CND7LOIQiieDn@?{|Dq?1tg!8RO#bHU*R9eFU_iZ3L}qBIjZ`d;vMD%`Nc1rY z7=L4zfZLas9GgQzv>5E8b@CNaidsD1lhvB8A_NNwA6?5hK*^lisp zI0YCA93Go}i5w%2Xaup&wpX7@pO30)P1oisxyK0<<3 zdE?E+AfUjxmIm|4@5CI@e+S6nNwDN8W!0FE37B8#dQLNs+2WT~MGc|GdMLOpomAdp zdOlf1y!jK@i#5b&CyUIwMWYa>f#t;^##Qafa6O4xn~7e;S7NNxZY5Xo>Op-roF%#qA`# z;EJbuE8$>bzNZ^pHUUo~5-yp{;1)zemwE&GRrA8QE?;@o(PEbckLSpSIRDW-bI*J~ zyr~7qVeqZ$^;)@)F#Z7;|J&?RZd(-_+i^+qmZ6C}_VH<($&1~^4?yG6ma?3nyqKh$XlS z3%WIES|i%H2+fL~eO@-m1Zt+4^T%cl&gGbS>e}#QZJwZ-UYM=3HXG`oXu_|iiib6P zg>&CWx}Ea{=A&t8sTTQ+_F=uxWJ?@6tk#x3GCS4fD3NT_2QohxsBE5WrwSwo0}Q6` zml$P7Vl3mT=O{4~*lpGiy5?;LtaH$FJ}kPgX3H`)7euz))!an{aj$#++YHp{$7aIv@9q!5{Pv2D>R9f2eTZbCu?^;Dsq z0r;m4N7;87%oQkqRdwaJbWX%G0^*bh{Eu4||JX__J7kR-9Kc-|A4VHhqA=6G2Mn3L z$N1DpA(tC>pL%QsfVvU&g`%H!n^>b(uEBM7&IRT6BPC3TsDD*1CU;hwej0Emi3gUk{{ zf3O*$$nr;W%%=CuUx>B`;YAcd;yl`(gVf98y@zFK4#wX1oKREAUw|nft+gDAB%4~c z&2W7ry)P|mQ8&xI#2AX~zMa^=&oZkL0u=zG^JuCmQ`Gg~PvoMeDwgq}LRtE3ZaV zkQS~Vl7Hx;ofGr^$IUNFT;V)|qBxTE>0L8tkZvK&nBhuc?hL6pfXyX5;$;|OJ28lO zq=~Yx_y+yc!FHRZPRj8(wNB06kjk(-9|}%rLjndRexchT4EOSljy{C=&_eFtR70mT zghsCCy=;}AUeU>okn3LM0X=TgJ;6oCNHVUawVueaT!pa_D%R63O%#(ZN3)^;$aT8u zb+<9mf39a@xM=1jfHE%0aNND>cTVq(anO2};+{YIrv`FXsPXosznWfqtvh8~-y64O zevXXiLALEr!(4M*_`O~puI=QPK0#gbyH5#uIK51 z!O+#TjW7M>3X38T8QhE*+~GNOA4-`TyO1qr&bKR2b9@tJ3@;Gu9{q#$vJLM2qav)& zP%mN(F$Y)dqj)ij7&x%ZX(PQsIBNB#N?(1I6^QG$os<*nSwEF-f)B$pr4MeOdMM9= zi`|>A34bO40NrvoP7ml3i_Yp87V!L(ra%z^$FAsF%ANUz`{~=$KnTMZy3ZI2Gt@9% z*aZ9?;qd~kJ0yo~wXXYv@PYb6k)s$3n1bQJen0&iI>qJ=T1TJ$xH}Dv4(9~ZJP@`1VGq5-GlIl{NhK2_g zh?j>2ga&`h8gGtu?uXI-`K2o0I~&X7{q*b4Fg)aJ!_A7=GbramW#9Nzo`8Ta&h5ES zmHlnZ?Zgx#*5R+Z;g?hbv=NUgOqqfGRSiu~Ywh}4Jp?G%&XR8(=3QLct!AP1B|o0jr9+E@PBOVY-Mhm8Qna(+s5)| z_?DBd^h~6>Raq*!LAx4uKiBRa#~2H)^QY-oF9y)Q*&T`>A6NdK(Atkyy|2uedcCgw zm&90Jk3lAN%=o7}fIB@!;FhQ4q|Pi|2nNJ-Sa(Sr%CeiUMZ+}2PFtOBO!!2#U*msY5tn2sY=?MRc$=r8sOcwH*|=;#d7R8+z(a zrT<2cyB*tR>N%Q>A(yUc08HF6RD#5{DOK&Aa74VSvz_f1R!F|HsHMh}SW^5BCM8unQ>E%KfAi9!Rbb!B@Qty`@vy-CeN|YM8^rRkK>Ecu>b?bPFJW)9`BaIFS%CpxeG=oR? z6^44@d=dH=?-)$Y9g#Qq5=2*PjJlg&SB1$c@WMT-)i`+y!?~}t^4gq_ ziC(>X@6jTLY@DR8`s%J4>nCPLG9}xd8`!Sh$gT9&*2a!YU=!`>?OKli5=-c(W=mI; z^t0RSgp<8UDjJ3J*bCS4V}mO$+{5}!bs6;L=1UuXo!NhO_2%mS!1#aU(*S;#VD~xJ zQII<4z*dMKau>Yzy#O@YvtUUJ<2vTq^rl7U?Ct8bS%_b`1jriNWAjfIg9yaChSUk2 z3fx@q%t1z@LOS2H92e4Oea#c4%hcA+vim<|PvMS+gcZAAg#X>z@j)S5OUR(7F8qpR zaQ!pzF0(0U*^Fk20zUd$mHd+q)_hl_NYu9Z=!qxWc~nN;3c$6{M8UO6vxo9gpz@)u zg1}T=lBse>Hiluly0w4^CL60ejnQIzlKiQO2I+CW`HLBExM^1UA@}^D{)E|IdPVV#N8>u{1-P^ zW`+B%tCOO{xcC>L{QyC7+N>UMBoY%B^MA~JW=5v}dL$|0(WJ%c1KS{QaQx>D8#4<% z8xa#{5;8GG+HE5QTpFjr|780k{x{n{&9M#qciLYAU`hZhI|t|glYRXUA~|G7`G-jE z9zm2m`hcRqJ9$_<{vy(mFR)XeYp9}JyYcYFnjyvDM!cC==dnmnuiYm3wYI?RS^mlU$|PetPYl? z8UM-usbQLl^wjcFAc)3J>PA^2`}LHLHbQ+EpA3^lv4VX%B6I4T_%fDltVLs!+PWR> ztn6YOsXpc-B28nJ2(qcz)=an#C>h8oeZG~0sFugk+NAsyJxgYp=&1KKzfNpv=|Ewb zkNxcbO#QfD@mmpBUP_=OPav>6WX&D30LUkmqrmga%l>_DxB7ISoQt7Uknz;(rB_IunQ9{pG`|S8 zAmz4g9-CUlalEl(JszFWSD4+Bi{BN-FmKvo_e;u z);)QSoPOD5A6-xRa`kQ9Vm@-6o^K_hn0irs_F3MJtJE$h^_ltH0=DTdR61DIzI1=b zYUJEi3g=B7)1i#2N$XuXg69BYuI)J5|Va!o{(S*)ednLe~w&T-tK z>Q*ydR*)8EpFASj0*>H4Bx^%PMMj}7J4QK?hsq315ftX~wB&zJaK&ypY2<$=^PN^` z{Yf2LjK0;;FeK>6lh9LQj_oE0Ynz<=<*kF#f9|qn1)Q4^0H5K3pAmr{q5f9~UxN1J z7=>Ahj~-hXe`wtN#Kj2fyz2@4QM2l_nYE(nSd1iOA*9~$5RhEdzFDO4#c%#{?_>r! z*Hw$z$9yoRvWil3uN~#D%-m$5^$q z(fi^Nae6pyn7I*+wBrsfmt4G5NzCW6SPFhKCo?2{1ByBis`4uNAV=99z58LQaEi!m z%B%}Dh%Hl&3s^NYL{NbwK%N&^hc_0KYCpt@xrVh`rp0oZ*I?nPS%s? z(2@@oHXhle<0zM9pp-v9KBr!qLf?b&QDbZNQCzu_ZHV}CLa#5ja!;|PSxaxWa=j}C zic-cgOL90RanIfhFVcH74-{^pvIZ(HY7s5eP!&-U0vL=)PT<4%(ot`M`RfYF>UsDM zEma5!bsF0ObVzZxLh>G_V$~#2BU4a3)b>0RPr8R+eL(_7VqJAjqRtbdVJ0roCN(oA@^))hL1)P44J(Ks%rqD?tp~5f?}h zu`o(RMA;GN49Z~Ns!@1~XMDi*uPi>ebV3zpnE6x0* zZW=dqx2ap19`js$PQ;j4aO@Vta5%A}<}cL#0DVZjd&h_3{{Syh7&Nkl-@w_LB~mWBFx(DAZ`OC=_9;V@d6-1Iu=Q? zipqA_3S6%%@k}xMrA@kVd{J+kbTCSc11DCwD;mkdHJoG}?dX6BV1E%LQ(?GpM?`SI z()lw5aR;$zUV499AeK)Cu3ta+A=W-Ss_8auT|O+o!OZqTs36=dNFvw}fA)ToG*|}7 zicpRRu2D2d_hOdi?CPy8==dbUfS0vV*0dIat zu0dEzf}Km+MnNbB9&&eyIV1x(O{~b6xrgan^z<8LM@^^YTjScn`Jq<4(@VUGRTM4$ zP05x*6mD!5e1gI)u5Uq$zpGcBdJSF|XEs~x)JWD!noNgICU8vhjUW7XJaTGLqYSOY zM{_+-k=CoY zCG~@fx`(RLH@8F|v}%Nqb&5z=Jru}2t)xdA11+7%{Scko?`E2jtdhgD`H}J9QGo&4 z#e4&?R&v5Euq6B|<#>uxYvyHQ-UwZo7=4n2Vr!#W5Il3VSzz|MveBYFzLGbe!L2oh zp3c;^p7h~@-epyxRRkb5CKE&a$1dY`V(hiFOAMbAvJqxXM0tb43lvVCVBlB%1?a#w zP?oI9YC~5v0}byeJCPyo3h8gf#061JP!y^AYc(di3NB~889v(ZRLv0$Y_9O#3RmAX` zl;55GDOQjno_^_~EH|h-au(ngW$;Rijf_}!h2pGZdls-|8Rt-1OucO($+`hIQSc73 zy7z%JLw;?|Nh}mQYs+T*;1tQWn_`Cx6Zu}VvqwFxF57?7XowK(sNpudI${j8EbkrX zt8B1GwL=g3cj9TmG*`Ibz=p0OsQ1(*(`-sW@dDxcjP3*I3%h|D=6E8pk-eV zL`xjvrl#6H?$?NpEyd|NmSJ0!Nzc%AV4h=@i9-$%1%1}cp_kp3#8fn*IQvB0Bc zTi(eb+fx}cs+8G5dpS9-nyBleoU~g;1!khlww8oJvfL&_<|=|`*mgtD%Bxtvpsog^ ziI-_y08ahe?=XV4DcdA-y!CW91lLHs0T1T=%hcivYmyaK1$nLIf$;$S$b`%odC{#D zd=5|;d=}(-NCV}9_@Iu`75u7$WZOGAVSzr_huvxt1{o}Y)w%&T$c2{a_B#OmiG~JK zJmf3GFo#35G&DPfB!)Twhio!W(5oqBZPFs056uB*6Pvw(l*&n=0!fHTp+);pn8hGD ztr7OVaSD%)bec8Z)gV8SK_o`|dQs}Zr~=UM<7yW)ok!ca4z!qG9*Qs0fxt%wCe%3m zaxjtxaCpwZ+~WYtg7VrX;ph2G4plHdizM&OZNj%~r#==xc*%(s`(o@&#-*9B!DIa- zMrqBIE}fn>R|hvi0tW^;@BZ=ne$ z$SVXbr<4v7U?4f#nlvPy7PP};d0&`j*seJTW=(~`r~>X!2X>=r?$HoeRHetK!)#%>v?Q_4hQZUvtGHecr5bR` zOFn}N5*o?fZI01pv%Te|7z){%j}aiv73)>4jg7?%Vp}ptI@$c)?CqJ^%#8nv^a~<4 z@&@5p0&Bwoo#)zUsImub;4JW*(->rNaGNQD#hF&CxPt0PqPXImyVtF_!l9UJw8~vN<~CvPCiIFMID)A9P-~m+JCAt#e!JK$ zk)dZ=cXjQ8hzQ<}@MhqRY5>S_w5w4l7Bta{?$B!+zCf7$p@LHVIOShn`w%i7HR~0` zB-xlx<&>lLr<H1-CEyTgxvQgvc!$?WISR~|ET@C*PWM{KJLeA>Pe8|w8072#LpI$&B=217o537OS z<%X_X!6Sug%lxtP@1?Did|~qxRVIR?{VfKCKK_V;c2M0oit9*9VEw?CJ(W&+oTZnZisI0k z)AI^jo$(_yl6d?_s3Yq|gdIBueBi5@+p&?Xy$yJwA%rL~k+(n9l_G+8G(sB=m&qmNUN zl6{<5S{I6WZWp|(0QfBgcPxRH?ZjSkSft}3%1H4clsJf(dk+RE3z~yNOEpP;n-s}m z)MYa51r**CE+3}dx_}RDDaIhKObb18kF1~bnb>s_ulmAhQ_?B!j5tp2DeIa;*2~>0 zY~ZyyRQ+Cwa{$n*4YR9WJgglIEu7RK^s_134ObUfNPO%>Xz!R^s6mlrMA1h2iG~C$ zM!-spx|lc!*-}S(o=9pp9%JTyf47n_6L=}KLAezNSELHF3E&jmo@VXPmD#X6u^D01 zl52kBDE3cHXJn7s@a4(j0bOp-?~GxlCpA;E!7XGK)&YQtv3{ky0W>Sn3Ey`HlkZN} z9P@3f(n_dUk&%Tq5qtVyH-=arivqe@uurVbz+B>TufC9ouP#N?A#Hl6(6mp#kTfD_ z4~-;nLgae5pL!>$t@Wb_G?P6u=$I6f(^`{g*VYf2Pw0X3kQEKHs*RB$4c2gFHylj_ zTKgjaYXETl+tJsmvCV$%_S2m~q=drVUc@aA_CF^Qr5mQq3Qn=MZe7Fp-W$x(*PEIS zNrTarF!`dRMq9$y%y*OsW<%hdxF+F99!;S0+xUqUA$=)0r&)p+@c?&q`zvL??1fI({BX+_`jnxra}LtY zZZhJK_s@p%obv=I$%U8so!hk`!#ihHao)t;&ma`(vlrv>aU4JxgI;!QdC~WSNi&ed zY!n6yY|h`ec5c@;O*4Qcx}S2`=xrj543Dqiz{P`h?!&gsEGR z<^?_8t1-_lGcH9sBFweiNeuc1FpN|W;hVWX;sMyZcmMh^3GP(0%Vg^LY8oj3>aFKG z+1)eg{(jXo*1&%Viij{g(D!uf9i>;J@kn2DH} zlJ59a(wvT5s~%e=|hy{s0W1SQ*uDU>bV>Fz_T zAAq>3(>)$K-{`}){KPWOhoRz+ER^0AeS3|8`-@BI`uUkwmX~W3nPesZ_MWEz_*}Z~ zBX-5Q&USzQj7gmxyL!O*>-%@d7Vv)m7^m>ZkJ3)yhauT0nVExOM-JxFNJ=1Il&K7h zI0e9xw_r8F&DG#bYxF!7r}+IZIb^RtB9}R^LH%`Vp9k}XXXVJCiqu*0nK1&(Un0T&~r1&kfQO`iEqB>uBev^4^4ERZ9fdqVXeq?74upl zp`7-dnac+e*%Kq@LYhfA0uZsOPBRqaB;OrULAmZJOiqa5;T!Bt#f{~}oMR2Zjyp5{ z7{I6aNaV0`GfIT;-;%M;uFKVcA(>_~l|W>7p-~4(^R~Q6u3{90de9;K~0sA!hTJXfORBiydNtWq2 zXkg`bIH3=s!V9R!c@U62Sg8te4H4GoaXTz{2@ z(1w#b+Ym*;59AKCcUWKCQ5E|J6gnG5tXJ^|?FR9-=Zwu}XTYTUe3tU6^rWIN3h4dQ zwQFKPusAUU;IOukda00_eQ_X@=?R4XeZ?)-4I@GjM9o~NdPrPCIUhY9F>7yu8Y~@3 z(Xf47wNG`6vD}Z;Q5V~P;a)?7voO^0VR5{s07p(^K2Y=piz!2=w_eBEqXYe_Jq%7zfE4VG! zFjE#$ukgP}3bn{M$eK5h&>mXgl_0Du`I3c3eX=E)DXurKqk{ClA;SmI!UZha-c3&Gca^gMu-Dk|in^WsS z>tZl3fE&9w8|xruk&+;fiWxp{FojmTZir;txjw8tt4HsH?8m6MNv{{YaUCnFM^&6s z&w@?}7|aWe@R9gxLg3O=!M#~H6|N4U&f@e#Z`_zuh1z8O^uvKKEaqUA{)ZjtqNaVw zzm7QwLMPs)^rrKVi4+5t!-O1hSo#w=D*d50U_9g*LU9Qw0kU-fY$?vMK1++f1s#$8Y8L!!{udTCWyVl$HR5l&ZWrz4_PUvOL%u~8f425a#(hwkT-3)8}#0pWdjPS=X z-taR2)#0Z+6}pu!s71-U=o#VW1~)YyGls`0aR?2jm$h~9&62a4P9sMW$8eLHTBU{< zFdwUGT~AfKFkF^ZcLx4x2Q<9w^Vk9V%G7Q?kN;fPt|Vz02_2>zd&J*pK;vBjRAmaz zb|XmW!kiF@UW5-6xV7Q}%$QwTd0_@U!nYb^&A^#DXwCd6cm>yLzE3?DQU<-ap-?)1 zze-!&sVK^ErCpH{(gsvW46nlH!#&dtF!SUwa-^!WHu04RES~@O!b>7+PhD;paQ256k%J93XEUHwa?#pftD=r zZzd(+OP?2Px-*FvqFzf@&&JY542-_u*Ig3PuZE2YD=yo)?^`d%M)ny8 ztM=zW@irSi-VH85n-J%n7jHFXKMH1C=5wU86u(^( z=J#BhFqH5QvQ5MpBcF);+D}A-u}-Q)M2t);l9w{F9ZAH1*($;3FqX+weiyPECm}~$ zDfVYy{sljO9nWQ}HND1IEuX24lZ4Q|M7BamfF{7AuJ~$W>EE|mf2kf4JG)sD z>rd6wSXx?2a_`A!srY&*el4!2y9{TuU$C$S`g{}1B{a7&yXanqA|?abW4}QC-DO?PaaW`Em_#?`ioN|7&; zOP>tWNTO6s8JF?`PVMr%odanM-0pBvBrzB>5UX@1f%oCd3WSL9GB+j#%KQ}UWU6Gk_x?*yL{galAf_eH;IH#n>>Y7cwwS%JyQ^vD9 z{HIs$EPjrwY7<%G(bM&5feGSx>qvtrL*qyv>mIcj92v-(gJhG7#uU8&IW9|KJXZp= z)7Amg(z>ZFYAK%A_XJ{`2wTYcr|m(K8tih7*;bK*ztW z|Jp}7%MR2ZO_5z}`LqKC%_|5>+%x3e(w<}3T-h)d$NDtFdWxKFIUn9(EEp9QkRSKL zRCZ^Fz^W(VUd^uU#D8#ul-o;;Rj;%AHyima)^;N`#X)Q&Jj7lr!d7DA#S)9Y;TyhR zb1IfM2>wxWHlAQVpdBQxgoo%Q#^;6`(U(x<5C5|wZO)Hi*kC+wrae{UGrmjtGCZ=O z!lXTCXlFl4t4ZHpW|(h9K^ClYtMkmC0uCYG+^5P!i#k~$36M8-#D4vCEX;t+xM_f) zc;hgouFAk7Y$K9#z$j$my$fa(bQxGW3y|r%C-Nb}MY2diYgL%|{uga8{x^g$Q0UDc zqxzukWQR5=K3^1_JMU#CKip4#?-3LxWTTS=VZn3b0Pnmhti{!mT96fA=B#rqupfA^ zK#Yh{czWm^;XDUl+JUS^M14ksx*k9vB0Uk|i_vrFpI>Iv%)Nw0i_e%6^C3=kFJGmO zS{I6Z9yKXDBZp`EbV;|FDEd{mCwKQ`^?0E3?NW#jm9NACE%|4-o(ucVx!kp26PEqAtUbXi9D$gq_p8IbZOnyaoZu^py)5 zqgK`Kifa3`Ejn-G`WV#o#)K@|Zw{fjGVT8=_T{)jRAJYs;k2B7b5;|67C(iMxDZ&_ zA%SLRWu~%DkQTed|1R8SO#OJ<6#9X_GFJZ}0%fB2TzHHh3T{XagW7=a!~X~?w%DEI zy}k&)^iL62L3?UVwyciJb1EP>wAIQ%{No_quVo((-Eo0>}M|3wfH{wUsE za^3aLB@G{>IFY49oh>n)IOOKnh%AtyZJu}?(Iqc)5()>oQSkEm%sD`-H@!?Ry?hFB z6t3k3=WZSQ-HCrUV_#(-K(hnwb`F=O*hyl7BH|LrkEmG+ye86&t9bu zrFK*apGA=ne=5?N&56ND-dhZ@mB*Z82@*c!p>&X`yh^0OvMx7tNYD?BgHen}p~KmG zj-H-Chyt7v+%D%(C=J*|OPVc^so7Eg-54K?vXFz#0YxCh$a}et88S_w@M-7p1ZdC9s%|kO&&nAhDTNTt{vCK z1uRz1Jai+WyY61n8@GSo5vxQKT_PzeqQ5k5rW38bdC(5=#{qoGo9x1}9MlfGYPatg zcI3$oi*;KwV|Z>D!1#13ce7^QIniYuY|+dZ)jYS#T@+jcUsZQHhOXM)K$wr$(CZDV3Pnb^8{&#imwociJ4 zU2E;CU29iYukL<64=)zs$zJQ8S96lXE0`kbCb#2{BBqjPDf=a=N$0R3_GJHxDHD5o z)XSq>Rwk@u1*mk1$L-?)=V=B#8V7oWob8vBN3rEo&n8!J^eQ~og?1oj@)1xFBqB7cG*4;4xUPFv z4y?3V)4m8KTMD&KFP+svo5CWK zauSmcV-AHBZZBE;;~+T|+6sl*Pd>%4m6q`FcJzPKFqolPszPev>nSldsyui%88Nsk z*S;)vxvBU9TjcICssEXa0sc=iR!=TwK9t1geU7#i!bZh&n3E0DIq}?E>GR#Wy!M^Y z?0I~HPBw{6( zC2@x{6$Ed1dEbuex%&FbvYt#$n;6hr>YU#V?{lq3EU&r)v}>T2Y#bEIVhI{q&X}b8 z#AUtitREi?KL5!y#2>xkXKKOStuEcJDY-klcXJoFOkS^X{c-l=3zht>M=|xGcc#jd znvAcL8q>Z31?;rD7N$UgBK61$+UOedM^!vKciqiC1Hx)3lj+y<4)wCL%kju0dz`rv zNsD^zzo|@hfPtHU?>`*g)`b`&>tL%tqDFKn-Sh`!MWeK72Ycz%qE7E!=Dpr!>oZO$ zD=4!EWTHx$?TnKLvZ_8*iA3qG1IlR(&tsf zvLibh*i0iA>R{EkcT@T~`3c0mOTz zf`I{>d%1sP8T$JO(j$QI_+@`X4pfRN^KMmPSeWCFMn1C3bg6|`anmY``5HaVUblbl zbVW=W0KDE_$CcnPb8aSga=-36CwuAKGMZ;`zdpNl;a%2Vhd*EMpHpuRQVDZ<-gESP zUt+7pB7^lX?CG$YqXkj3D(eLjp%S>I$CnnFzgj4<}pQPG}x9c4WQLq(b-KIg6XZ!ImVS0 zlzE713dNQ%CxVIebY}E*0cc*MFob1Z*y7_*3hLT&7Jj$U5vCx0Lq*QkT=CA z)!SyOtc>HkweWs5iu#D-_j615SJk2l(@O9iBLy4ivV!~^Q`TQ765KH5MSb?FTW%_C zt8_#Z}_CvsvohK zsTh2_zk-@*|LtA)%Ene%O*?*SZ2;_i{eFF`EoCscUM-s%x&)fj>6R^N5P}%Ekpt3A ziza{GSh+2nt^359zUlIiJ^P6zPdmd;i%eCZ_w-k3&jX6hieAA0;s@?&pY(c0GM0Cw zmvN`8*swHN6C(4Pgg|n#>ger|Asn*&s-Tz6$)6m9EV-+{S>4t|tHEN%Z zr-wLu9$~((O2@2u9kG4A<9s(?QLk)x55BsZT#Ad?)?b$NZCw}jWMgbJxuqMDLewN& z7!GG!Un+0<+l^`%j((%aq~-C8#A8i3KPhjP{as>@Bs~O>H_W13L_wnt$BXNsAlHf~ zpP?t3HYgNBN{PV}fW@QusutOb85eaqi{<=Yc~1UKZI?2xDXw!5(Af7MFKS`|@2QgV zzU~!gPOZeM4@%8NGgA)oB~qQ3gNGqd3vsMC#7TCqw%7qNIqjpC6q zsB=A8u!Tm<5tY;bmYV)h+AW`oHErLfZC0zs7Cdp-Mx%xP>j3! zRG@l1J@W-QUG|F^^Kw8=(M`*buXfZ$9$Qw5(W+jc498h;E|&?$91@LW3buV1&-I{ zw;aH$k}YLLZ$kDT$}RUb`NB5y8DNbrG8NC^R4iwDzwMB+S(agSq(H@Ny$(DTU1Bot zIel+bBuUrq!sptBa))@_?l!>Hg8i6-4|_+m0ZB(shF#p>_xKr8L@@$m*xy@B!-m&@m{;98|W4g zh9uK_DI$q>@uE)!HGM5fy!T2L7W9Ey$?gh45!%$ZU%x{OD8b@WM5Df_QZ1&SZP6%wYj zRbe|lmgPkA!3DptE>$KDVC81o1!zFZG3-*4pKjw0g-a0YTLMuPfc|;@!l=e{n4}5v zH@MZ5tb%U+u`^W{&jNJlIeyvr>GD_WQZ;T%+lt1b<&&?G5@t+>jP{jPo3@8}(+y%u zxJ_qK)-!SinipdrBy%37jZ*dLP}P%ok+{MTTy9l;x*9C$i;ziK__R;9TMK|_`L@4- zvCwtp0Q`Y-W>;LT4$PX=-iB2g?0`#Qq2RfYkFy0HJXXeXiQT9D6#v|2MW@e z{^3cLiK%6WZjd;zHYFF9&e&|GG*0<59SE}VE{ za7E^v&M@CHhXDuhW!iEL?cb|KkT!%zY(MCI6wQJ<2`;d{JSd?o;{pJBv;p#oDH*6u zfFbk~M#OnK^(H^O-q;Pczv>t<9{-IHVFxHqeci>}!UK^1T|b9ESVx))5}$Al@-c46 z(&>5}9D#&CBsX)3wJRCw)2DfW}~V06zTy7hbMS$ z5igp7Ke6f}EhhPqkrUty;Y^EO-Axg(`WK5A2??c2Vx6+quo2yM1-u))fS=p&c*U@@<@C)FP-p_5xS^tPGWN#q^dRHMqBKQ{Mn~jfXRdZsnMPzg`bX+@-D5-;`gC5| z2PNGQGrHW;HLUIn@7oO92BwH~Ss|#z#$Iz3!KKdk))GJ6qauJms>T3Lq_FO|4%VgsL=Ur6)c88d7&Ps4ML!CCWs(AqLWN7F(f2oEi&rU zl1rgON2LrAk<%5?zZCK^OwcV;?gd*Cxmt4Mf|(oOci_^gI}w*&TL#K^T zO>Ti6wjrn;)C8o`2l}edKiM%V|FP18X|~i(Aem_(ME^4` z^k}v4C&^JW0l#ieN@{0Ul#STotJB7Rr{DlBIto$H>H+>@ZgrQ~*@($m2 zhRHQ5dWGlIxYD|ZCeUT&c{2dm3JmHnZbYcCzV7-JLGh%V#rz-78ZqS*q=q`;Q`pu` zGL_;gN5}eMWhvy-ti@~~MXz2bT zERG?-+?e{wk}A)I%TGQGAr8qKuTby3z%>>1&mh|S3{gN3Q2J$C;XCz>P>!O<}KIPw9fTP%h+a5x%w!Y2(sS!G+Rn?(daOn|B;9lbsXV9e4$fOSE;9 z!hf^~E(`FDXNR+tURBD_GI3Y`8s>E^$dPOTf47dvZC^y|g+sC8I9}msz?daBO?3mD zARcXkY0y=%21_^kQw`x^FG9#4ri*bWr=8-0?a#+|G#2!95Pg6I1t!4Bg#{AC`JGmu z&FA5!meF2|VBJ~~3ET^)@!KRN_!B(p4d#}f`twzEaxGF?clPzc#R-0Ok#p${c%mQz zz6kV1xu0->y0&9Y1a8jsXXBUY6`5z+=DR8T@HdJrU}OO2MaKH5DG+}K3hh)2l!rQ^ zHc8uPBHAHp%Vg@njrl}L+Cz2BTlk}V5G*zz-+*qqLQewYg#Egy*~EI5NJ*ecqu=#2y4OniS>$=uriOpuhhe2s)F2*mk#GTj<_Qh~+At^L22F~O0&ls|~8_?VkUwUj&*MWCe}*%D@dY>{2~JEMx&G>6ui1A@`S?bN1D5#BnBzx+?ZJ!(xcBE@ z8T{+6>li5^KdI7Na>1j|OelbLz2jAqTU8PoDOhob?c@QWRhNvZtq_E$;k#7#E#ioO$MmW08d?fNhzNmK zHb@f>SqO{j-?mBc1!q?KHtf3&fYDBZVRJp|w=Bbtzn34|^ikvE6$g1FjrK?(K*GXcf6sTy85H#M@k$bwq0=JFChY3(r$sA`h- z9tdR_LGo(qpIvSoaoQl%R&}K9b0EdU`2k?wN>9tdcJ?r31+PA-FK5D5tgEM5;Cy z=iYyV%NM^|o^kZeVHl`SuY$Fz=#7WG&(+Pe@tOjbJ;2gpo3Y)moq;ScSaq^dq}0hM z5{c{Yprmq}C5xggEVj5A0&6EE*|vMB2Qx$EK<1-tvx=L7*SuIL)U4~!oG8Tyg06UE;B5n>PiK>E|VjHI|*iM@Fv9BUYk`b60$NC)#D< zj@egHVz&{g7xhf=Gq{?p&22nr``ViS@}}q^x|jB7K&@qLW|VBqay!69SFfABbt@)^ zHmK7=%4OLLtRG@kYwz&c{D}1~*-zzuyfpr*)qi%M?E$nXx;ww`W)%>qe;AoK6~3)F z-pjQXTxZ&|D$>8zO=>=#B}ZVR-|bh??5eAepV-9o`Mko(=+4vSpc%mbb5zPWu~rM! zuDKMCmv+`FrrfS-QWpPu#TztaFN`>l9wSEeRJml7675mJh zc^zHf0P4l6mB`Oam)@Hdruk1k*XqUUvYLZtdh!lEm)u{pG0wPyA59Z|Z9~ko>(y;- zO{5jS(i|WBXHhML#|vvakuloU@mquXs_nZt_;z7;OJW#4dr`13?egYl;i7nO1Q8Ep zVg(>YVg%U@KiXrk@{W%GmB&7I1hn`=p&Z6i0KDbx9)qb)|CU`vSqW_q;QxlIY*R83 zvIy^F&zjeuK19tbBpF?Ba1tCn@57#OU;?4zEuxC|l7JND5e9Y7-YCrJ{0xK592r(3 zXrYSbKlFL7!_R%~=6uA1w8bctMzZ6i5BU+lG75BdM0y#+WmE)8Vl;q38Yz-7o z1~8P0NgEv#OE+x?f8d)!P zx7vL+!uRL$B3TuB|9w1lCNxCDz_^)Y?QRY25%bL#v2nA@$f!tK))(VQrk^T>| zWbY#8@bRDTgNy^=$UKMpaTz}+j~@WwkH<8KvU4eT+~|ir{=Q@KJ1Fss_vPaF?n~X( zbMHEycl@be3;{8?kQQZm%|^o8IzRT=Q5FIhI$`sL4sw}TU+N@Q-kyTdoJM`=KWpJJ zY6;^*2JgVG*q*pMlQvrSVNeg(Uibmy1A0!07y{Eafs2+4$V-8FaehXzop;#jSwN6q zFM6v5!Bp?$)f(wPgXEq2d52!88|z~q;|r6WHymOFr06b(QEckl%5|KNFv_YI;m6n; za18Ng25R`y=O6nAuIAF0T|MyFVQJ1)VGX}%)MxfM(B8i5(w&VfcKYM3J_VN@v*&UK zlDiY|-B+MP7yI|lFc4@vCN00*Fmlkb%EVb8&j*IG>)?fJ2&XunfiI&WZt+V8*~Xwed2tbGi8$pzwcq!} zSX9%)PA+@0nTiVxVPhm>O!S-6uHsV2;e|#n`WO`o0zQwkwF&|~b+8(N^M&8Ddins* zeU?mdDi_bs4^|w)-=8N(vr$s-sgoDIxtomEMqsNdL0&V+x-K(SnWT7OhRot+{#yLn zb|-kNSj3R|@EV0#01{S6F{^MA#iR9r38zXlYUvZa8Ky$l;a5oKO3kQUW27mqN$#RB zvjEN|3h}=}Fr&e~P$y;0A0|;R59@qSK?IAe);Mcwep(3IT#ZY2#;gaJR=Q~sM!sYj zrZzaRi)zPKrr@Mp?qg6IkYb01@bRo!BhnEQC}uNj~xW zg_vk_AuYud5psL9R>WJvhICXdta0o`jYQ4Z91*e6(M5E7w3d0;)qNmlbU7&j>x}VV z=ieVsL&XS%sVvA}ua{;@;NL0%!X<`M-EgUg-|Je2ch1V@A)3=rz0$AP{pl4Yj%n3j z2Ix!5bKNX*fVCstKyqph#+qsE%$F%C6cWm2X%yXzd}BID*c0+cW}gT-jn>K5Nim%tB0W7cS7eq%U|rk*b=)LjRtauUjun4oa-W9M=(9Xo z11B9m0p~04Zka|KSfI3|c$PZlD%Am%LmQ~wp0;_t>gfaSDVaEEv>A2p;PgYtX{T@q zM^uglIGgFzCdsGBDYICosmddZ%C|t}(4=bbpy3yGdM3*vj5vpS%0-Z}WVlJ2vjsDI zFzJ21>$2lMI#;Voq=RU=1?4N1h-P8XFWPDaTO^|{4DZ;gvn)0xG+KvS_07S!J_T%` zEED7|YukF~0Wy{itt}i6Yj<2%WxCW8%IR;-uPR`ImD$>dPGNEVPnG?=AGnuR+4PNS_9L_8(N;mSYRijC)2)6UkDahmp!Pyw90KeZ_Vl$ zSqvwlADUHHbfAVsNV%t~6g0_DvNj|@oC4S~?6t5U3a21S4c)ftqQ)g``9Vevt3~1~yZ181l*XA@2lbKm4u7Xt%ocJuCf@;67?=z|h2F5Fjc~2W~+4yn# zFNisSmlWf)+b<(RvvBq#zD&w`yQ-X|M)iG!lOt^2Rv7u+tSUzRn)4}0!e`FU-z~4e zF@~W3Ir}*#4Bj70Vj{yH&lnU!9U+ng*Z&fn74shWJ=|7uQNbaWDuI45Z}PJI%(Haz zV?+*`&)(fY10Hhv;utBoEOZvocs6$@r7s<0xjYg8@fpH3x53tzk$;&Hzh^BLDGO8} z_B>-3YwlFpN(hl=aXt7XsGdOXE*w(5(3A{w`O8MD3rH)DuKPai3+VK)WV_`78X~gZ z_Ame57K71I+&#s%=@@Jz!t@yQt%|;D)FYNI(y|{cmuGj#6LHH{o?RdyVuJFrqtvm| z5PxpGI=$ghI+8eVbZYH5sG%a?1QeDD1u8gBL-MW$-V(V9@6nUEMOINLcJxxMQ&u(r z(Rf93yAIC>JM-k?-K-7QKFl|q-5d?G+yb#fuu-|zk{G|2Qq6O@nJnLx;zvT758I@; zp0HxRRp#ftO*&pb9!w926E=cHu^th{aVc19b(kV=Mw<&rPwLj&m+EG0aj%%{-~UJQ zam?$PQaluCDCP4|w{zF1cP<_NPVcrk9^sTbjHse?t3H5w!S(qQt7vWQ${N-PD_&Ym zAweJW=e*5G$RJxJo}B9oPy}!KtlqdGVc-7~)fza1YFgDA0RTuufPi^#(MAf>3N1G8@A<^LWhLhR^@Z>Pm%>@PBp^rPcj$qM zefF_;Oe~@kenZApJHpnOZEAY&wO~&T{+Q5Qt5xk8lZ)(pqtZbLlolHsE3#!~B*3r(bv7w{4vk>g(j-bVujO>8 zQG|$Z6JAvmTP_Ea8n&#wG&{8b6`ZvVI?Py~s`&|mvv+ZMDh4vedNeit+tBYYlR@M0 z{GI~#j)(a-*~VyR$BYV*^GYkdFC z&*@fjPe5~=)Pnr3Nzv@pisdLVdQQX!Rwp2@yg9T|T_9;cl=1er`YzTcsxHIw5ws3>dw&rfke^-A)) zg-ExV8Uq-utynjFpY36R28pP-u4)KPU#o^|Q8tH^?lRPP0Eg z1xR9rL;K9p)IR*--k2~Zt0)zCREmIHcL*Jo!#|O{RMYNPi=*bwSVl3%AUALb`7D^A zxu2r1be)#pnkxj)=H8%fF~38 ziP(9_<%8paBc#2a(W(-|Eh+u!28PcSuALrk5Bf$|1d*l-lpOyh026b5`vK(x-vM*U z;;VUlC+pSY()A{f*x{Oc#x~Xta(s6nN1RyGAjQTYVuSZTpHEBIRugK{gRxk+I1I)N zrDIm^wtJiaf5PzQ!!rX+{QV3-m{LVj6uq0hd{ z5@fS=|8RgGo3{P=&(eSpsvMGo*(H^DAieF~b;G%SYO~q>A)U;U?aCWaRLLZ@tJ-~# zmu2tT?O(jqgJQhONO@E(f#!5vDXO@K?=4#HWMA#QRo|SwjY!icgXbsz=c`mdN&6!3 ztq)1po2WxXbdlh@0A`t;^Hv$S!Fz^TW9*uD6L?pVFeFGpVV*D0Zr0GQ4QTWV$|Cqq zTrPMQ?NXUjVXW3D9ugI>r14Pd+w)f^%hYL(iK}ipe^u5sT!;s|u;`lXVf&_@~P~rqf(?%Zh zN+S$mCkR-&ASZ@!Vq7Z9BeoIs<@`Ofjt$1b>g8fqSDpe%hXyzR9+7$1`H2f&2$ALt z7TDnHj9$c(6!`bRb*fR!<;&JH{&!}DYgv15dF|xW+Ji;^qQMOc`70M>*qeavW4xaI zJ3|--8!7&m_O?CtK14%#Gz|1+@Wt7ic|kBuwv4u<$Gm+HQ3nwfp>|4&rJa>a2h~rI z>3?gH%-uyj0k_?ahkQQ&&fiw$+{w^#$vu}JrsmtByiAMIBxiaYDMf6~(TAI)^ z`#0s@8@&ZCXS$A^*x(hHf%Ro_O8tv7#Z2bZTE|iBH-)J~C9O&)Vn@~eab*RY1V=Cb z+I@^J)iM;ub&W&6U~DIl&2ThqUHQ0jES|L-lZw(w`Lf`gOme-Boqc=iGb z0nJ{<<|LXOLx97 zt?QXpciXs}O601}G?Ke?J~bS-)TIZVp&@oY=6g1_?d9 zULXB2O|2>98FmP|pb;6qc|X&GA-6WkC@6(o#cvY zcwL4l&9`Bvep}$6;F*5e0j9eZu3me1EYh7@<9)mt{5jV#26}n6132w6;%Wuwc56X9 z7OLZG6$RGklFb6EL7N7^V%#{y{7N^E#h!npsUXc;n%LEdS7fr3HLGC{hG8{Gy!`+ypk6E|iwcG^^{Uqj3{q#MAOs+Xzbe-oaLzFlvcvT0>s^$4 z*sqT<)^#!$nH`6OH)MDjXV7h!7$mamLyM8c*TX%RQMbv(aY$0eud#Rmi!pC1=j+AV zqWeFo{vA;}@t00+JLVN^sc9;!raJ-FRBE>nt~4q(w&|TETXWtQWw=oSE1UWo01St6 z=z_hygA6d}M}A~em|j}6&s>N`|7BWj&CIZ?pD#kp?am*F!B{w#R)C7TRmDWIw{vkR*;8VymO5>NZTtF;<8Zt7XG$i}Ge%x9v2{ zF#A`b))LbM*qBG1vivKDrOUb@PDJ?J4p{cZ)eq1`lo=V_>3oqSF3~0<>?D-ZoV?wLvwqwbOTMVG8?Q;9j_fb?q9ts3QNYST1aj##=^L_ z8&o#}p8@Td3nC9TlT>t}WrT^UOrk04E^z=Aq4e&Q1W;PH04%qVRwJ#KBqFs>N;P_q z0u~(be$;QVmfu22P_84w9mt-`$IcGPE$~(<8QEjTIX=_=v~kqYW$V~wr{=UFN*4L- z?&xzR$B@WYflazkP#xNVm#`dmWFfhZ+kzLRX!5q2`# zn5yLsY6}&+EnWngtmNtKm?qj)w%HIJ^<=?nTqT_8lfy}xYS{sAb?4=`ol|Q?!9F%2 zYEmi+A`1u}D^hO#c8@9+CJO{ED^~AYnoP7swrh>jz<<&bzi__3zWR#s9;Dh{960}k zV|7}1y(xGl$VMxu%)C*Ze5?Y3kp!uB74$KT8}YJYC;c_lN808FzNumQC>2s!oBOT% zaFTJEa5`;l_x+$~cot`iVeY&rX!y)COlIyp9M1KuF2ixf(ByAbvD^ZwqJpgFXGpk1nNRSq8HzeLVo?IkXH80&-Iu z!d`}Fl%aGU-V@`ZmT4id`85I;G3!YCa=Gl`O*{RUWL} zTClRb6q8;Vy1n$4p?#DXHWo=7p5Y{2G|WVgl)7NM{jas47!4qE50XfuWU;UWlitkW zn<-{{^=O9X!rPrX*`#KmlA-z5&Id(mk2M-XMCLIMx_BC2KwUEel*777p{})&?R~O( zl(1oU&CdBb^QS|s+d~e2he*Kj%s_f+CVk_m4gYsA!F;%kZpUWNy?9wb+Jq`xB$-mj zX!;T`i{(l5NhW|&$bC0o%nbO|znKmd=&8y${Rvk9qkPPWzO_1lXgrU^#|iu`S|dXF zx5;b3DN2VMcnI?;rW-|dZ?+}0DlIo(kgUXzvbHCWso*cd0n~9%=?bNHd#6mHwm*^A z^>nQ>B3%hKp9-b;sP7G3ia1c{D}AqFKpG{ zX69HL2;QRzyQ|0%Rl$UP5j(p5uz>|F8JoZJ%#8xrg|eFgW7RDPr}5=1aCf~YWT)hA zsTbb{hkv$e^6?O#METNQr%hj^Q}1|gx7*>k1Y`a4_>Kn|K|OaT1_t(Al`a~~<&<+~l_3C!gWM@zCdR71!42nB9Q;p~auZ!#jEbHc%K30b?ZkD1MPkW{ z<-FR$lE%^VOQU=R%s*8DH+G7vdW-CqooMt);|TKh6jH=kKs@-Z|a z&Rue^OASpvxsjW@c*G1FJCPV@xbW;DWP>!|ZPA2++f1L&-8_)7>hJJhu!eVKQcF{a zJw9|==W4;q%>-4r4256+B-NcHG`Uo80T$v#ww0qZKJhJ^iCUyH*7R4Vpfl8{)N8_) zAK6rqo)bISQmR=7cyGv6U?I6?hKYK8iljH=OPuq_uF3u?*jdTvF@7~nd>{py(%$lb zPbC%pbj3*$<98oeLuwVvCM>izm@X*NX_^NMudLztDaYBgX0P2pefBZ0Gh?&uBa>sZ zv?k0iERjTfi&{*?Ck6r@=3?Z@_7K3+)nenW7$Dp-Sy7RA#YzxjBcW5VSuUTO=>ihP zD%4wK+2+>2;)_^>z?)54&huHai^JXkzPGvQxVNO%&!d14mHAu5E$$xRSYI6H?Ofs$ z)IaW+4{KMwN1snO7KAvRVqezKTyXvPKr)+(FMKEu>6kX9{HTl$8hny&u|bFXp-(WFI8tU94ayy5r307dHhyG_ zUIi*G9_=u#uSuLu`F)1TH{hRvGi9PYMYM@%_-O=K z0}Ly~f6>*2>zSDLYuOV#y@=F#Rh`TG_jw>V$usE%rb|v@Cgj= zKw%Iq!&n29Q(Q?7miHV)xt+LNXVV98D|dmj0IdqjPan)|a7I6vu$}9cql@jr;A4GG zUsYbWQOUuv2AEzBN%ls!_iZA+2?1k+#7@b7l^}BKdS*d(^;dl+L;kY}T_l6!guW8o z>Z6DQi$9D2vEEtuM`j)31p)hrT2byH!4G&cqrJ=pRegP3{@s(12x8Bi#LwI<`mAkz zzDlq$H}MhsyFge`wvI*x^?7tPP!@dzNRd&l`g-*Rhd$%xvQF4IL6lVUI=n&mZ^Wcd zNy*gwI$&jB&Q#(cVDg_HD0AwK6EOP!ZH5Nb|G3IBGqH31k8bF)&QCX#4e3vA?WskP zt52^a6jkT=F?JIQArKi9a#7HC>P_>8`}@>7iyTzvdbazkx|=RPeJ7tQ@xNzux9=vi zNrqhdTn7CDO4tB~UOnG0``1Y+4LXsvmse@08Xu>Qmz~^ghTFZ#(aDQv(;s7t z*<5<{_M!XQAMT#y>)_qTs90?hV?Xu|a}YFkQjNHh*>Dc2+7xl6asVZT#QA9)sm5dx z%BDRw?UTargl>$PmxF9pIRNOSjBwok^n~d!OwEOqlY?O++(vcFM&=nW0?nj=Q5=;; zQOq(-R#~umL36t7-@7<*Xp1g3piDCui$&zXKt0|*K|Wwp>2m9StP6Pty{yFCA?>E5 z0~fV4;ho72H)7rV-)&iqUUNzW)JlboIyDt}N8O-bR8gpAc!~NX2tX`(B#uQy1`(qS zmU~0Y8MPiqBqQX5<{jpXO0TFwu^o!XaY{(vZ5OY*)&;bLDgJS3-o@Q8Nat9;{)qv{CPbRS&FEIz2 zp?LyN835f6uK~*Vbp*nEtk52hhd@r#o&>*GjrCU0%EAtTH1i^ek2BcPW_~mc6Vyi{}en|Th z_m;n>&=@u~I-eZ-BecvIsNa4V8%S4)GQc0{D+ZR?yi^0uDCNhO^_SP=CJG&bW2yxF~7R}Bv38;KAG;@MQ* zkKJkqO##Ak#d|5)CIUYuVj8-#JJIuQ96pgcsflDhm8;bcg%EtdXrbl!VGg?fs?wAn z?1*%CX8G1r*g+lGQo79GMV%;5OugLC7P3B9-8!q<0tmhTH)XEQJWR>y+vf1>*B>Ip z$~(+=&FbYFsVp8Es4etsbo3kv)pYMeH<*t2r1ze0@NjQ`4%@*?3R{0ka=O25+o>vj zTb_W&k7?XB?7epM?5x=I#13PV+5a@e!Qmpv1(I~w57tlRCH@)2WF!6C{u`8(zGz{L zw;Up%2as*%X0&`Y8NuHLy+z~FYKu)eHh_M=O7(#sN~!Wh>2h>Bu&4$#ElFdXA{Niw zZj9DGqOGJ>zsS4X?itEPXI4`mSXDbh?>qt-p3<%#*H(f9J(s_ts)f`OtC?w6DRWV>}R^lRER3IR;lv%jzOC* zAca2DY{m?-27SSWj&2sD$N*-u^k%-upxiy3^Rn0|av%sjuQN6VigEOQ&37Vd$JwIM znRyLQI%W2kjzM<%d#deMv}uFptJvn*KjeJq=%}b$2WSgLqlJ7D)#ngJ5V1AaRE%H6!huGS(Y?y?mJlN)3fzO^Z)3Q~l~lb*j0=@*4W(yp$a zrm2sVL z^&w*2sFS-^b>NqOHM-k7#Wg2>rWYk@ah+`nJBaF$%eQ>vSXq=xHIjxX1A-5tP=B9K z)71KRu7c&vjr(Lr&5R!+w>u{CViJ#S4H7VoZLOKgxqE*$qNkTXmnO>LH8L8;b)9MC4jdK00VXT6(HdwQ~{K+HlaJAC;FM%Q_c{JQsO;V$-&H2ygsc4>|r zD_JUnAfB`*k;*hk$FrG{( z5V?bcty!c+Ga>JTE3|B?h)s`o&2Nnxp9Pm)MdJMYBG~5P<}ugv%7$sIzGsn{M-+x7krjjfq36h=U@*W3P0y1`wb!&m8i_P6~0YOkZw+m01>CvOz}&+Oa>>a*X1 zkKsxO$|s%r*Kwsbb~3lB#$|E)-%1PU#OI~Lt%w|#FW|0SoSRg!_W#e^g{u{@1Gw%N zfQ5;T?SCXM{|%Gx;%E806p9u^)+6@5O9*t_+x?eNoK)Q9H>iwOgPb<^mK)jnzb!I& zQ&Z_K^vJ5gjySKWyMkqS>IMhX- zO;v#Z@SM&5b+!6eEofK?=WU}=aoI)ZeOehc2}RO69QMIJFHxHX;jf^Sy-779va6njA+F$E6? z=*WFyEtk}Yko~qX+_v@HhPbee&5L>j@<fbk$GDda`Kp7?=@$}Y35N$*kxh$KmE7>Dr6)Db6O-f0z)!a=9^S5yFu)go_#>#fTVW#Hu$tfz?x}t|E5O}NsNQ7&(aDR zldZ}}y1TJ$$zfJwffafNvdPpaWZbB#_C!vcV~dHI{gshr#}?T^YF_4tu*Qt5fWF8h zV)lFQQ09%?)oV83z`02-yGtPgAfPCbRMwa!3|iAz76&oR*<{%P@TU9cnh_=gqqt5!D-gFwRl{{HP2K%F6iCiDXaR*+IE;X8nj z9)n`pSo3HR*odlLU(=0tW+nYk)l3R6lnq&~b5{n4HxyTu|2>27s zTY_lxA*A{YmnV~BeX$taR;MmG!l~8^w5&$~BEV6jSJl*xO z*Mv1xEK6#13AACDE1obCOBCaYgwQ6@C@D1KMwR@4gsF0YqE<4*sMM!PE|qmAFOCEP zbstNeN|M#wLLxw=>P7`X)ICD_iT?S>Ttf(ouaeVk;=MHqVGvl(xCW8my0X#WB;D^Q z1j;m5e~Y)NT8uiqi=x^)HzKJSxVkzr%+Z)fc?rS;H@U$>=D>tRTd)vV@`lA5i-tmH zPf-2tR|16Pq}kSdmt}u(udtE^ho<7WAk0P3(#I-wM#P34Z0rso_dTkf*b8?pk1>?uZXqZjG((RgKrx&VE6Cu5 z8fkzX-A`0(C|lxl;D%t}u54Q1_Xy#FEDMtUAjdR^*3IC=Sa3qCVMMa!j216`k6Oo4`4nb{$@hn~lZG|V=ml-xxdzLWL}>u3UiniQ2JatO*x<;}3SHq9>21&k7f=0uCK@QiBt(auXCoB`)Tm+%g%upL%7y;yJ06O9! z!N}0=tC$slSa3$ndd~_IYq1>ov@1hUXH&nT^pnd&&`7>;>czRYzBNWY!T$pc%(1YF z_JHob(x0wIAemRS|I~qj#@ULBAP+cLa|_LZC$I1Yy2CDPFzwnX0j=p(`q$|uI)!%s z&sLf^KV|3Jo9@Xe#sjaa8if1JUYtKRlki47W#2vdXwX#NW}{+Z9$kKCZ!L`q(Qz%Y zOBc+rD6PI&D)`2eg&K4#!+@Ss#!FMvd1VtMdTiQ0~u-$XS*gq1eU zI;(&H*!Mg?GWV$+RQHzw*fMj6#trWyv?(oL9=EwL{5WgOE@1YSx0r>ktR4E!^de3EtO(Vm13NW zV2xdTHn4pQBS3NrUaRLkX&1tZ%XN)_3luwEaZVJ&y^Tfx$pc=g6JSzX=E zJzA>m@t*L;fb6gOWd8f7cbVMt+l>?{V1h}3eZJoh<634G&Ga*eiAki`Zk*X=x!rU( zATrM(Q`gneoR(N;mugn|`>zSuk)N2NNms(=Y#lShZh4(>#qjZuUMO+WI&Q#3J7-vx zX$9?){tk-6+Dwj#i7B5ne!S;Vyf#*#(fq+rBL^<8)Hho(r9R}wOnG44a-n!!fGoGt za2Qjf5gEu8IFMWXiKJ8JAQKN^MVF|a4~DCRB-o5XWw+$hnbu9kH95`16xfVkeoGniw;&8;55*OR3bdDu&@2ZD ztXpRUD2Q=I} z+j&wj7Q583;~L2gj7y(LTh}kEXaXN=)ro#f=Ab71NJ9$vlp4zDsZG5lwE^#XS_ilq6%t1B-Xw539mlmM!R zseSJV40a#XfgS1`$mJ711VN%Od{fDF^1Lb&cS0sq1h+suOr%WdyVqpeb>qu4v*rEb zs8}}(WWWv?xchVOq#DrjJ}ksmPHgk~mf1ZD!r2{=-TiL&8>1WW`F#I@cz(MF@S@5v z@2BNryP;%$ko}QH5N2PiE4DxJEa<}tXkIYUhdSv)6ez<*DooT@0*3c#&jR8h>lQbg zhGFdqPz0LiTn10Ewew+dHubWb7V!z(!p^a^10%}k(3>*aN+^TgPd^h_k%Kv({ya+l zMf*Z_KNv=T#K#9H>^}L*&e=Dj1h!C}X!&X*6eeJt&d%-vJP4sBPkXBc8@Kme!&-{4}ciYH9{Sz`dk1)X?&%L5@=Fc`bH+tA7M=4 z=sc10Qtipnz5h(SzFJL*lZ}z*(+h`qV^0h$V`nYnkKBZ7>MR6HaBEA*Z&<9SxY&Xve2{{5$1amHB#*>lem~|QY#~3?RBwSwHNb@a6Km*)LG}C zsk!MIz?q|}*%?#Lyi*ozNPU8LWG>Cw8R}xnzb6Jr4X6h`_|7*=1SzOVs$u+5e6Yea zE|O+Ym9?5g9xkS~qFjhu-zrfj-?v6!RZ`NnWHZ&9EN(hl4znmdjMs>S!ZBwe_%6Ns zAz-;miIM8t91wy!W)syzBlz>T3HGCxnlb*`!<{;60CFS)G>eZ!ck3V60JC7EV1-Iv z1Eyerb1moM@r1qt2kj7>s)%)mqID53OD_Cub%l`im6imDijqkeiDTDA7KaS{E_*BJ z`)qphkNkqOW%+J$oP6w4JsXqF4xswVjl_h0&YFcUSO-vB*nL|CkqSE{`g-UuANIRi zs5^5lHkv+PGftX_zhKD$MX{50p_QMNwH&|8>d zq`gHq?`Y9# zf&J)=k8N!&dGo;>i9f>m)3^d-MBS=#7;K%DbsyX1u*HeCMus@EYZzARH&iB2^knz| zMO~6p3L2OX%zdIIT~BAH5*L{djj|ECo})4Te*|oDq*+|*N`2vzA8Tatg$&q|TBGO+ z)$pGkB6;WYSj?z!CBzLORIPCBNGH^Hks6jpq8e(44=!|(eL%|J7N zfSP1`TIl!DZO!EIph$DGt@N(7)$_IhHkl&IiKiQc{6Ud$q?0{ia`|l>>)F6q)8gO1CWf*W|*T$hMw@>ox83_B&5`!T@TAf9MUA zRufP4uV!hV5$=@|uICX*-Z}J;n|E#$tg#I}aC3u(@^l5CYZGNkCc^S13X-trvjjSh zZc}{;7n8_~YXySE2TYh437L$_Ogji-^wmsyysA0?1W){N{J3%$bV%obb15>$Aa|lx zCMCR4%Ot0uU!)0U_>_TszcmKueq7x+a*SWkExscwRked{4 zxd9Iv_#}+4BM~{MPK-oP&sWJb3(t^jq8Q8keEfx)K9>3%v7Ib?Bnq%j;q@!{F(@TU zE`edR{=k$b$YM>g6nBw(f<+5R&t>B#JMR`xwpYWRz(hIqg zB178Ty6Th$-Xi51J*!z`;gF^bt|6EAr`^kFI%;aw2eIONq_r2jRMfuSklLROJaGE7 z&Z9-;`DJJTmfK;(4;(;Mr(T%T3Y>C<8Z{cR$%_hBWfNEmqHN}!tlO_Eym9HREglF6 zs6R0mXfa9Q{H~&xVWxMvb=tPAk#KFOLmMli5Tej(Kj1NAepWNF0aa3EO=Nh`U@865 zsFSj&(N0~kgKrSYczrb@!XbX-+7f~|rx)~&F`JEKVrfkqL4f-#soi zTsZfe8Z2|r3NIm(x!`d#)HQb`#+Y1C{iB4)9whLqQER=K@Zd>t96jkxb$r@Q?GVd)`FUleGmXfryMdB^D%#)6Z@y24G4(N zl3D6WwV9>NhaJYXfTr(p8Xfm=wJ45><_!NdY4#PM!(%13{@1$x9VH|o=n3a_M4aQ8 zyWYV0ogoeNBZ@xL9H*M9>(alY)Ij2lAxtMt00bp?(#59OW$w`{v>`=_vp+ZwxZML< z=lSB`kyGOHiVDpu4HxbuGJJ7V*#CYkBJqgt9|-1g=`SuH-S#YH;c@iHm0blP=>ZYJ zSBC@$l2GsdR4qm!AGo32Lb{niys3~_lLFhZ5N?z?y@$@<5S96{N~xAp7D81X$L3*w zMuD2s0q~^xtLjuDv&mm;mY!Um&?OES(Pkj#<0V#*TadX;qXLuRuYWapEh0xXvJJ~K zc2{hj$)0K7Jvpy=coYxOIg$9w8>3E;vQf}x;>17i^O@(L%D**(ADiB{+Muf}!%J!U z11*?*UCQ1xRTUHlYPSEU{e->oBE@?}wfZAV0h_^qENE13eLc0QvtxI)WL_1ZadTmj zz-7rur;t;jl>CFXNn&&zMUR(vGAN!IuTH>R1Io(BM9AtdB?iAQDn^*QkP2j2>TSS! z($rypXE=>gF-=qIM#Ut*4J9R+`w zm_iLzXsN^})Zp%wiA>?a=?Vq2gx15lH+M?-`V=tenREhK6ZZOq=ei#&eep5AN z2NWH_%d(N1iNVS{qs)q>Wuo?cx#Gjk1=7oXtqv8P@nQ)+?RG}d&H#tmm-APRn2%(k z;@=M0E9Nb1hMu1`dYz1v=uDe#<^cveILaE>w+<^9Ot<|_ac{pey?^<%U9~c?6=F_8 z)57@}*B~X12Ob7&p~;#8dNZjEt7J5=5Yz57Qp|%K$QX&(0_#sY51&nn>5FsDiigrA zr+MDIZ5q;(mv_1S!w!p;Pj6XR!0Qh>R*8j^fUOsUD*i+s!aA08cGGfJpXcuUGqF9l z5^}%6^VC~ol z+lCdf-joZ<(qcHEx~p<$zIrTjWfO@hTnReLpOTp?^wCxST6^g+;fdUd7wzf zdwOn=x&pLkgs1k4SA$G_4;x6=QDmcQQfS*u|oDGjdiUC_Lx@DuFw<$ zZ=vDZJ0p!)TBALlNSHd#L@g0@uL{hjZ$uEENRx4uhg$jx@S6=(RLhdRoPvb%XtDY! zNs6?qi98-a{&j_WstU64MN9jwaJ+P8*V!XbYu26sctADR{bz^D#>SH?mbjuU&V^=1 zdNv3uh#}*?I?4V?^Q&)ne4@v>Xzoon@ zQznd@`=q*+cgi-z4~=iT{GVHxKXkUJj^^@yHS4GM&VJn2n7SQ!qK>(x>3&!uqHGFu zO>I2*-v_8?uRZMfoNbW`JySu@U^e${+XDobZUxj3rGo70Ip9s8XV zyR5C2E-(2ck?>KMp6Uj7LuPXN2;=^=Pik2Au?fSBlRD(P*;m?pN$oCagG*8^@!H52YAyJqpm_aRRS+jNP;a|E`8*m^eW z1wre}n<6=2pEFUpdVe1Zb2QrMBD9wh#L085xu%DAdHrbHYxL9s!t3ruXh9~kWjBslXKIR}|hibh1x;1|`N|LXWij$FcR9Y&uRm0!J= z)v0)t3Wr+C{lQGzjJ>V-LEXPD%kuaq=nUpDw_#A$e^Y>|Nd34$zoC*BcF&O1lO^hh zNBhlU3tILld$0`<0rNMNwgZsV89|2)({DiM%8oTI=9u|Z`KtrAT?*n8muvw?3j;+$ zC+^TfFSg9IAlKQ{EHx=!PrQZY7#d2#!K4e}ddP}a+qPTqzT}r$byjaC6 z@Y%ehieB8UnY80jP2)pn7gH-r-S2sNvc9zHIA#6DJMLj+U35p|qYf3S^XzY;t97nh^vduOHLv~SSLp=Jd%S0}${y5wQH)8qK)zw{ zhppaP=paVb#A8|0VxzIy+Ev$_cX!IAoh9i^DO_3=;igqe})|H@!lxKB+O~-{V2?QURzmz8; zGL&ECC{>~qH>6GxTj0V*&2f|vH-=GK@u8!AXLG$ing*POuJ3NQ@81vFe|af6j}8PJ z(ed$4>O*_Iyxrj^)>Q-CKX0px-7v-Q6PVsWZI>YDb2^tSGNK?+|Kyy%_P|>#+#Lgk zKYU@&{OxN@=7#Vcg2QGuMF8a%4`SLPYtuFLDXKb3p!mxlq!o7t!I-4B( z_#;c8N~~xc2RAK}7bV=ynFUiJ?gk!3kpM zF*yvSB@tishOqs?mUVWI@igUrtrUd3HAQs25H;tC9zgKPv?=H&g;Gf~n27=S72&3C zXGHyRo3~5O*hmP#w@vKz`P*s(*WAq-`z$t07!0jr2P3Eu&Vo%K#J{V&D42{Vq(mmR zz|eZ~gcv=94525tJ`Wfi@4!;jD#6J0j_b@n9NDZ_^dNa66P1a^i4ztS3zmvYi&+|7 z^ltSJ8FhAjUG%j3&3-R;8>|9GgYxCSu?^~2AMC!D!}BW^8zFIYiAijbV950^!~TiU z#42EWiQIvizRH$l_kZCN^x1?P@HP~36x4Z|F7p@v{xTJHjZnP{tGHk|>tHp4A!gbj ztUD-_Z5<|CR+HwX(&=ZGW61t>!_*@Zj53U^!kN0f1@~*%`yrpzKr0(}9#jR&G3#e6{k7u0z8MwqTEq zCR@HOLBP=%LqB3-QD!BF4T~T@`%cMb%(!q5}>; zG)_GtXrA+s^cI`fcDMo@ED$n+(B%%OAiQXZ8tfc8+IL3_?Y2!YD^%aIfK0X%KKF9I zO$81qy|A|_sE+>-<;|P?Y2^e`{1UmY^NE_q@W$5l%7a%E@pSwKa@&`cewkT;qs_)n zwaSU+=0kc%wvjIQ8TjT|@R3fAK_;$a9-1u!5(K9*`-5oBFmVMCH^X?oMdR-Rw$^i& z#rA@Pj+HG(#d^$F@b&#=M!cQ`k_HM_(N#1VANH{yF2O^mG@;;rZ?rrjo`Lq~ewJfAQv6weRk~R9#X8ReZCjHZ7lX~)`I<%Fb z8wZKTjWi?Dp)2yeHM4jZvTt9C56CWj=Yr_9tl+uI2s>Og4PBhWx0Xp?OXmv!_S(xb%_1etLK`Y)`U1k71oWLdHPN61w^3~qG^#C`R zRoYxDrnrliu4Lb4`Q1$Xp(mX1Tx^R!li@1jGcsRbY2a~qlxYu&OSfhrIfi82IsG6s zm?GgwqtLcy`{LN*!rUdt9bWHdy>B2WkLTFHz7xUpDfM@}N2yW|Mt4*ke3|$#XBWhF zD1Q0RV^M&Jns#S*{xBM>-%Om1`&*dKD0E@+r+rZo@(*W1FA1^j+^@}W*D|7C7FZmh z*R3mWkE%vWB=azDMS5|c{y910pR%k*?xUc!^#kCJ*6ZN18y}iaGlCd5(w7NAOZZc# z7~BUry<^=Tk^)W%8FYyIRfockQ!BmFQ%w^xI2!oY@T=xcJIBSrBnVe-J85BqsOH4V0nNGEf1f zMkoPvjA&{ov1HfD{Trg{$W#)M%oIUdLa@yei3%igZ{wOGl}RHQ9`4K>fLg5-ImR^f z66=Vp^CP6sl$Qp|eh^tBtinkDV40y5mP-^g=3(X3L|w#Gy(V^5h8w{a*zd%5z#;Le?wnJMosIgCkhk>KehP=A``v zaeQ&mhb)2uo9<$iqx?z%mlQ5oUAW;K+dYxt-D+3IFi~&y_UgY=NIZ*L-evtZ}k3jAzFfKh*rlsHnhUtkMwTQg-9ppHKp$xO__;ifYnk5Ke~aGZxvm__N0F&lx$q9}A9{_}E` z4*Z9WSl$7PxG;47+K*?QVsR)Y1qHKD){3 z1=AB(1c>jFmyv)g+N$N(^=z7TBsVHJU|C)?N^_$rnqfZ|Us9a$Xf@lZ0Kb zk@v+t(XE${WU>!Gf*L-WoeI^zLyty5GM>EQo+qnMAUiPCC4C9GL4e&lx&md5!&Y7N zB(cszw;>(@sQEie4~n#!yU$ReOwu4TMQI6z5@n`2)>lFmwJg5{Hly*0iq;r)cj3X+ zuC=55AeY3zV*r-_nal4a&ay5jW7*U|-QTF>_yK)t1{wytL_(^mCG%zt zJ;cb_LTiU*JaE?{=d{+_GP^ME&hW_{m%2jgLZfyef%mjiQGp}IDr4Vuff)J=DHXT8 zj0!#vKyO}P7-KJDKIdIo#m}@DLU(DjBE8cemP+U?IH}_SlB*$5PbCjBwG+cfejF3> zcrBeB z5}6C4zU5Sb8#p$cb2cAc(?dipeO3_gLp{HD0q%n}rv~ED1?@-dFS3lfbjDW|JdIy- z=craqqAP-L6D%A}qU3%*o^GF+pQ@3ij<5-H`R9KuMhGhYwG3eNWJ73$G%jlM!2Sh- zmt%#_`=@96>|7A7SUsdnFn1J}%IE!Q60M7qFf|LUM`wrmYsC}%uXE1H(X+FMGoKx} z9AHw2ZNi%C%j8|hzSAy>2x`dst16rsr>H9rrrStZ7Ob1H2th&G-)!5-(4TUBUlMiX zj}qiY+(|U}ychl>^|wdU#y|ZW2@X8B{D^7JxF{b(%d|lk44js)mIVyc0(Tunk20P${_k z?8U>AUV$w<7*~QR8r@otrI9TE{;H{v7bZCy9NWdzg?AqagRFyB&iOft!}n95&HgcT ziuf(c6Td)&M^Kf7HyGVIxHpkk4?jEeen@5NM~;EG5<4tni?4=M_~tLYy-z0<13Z+M zN2u*QIvqv3jIo3!h%_`p>>psO{!R(YutvQMkhjE3|K+WrJipX<*95f7QX5l{;S75k zcx;kmGO}SJZXkfXNiDxncBETzZ+bC9BP5)MAhoj}!me}mWB;>G?lZ1FBj~QkTM}Um zd+Go0(*PGn^`#VK>3;#3t5&_4R%Fwoh2P8g@~pOd&!&-(de|tLKy5uNaXM+UzpmO} z7bKW*vMP}GGyTnqV4=RIzLCnOg~0+ytI`(spq@w;tSb^blv(y6u2S6!dG)_Gc3U2_ zB%~ObupAcY&x04r277w{uF1{UZs%Q_%tR=v`@e$b)K{&{0Sj75rsL&a3C0_VZ-L7P z2N@p-saGwzlDEYL+S3d6^YR^D%(8W)IK9Yz?sgM2MaY1fMlG zMYrhjLHWtb+-6VTjTNu$9DM1--3pH4J#@+ThTN%HHGH0%Kc)H6{x%vc%k`nldD0<| zxgHevJ4-t;oL^)fxdZI>>)0O+pKHf0?Rw}A5hTNuQ3VyRz?K_B&%l*_GGMOfED)f0 zr#jsTuvicuO5HgpyT9W$InTVgp@iMLK(XDb9wpc@!|B7UZ-EaQ&(q8_(z(L0jqr#{ zj48B9G!PVLtW+>S8T$F{i3M*%)`y8sUT&$~Q5lP;Dwr1n>m+z?iAX2?)y(Q5G(8en3Pl|YMp5ekXu|zvux}y%GZeBm488DCp`9YOqRvt} zXmL$tr&}|R(T1Oa>{Lg1T`pWF&r3#S?{Qzq@A`-efr|S?f0%$^7mdpYp3b*Jfx~RO zvaLr~SMf3lbtbG3%yw--h(xIT*!B#Hht@{|q%Yf(FT3TMY;s@jv@cu2;|OZ%$6vVt zfkk_tK#y-GKpo)KhVw-dZNGeQi)1k({y1yN>`qVbR^n1`N?xZ0@)bwoe5*;%`E%j` zLgiQBfqqDxGnL&BePOpkUB*`TpDTaMLrmSk=&gk@lW}uyXO{fx#LG&d=)~&^bhRS) z{&sSxMOE^6DIf-Eb27T?n(t&ljK4Ma14d9VSu$_)QjDKn*d3zcI&c)TZg}}v$%CdQ z?N%}i;1TA|7t!JGvBLo~c{qUzj$|%{tZRNAs6!>+%Z4Fi7x+&Je9#!?FvMr&ui%-3 zHf~N$?BAnayOjm#mpWG-zmMV+*FG5IX*Tma8rQs_7R+>~uyc^eviE<(G%e$V6%*)yP z=IiU=P15rja4=kK+ijYR|F!47BZy;PtEJ1XxaRr*3T+HbgoW|wE62^ z2QOCBkp*$kKW9Uj)72SzH}=TY>l?s_i$ku&=+e~K@L-ef;_3-`H}a!or-cGD8>oR2 z$Bx$UwSNJ;73NmScP6K0WoyQz3+I-VcBO3kFuVrKd>%gC`jbeWsU$G>4s z&-wrYT#Y52uJ`)_Ag!D6Z90IFl*LejJ)puP>2kXKjaUn71OKbqgHG2V^SV0NekjGm zWV`ifv)9_{XnQoT%RSUhHUmK2J95s@U(pC0fC z@AQ5Qj23o|bFn(k+~$sfb1sE1&eSs`PXu`G3U+%!K|WgH0}PtxZaS7J^42RF^@2R9 zaSDt-b6BPJXF-c`v+o8H>#*nbA|sm9@=SDtX8omH^vcwe`uVLpWR5d~dpB5`it#yu zxy**%bttF@sZtJ8%qWJbP9=fj9XOY7(W_#T22F53)Y3+TTLT&v&_4iUHF@$TS|@r*Q^Nv;->;k0X#?<^^6be8SBf&pR?hinjO*VP5dPwARHCTsG zrZM|Jk0|sBEtc7_<`oK|oeEWB6~;SAgVc)sta8B^ST`3b6$%Jq@)VsL?-*p-)FPDPoSG=8 zGVxAs?tMEr0z7$RjJa4UMF5~Hpq|?i@?$*$O*O-?@V7a%m3|*c1QK2cfkbC<+>Q8j zI#2~t*aoVC{=6}M$siQXD)>&YAf@i-agAtg6OekhI5JIy$cktE2@(5w^-G`($a@e4 z1aa{QU^t@`VA2h0S$$;!zc+dA2%)3iAxtwJ{pbqVV=^it`ju1@QvtKLIp1)ulA$PF zE-foR4tr`(F5}?@oBQDd0YnRWQL+l*S{&NAWP)WraMCD!Hp6{5BzT5G>#0cLVz}iwZdRX6t!-k6vVe}O z$Ve;&ZS0%`^tM}zPP0ALXSlv6vEVhTSIH8j!rK7zq!&6}FhF1g367LAAtf8*Bex%H z0kgqS*qyrJix}?3bCQL!%yg2pFQ-e|7srkwk}vvw}rj@#v8 z-ko$9#0TkZ2tZY-wExx}kftgu#zWbkYkNj}l34AIT|J()Sr^=CRlUUG7q@q&RNcbq zu9{AQ&>`hy(3Ubg0VZ>yUfGWA8W2%}ByJpj_-J;V7~@ogp6K)VW3-Yjt_y3NgAHdN z0f&W^V=r-T%KFMH3#&s(!$PREr_{yHgtdOmIq{vJ1mI;2Qb=(pRe4PRVcmHB(RDs6 z?;s@-{XBN0!_1TOQnbIA()<^Pe;qI7SW0!vu6YXXs*dTwpDom-kt1~$C9Jb^`WZR5 z(TPg8xh6VDpbN7GC1*Y*@n(KG(lE!))@3$u^o>k`Hd>I0?8IT4L|XQXh$3W_9Tnv@ z&?O+b2#~_fVQ7JIG>Pdi)2cF5ZBhY4mqZhA0Rq+xQJU5;9A8BViCGM=3Z@zpu_UK& z+y)Rpq?l`dQ_feY`CGaj=81DKq7ELSwHm~Oea^%B9&rsM6hEC=?#*wiA5cYXok9*` z^}s%$g>OQ!QzP`Nz2OodLh0RMN6^vprKiL7WwH7~vq270YyP zd+tE~!BM_oA=`toYtgbG-oD*U2b95gdorDCt=*dHm_3m|lkUL0JrWfshH%;9Wxpj5 z!39N<8GUe)lZZ4@SS%GArn!Z-O9n(2C`i*h(abXEy z!qQWgu}Aimfb*#`iJvd@eaSHlC?)O}31~&&Qd@LkhG0X{*D}}xbHaV(2TAA5mjvQ~ z%uFUAGb>n9q+V>M8LEnkls3Q_ys!c}Qv`ik^(AmLjU0Y2hN z8VQZqcV&(l=J3D?~l%fH<0w1d?9ePQ>OhU6{j_lno7Yz(w=mD+`>Eo}qkQP7Zn-8eo{Xggq#Q?Z zcZqO^JVt1LLY@2T0mX_qN_h!uM5ZJ)B3{lBvGZCZ&s*bZvPT3Fd=qJ>fPzn>qnMb2 z*4)u>lSJG#k#qwT|#j9w|To=pwPPAH-5*d$CYjs_nY{h`M(A5aewx@>ZEy6 zrs`Fvd;wh*(yTNeEjGpm3ftbg_z{xm-g(8V=)_7fi!kEQd}Yv}|2Qo3L~zE-CV|e( z?Xz-~4r)*FGx57#D0G?vh9e5C%nVB~%_o6{1ut|fgE>;r#Uzt$1$ai~`EZm7n*748 z|B(wNsfklXfr=N5sPLnV2P8Lqfz;Z$zU5d+-}iehR60HFnvYE~}Hpz0h9Z z3}dUGFv(1$K5k9^7?5Zb3{h+EM)PYgorLyQtP~Gw=@oJP3(|6%MorSTmX_)1lKe7E z3o7@w>9xzRsi0W~$<}u4Eh1lJ4)!0uGP&*qS3)){QsnV^T>Hmz|7#keAsb*Z=*rB) zuFJhpN^68Y*9_LUNK(m6ZN7u@+*ZO`{~7~S02p88w1MJ{*gCA6_Z~kK|{3-@od3_c$7U|zZFiPzihiHW0 z1Ca&Bq?tPvse$87UP^<_U|dw6DNuZ`pZ$yP^UWBZKSkGZpa}vGNll*-)&;Do38?@I zi$#A}O#^5>=Q8ItK z?6H2Yo6hukl`ZzX&7El^oaV~8K826JwM#UV*+aWMl1%_5PMBD9D3-}CGEN*ZtAGE1 za&-JXUz$QIQ_T%6#D-YXEBtnFvnek;c#OV#WV6^WtDH3225^9!`{hI)s1^VX3-ZoJ zvDI0!#;}E1#*Cl*?x`8w@_Vr>i8wk5$B~M5%Y+$>4f}5tLL!74^HyC4HAtW2{IOWw zjEI;SNep(8xrH6b$v0_PHvP6_bf@bQMQi3M%_bBsU!~W2Sc0E0GtMjJG%;M&A|y04`snVCgwYg_c}LZ{5)~bNekYW=bZJ9 zoc2Vz)LT~<)^#q%ZZaKg<+cjnRWaJ}{_>dz>(R$yAD0!0{BoA}1smttnKY`KchM!D zvfIh8+b`~vMDIht^;5tmJtJSwuJtX~r72Aj9+9K2%t33)E^8nPjmLmU>p|4g;(miJ zsajXfr*B(V7OEplKZINLSJc__J>7DJ%&F4WG6#YJYt-D3GX;Tqdm2dsBUtyE(-9S| z)^qG)`!p~4?5pn?+jFtPlI&;4vX}|Pes=Ol8=?~{K(#mt?-g)R6sm;~-%OEQPgPaK z!D~55TF;1l{cye&0IVr3*qPz%#)CHTH6m+A?cPe&d^1l(0N<(0GaK6B5Jvl6P~rdp z-KPphF5$TH?K1J$F9`x(hAxt}!O`pLM_+2djp%g^q>r7(5Xrf!0aaLG4o(3HsXgsc zIIi}M9cd7!!UQ;$LzaCmsK85#bFGAE<5t*kVG`?K=nL66fA6VDfq2XYs<8Pn=F`5v zFZy>hl8<@}pqmXFq#?V%4Yx#=^F3b*fV$U9Ww>%MkjOxv3aOPQrTj+*ESU4)ZZrW_ zg$&cESVwJ;Fru~b!uBJHrLHeleGC*m7P{6(n=_Sy0C4&SQ;)$|!*LwiSs+!#QYdaX zizoJtwy*!aiN*2Ny*OST%1m=#8L7`qyExmTBrIu!i5D2&xb9H(d7WUkgd6FxfT^Dx zKLmw^OoN2y>li52P_2R{^Q*f~{MUD$tSYg?S)WB6gBvNh36illQGDQ3`o<}0!!oMo zC4*y(nJ^z%FwKwy^@K__@a}}hdhY7@)`Cda()r=`6aYMo&JIXk!vp#65=@==Apcgm zu>NNdMSHc1q#53;TX%LESZk>ZNWdqR%kd*a&&QJ=9a7+D&(s&_td2sd%s1aNYp@Ca zElEv7Jgh)1Zlnlf_wysF?aO?e_8T^HaD;&q2o0?xNaEoEIZ z*}p*)J7-UkQMwGx=)~$IpUW?vnZ*K(tk?MnC;H1-DEdOlbtp$3r<$gVQOt!gI74bS z8GhYPP!KDZ6dD3S2hDWkb3Le3;<>2h;*C?^DwAPAA4F1&OAV8Y^S{?XTOx8Ds6c|P z{8T>{Fg@q&Lt+GfG<~|7rc)}3{Pr?*9KGE`0efFx@e)bH3T5u(hizYNg<-#MwgB!g zpOZUdwAnv(+Wolh16n*CC?x}^ykFlAq65T#htOYE+kLfm?>YxVe-w`w1G+umnP&>= z0XVq|4C?M=+|5y*dRiD{a=EbTpB#$kXA9HgzfA+K3M|F)#P_=-t?cM+h_yOMlT!3q z=}B3us;_%WtTDjF^l4yA)s7LJ*XJC(?V7^m+W7d0IexO>2kdzuCUf@{N?bX;jvMgk26xDM=Ks#xD)ZKT zau?X@@GRtYz}aSV!#!-hkC0ceAGx!V8EC@Ek{fXeR%lfYI+T-A#<w!D!5f|uYPWfikZ1gG49Vp*TFxMYSXA>X8L%!tO!lColC4qZ_j+kbI?xN{Js zDn~6^A+wArdgx>NO|__5DBsb@FR&riz&ochy>;55uT|$f zra~WH@tmS(H5@;;6RNmor4&Q81hBkh+NXy%P@HQ6Nbz+odV4OH;j=fIIPG;N(x;>qlseQ) zQSR_Uk3F-p?%?PLnGHe=CC380JH}J8mm?{LU`_y4;S2km;vyVL_1#qK0g_6PaSUbD z#Z2zT!1$LoNF3$1Hg%6pHkMe+Ck4#^Brvv{Ur0qC9}cF1|E8Ed9NGUA5fru(RxB^% zg^Ac=XKHkeNw_kC;^YAngmD3flnn#i5}oq6jwj^xx%9F4(wbCB(L@kRj3AG(2tJ|Z zP?;9*2}IS%s1T!-Iq;{~0)nwUOM+AcGwYI8(mK-cwK623&LYhDoc!Yp-+&%}A~5*H z!=pjeBr^I?7UUxHFJa~5ky0Qb0~MPi`xroT`rSdirjlVz-BF?N_#mSj3~=SZ%h7J} z33;T&nwkg2C1=dxSSWY@H9m3bqGPyiI-NS5z6a~|ogMfM1OT-P1jOY6gWJ|?1v0Ir z)aF+0pA`&Ar$g|X8e%6dC02u(<1ivP%f?B0XkWJfL5-W|(q{8;+WhMtxrtze&0^-W zNr|9C;@bA~tCkCeY)6n{f0y|Vt9oTku9M{42*~URey;z&DDZXw#Jez4^)V{SKRCW z5cZDInKeP%=p>ogb~3ST+qP{xnedKn+sVXECbn(cw)thA_s==+ch)+;_F8*acUSlB zuB)rMtBT)kzSxs z1l9V70Qruc`#rE@_^J~nAhqg9?(&Fh0u8e04T1W}m_*5|U*ZExr(mc(WF>2XK;SL8 zNt*z6PRoHhe;#0~LW5y|a_$gAy*CRyA-WsV0G$qeoHTJ+CB$Z{N)!u!|KPJU{!Ayy zXb)|d3(b28ER$0T>n%CY!xB&55XTgg7^tN_m%V<^yZugaI&ClpFapoa*|M+@we!-V z0PjrgR(lB@WBkp{ZiPl}ex1uFP-cZQtn=!vws-eRGDmj)`y+E7Nwa^^fcZ*XNJm)D zSKhdIC8`~s`S!dCZ8a-v%gyVP_S>t3j7N+1lKo)P6K0665qpk)Pt<~v%}n(7-_vLp z!VtM%J2$_){8Fr&0mF3bl`sChB%)9ot%5@rR8RArlNVH8ijj+DA-scUQww=x{126N zaiB)W+DKmTeG5*n-1Za;c`SqGUYzQ=UOa(&newLfSCeY<^|zfR6el(BbuapG4I)clITI z^o@(R(!~wX8qwV|nWdnmkW2NYyel^6>f>4^!Sj^7HCYTQ^YP1N(tx)BBHLagt|%b} zZ4utu4aF5rP*t=>o$dD0w4-61bCGTTRZKL>YcPdb?V&%eGRIis_igDokJP}eu<&FR?R|}{If7CHVig19 zoQC`x{VPz?uc#1nTsL*Wr7l}}T!V?7g~BPSd=*7h`74tX_4iRYv| z`T>oW%6w+D2=+jgdfEyzNV12jUzjpk3h7F`v7AO^YE7-Nqd}s2Efm~-`UJT!fyyZS zaE`#)nVdw04e~0C*@@2*hlv;*7ot@Fx+jLypAw%PDLk|vBTa6nN?G%IjuT>}eXt!C zo-&XAwFV7MQl;wW@%kb>@Il%RJ<8^d>$F9*As31UeYPQ*ZN$bVDe1i)qVujN#O^3k zQ-no!65u{WFb0{n+S&No7mp?MM3}kK29%}@5GonHj;iZ6F^YEto(&09TDZf218Jjg zTgf7__F6&T`jSM~W6RJ;x8!V%arLv5(Q$)?z9tp^{aUqeC3QJ_lh%?h$D#K@eMbQ0-_l9OU}F+9c<94$5w?>3DdpVi3b)h3u8I^F zUC|7a*#2`P(&(f&nBVx?-~7T*S+EjSncPLPj5F6qRWtt1 zAJn*yX)jM`SZ%KVeY2hU$E@<~dJc#s9i6w)fK=xzK&w~WT1$Dn*rYB2P7A$H zXsE91OMOQkDMTBMskw!ACXvY@*x4#hD$`^yO0je9!>jWFi+Ksa{zrqra#)Un5RfSeMWQhgO{b99eJ`b z@$i1FH6@4xfMxhsRFRgIV_-CKzm?uQ7US+jFc7@=YgB(nMFbp{WqB5uAt4 zG+WS;X9#WCUUk$_#aS0>j@>wrPxRCh>5NC~6dQI~qc*GQJEIA4doR;;*h$lzbcgt& zg?O{D-Re8mL0P$~?f+KK2+$%)uTr$kV=@G17ZP#F_ZxG!@$)INPiq(4CecI}jpx zWLEFq{iEyzhSlB};pI{00=-um5DL)_X#AzmMza&XJb~q4Hi;~N2f2b;u}1jnEoSU2 zwvP=BkQhv}IW$Vbcgn_l(*SvoAlrC&$?%_|-XLzSAx^qRrD>Db5DXxchgt&>nuuU_ z@luAqYh8W7@C(5!PcM2{At#8xSvLBK=TTvqy`!X0@OUz9;EVgZc9uopB)mE?%hAP| zTLw_#WvKNdDO|&=wr{fej?vfKc5wq`M!-7(xa!5{3XBXI#))%G_zCDi!>WlDKSm8v+a4x^IsZ{6!K z{gEjzFmz1$TVTkpzy*(E0E_I%fs9AV7IdJkf9js+VF58|w?T(K8Ac`T;LIvL0yr2C zk#C`(HVe;fRFVz8(m6aFhgol<{>g=f8UZpR9)LT%fh~iqw3t*kR$VV3~h@r41{jD}9m;jJhzVw5XG2rQG{H%&l#4t_0bp`n9ZPjyHjL#!J z9f=9U6cmLaD|qm@Y)b55kj_ju{CXvHITJGN$hcl9pnE6V{8$U0#nJletbBfM+I^QR z*)bY?A@@CL4$W)tHo8H&>w!Vm@{>?cQ^an2OSyh$0GUO9nqAs{>_wq@qeL`chWu8S zd36*Uz2|z_5iy&t0szFh24vmE-}A@-nIu=-y1o{Pp8H$t9U>s-_)`Vmnm&YEj+QKX zQ=@dssXzB>ohTkIb`#hR7aYrRPRC$MD_QFSpg^s^s(^_Z_?C*_W911Mo=|Y*_3poS zHH=5_fyM)rtyZ?L+T``3WF-)^_|2CERd#0tO2!23IIda@l{WtJOu^Z?|=WZh#L)7>b zArLCm7CcTOxEVQbN!~p0qbKR4sh8uN(uo=rOo90pxnuiv@(+i zeIfd2fMJTtXma{d(FV@zl9HO`2aemprIj2sC&;qeY9B`dsNbWXG|dwIM?i$UI43F_{zl{HO^)h-m2hN~tj-t3?Ko zsgQAaW2P@mJK*Y#qN=sny6%eve)+`je7)y>+j=f`o>TO!AFKg{*k+$MwLMN~71hz-UQq=HAQ%M8K0QP% zUU^mUGSxLBLIph_$T85V-~u|x*$h$3qxh*3SAGno-{w03bZrbYQz1=1=70Z;=Be^4 zU#wIBW6L8CF0~0Hfw966HRTC(x>&LC%R4k3MWv2GGMHGg@l^qwEs|SMA`T4Rv(g8S zdq5Pe)vo~y$+$BVr#pg<6$q<4xnk=tw6aL1OA6OAbil$8)MF7k^8b5V(UR>5D^(C# zb9lbk-RfeM=s-yn9(7V_fRKjycyzsW1y4B)TAhFWazXGR^YwM5jpa-^;Bj!Le3s+s zNG(-4R1Nx9j&+QdMOA%nzW$gJ951q z(#86IxARi^>@9w+4hIGwdkT1CYNY4xVC8$e3k_f8$BH4OisE(EuexTk+nJL@id$NGau6S}9UPgiW74`7Snlv#P zp1s-ap(57&d%XFfG^W<((hM`?y|^7E3njp|qm(MDNMp{Xe`Y@kRc%ITaEL5(w>~-( zlaey08PKE|7l)@ey*@(DvBODFIcI+$f{8Ytqj5TLBylKlP?t!R-7jG^aoi@sm1H1S z?qXmY>jf!e@+Qk}QVrE9JVr6|K*L(-#a0DOT76>J?PGUJRTZ!Vb z>QZ0$edbbxAu%48GD{e3{a#6TDlMgEdv?~n3wUJcAb3ms@|gti1-<4Y;I{21z6ZC% zyl;#hdUVdRmsnacpdURohwc&Ox1&Uz`PiW+8K@{NbIVLTTykc_Aj!Wqzf1x%p_-*( z5(lLx_O;Tha2tR=+0tyhDk=A+IVWgmiZdpWc|;|Z_n!27 z0+3$~1cS)w$#y3UXQ%ESD+!%D7M;P_;7GUpXZ%k4bI*)mzdgXYBCW1UgU9VuSI9t$B;3P0kN zvfSOu(?5zA{5MRE;_u`0LAqgo|4;y0bX^ZmO(*Y!s>Llh%|fobe7HLCcAo><^0jp= zY~ULoLp0&f7Aa>ukK5s;4WW`fZ~)g?s!4bj;}BO|79a;+76>tXKL?b;Ha!*I^97La zxIc6IHV^!Vb*-1%p_*uJjX~PnIi7RpCXCp9X??XaxK2HHB5CYBfZ2OA)TaRbkg|f@ zgoV@8D7}z~2np*>61LP>0r!vEEq6(G@~u2kNS6X)ia(%|i9++Ve+kVj{Ce^%gHYL4 zW)x)+46#|^9uq+!6P2Lat8ID8G}dxcE%gPp&nJ!?gL1gy+F zOkrP7BZv6&v?wGth#lxwB4`-!M?g$Y-w|zItQu(2mxrYR_&Nf6y3milhn*l=v^m)` zgigD91#u>|AK5bouFF;Q%?b`@JtR@A;itPu*9>cLS;1`42GWug{}mQLs?fM9>P{c3 zb)>pjY@G`V*W+J5m2bNeaVjj99&!pS{bC}z&UetE8i#ENOM?2~1sN@Xkg>Y?Qoji_ zj+i=ude3Y((7d22NO^iw@Nmtqp7dtxZ+Z2Kx>Un#|D!Q>rMs-Sk^pI(d}YuCB$DNz z=t}CR)iS&N&&F7dzSDo7q}K-5tPOFkMkDB$C{+I+?R@ia>Vo}`1#KerzCk~tlAv)c zRW=&{Y@7ksb{(i?qecJ=HEhM&u(iI*+#&)bsf%aN zk)IR9q0}C3>Vv&AF6qH2Sr<{K&Lye}m^xd ztzhhqTT&~SOIw!PPp(7}6ugG?=aAmkbpKz>5J zv?bIkLW#2GbEb?<*Z#l{Pyrw}B1k=e9~!H5e)~cmxV>&UYJl2|XNCU>s|{q|+@5@qU6?`5`_4}PMXW=#aEd@-Aemdd6&&~xS8hhFJ;N)&5qU&fQE_|SD;`%Uujf5fHsKpp;YpCyO@!YV{V#LGh zcXlVb=IU&BN(mBD$}liMv%`(GXW1qW31VKMRgz4gj@^=mg=R#24O%6Xr$?@l-%$mI zvjAe3v*wx9(vVZ9%F7$utN#`N4*0JUxhllY;pnKEmm>QDCi1mKtYMl!MHTI;E1|id z5FaQ;Q%K&){7Pio!~~f$l3buQx*+Dv^lB0rhm%9N#m~~j`bnh&6^AmfY%67rdWl1C zrmCAVP?%u;is@~z!|WRn+E~?fddOk|rp8hv@61>@o1#AtNDU8{nxB?{$K#{9ruu3= z{J#?>dYLGd&~92s2UXSD7Cwoan#XkhU^^R)BW?XK(F1Ja+%QI9g%!LgRs5pLNx_<( z?65i<%v?)|(gK~gVk5JZW^oC%O_v%QOxR1RADFO zqvi2L>l^xx+#-tuYE z@Xt?r*TL)PuJ}Hmrj(6oS7fzCaf|Ro*I{~URk0VZI?dvNL+Twd(*>@n3PGA>;{Kt8 zZA5bRp9XJ5piIvc_hyCKCcHB}>X?b^995-M<>kyRk?HXj$$z*2wfAi@O`O@!O2T!c z?fBpzT}6Yya4rNgU?L&9$__;$Z_T1CY9_(D;+-Bsxu6u(E<%<-4fUy#q6SEd>~X-4 zA@iwA((!qPT*^og6sYS?Mr%S(ZG^MX8z&h?FPb)nFV`rxG%b=Zi6EOd+#bt4P+`fM z)_VlZYC;q(@GxU|hg@ZDK-+m|*M-x$}+!`S?Qy@k_~oq>srg>Jbnmm_Lj@84(Fv z{pt(@&4Z)m`J6meMIWR-Z#(=i_POWx_oTSwVByfmJf=rBSv%npIDZ;1s$SIU6Nnn;Jju3F*hMM#Qh<>}kJ7RWetXE%tR6#_}Sxi~LDTYX#m`!mO zyyb!&n3sy;FJe`?kCW~>=QjE=-O9S@0`VS}Bsv7zc|2+w#H;62{$6xIFhWYn-~;4l z_zHeb@?i1>tNv7E_ZDR0%kFFD9|Fp0z^QE}TPMl@`$la$9_HaVo2n}T-9sOA(eS7Q zP~5`3Gpg~3&zh4kQ2Kp|L<(rSoV_=BhE}qc-;=|zBX-O8eUmD;BU(FeyO&wY>F+qI zCAK$K^F^hH?!^%nUa@<9BR8E{IO2HSOTrv)8mzu%94lngd9ZI-DOaf{8I;9RPtOFT zvb;fn&UP=e-Er-Pyz+fp_3X>RcIGaS#EbESF6OpU5rwm`lHO#YyZn=pWD}M*J78N1R$FPJsOg=-i&vkg;-bg|Qs>gmU&<=|aBM=41wmcG( zw31P%E%yAtLy`oF)6;$1Z&KlgA^0j{#3bn&eZ( z8OEOdX`Qx*<>OsN#dyL4$>2L#jG8HW9LU(|NOpe?A!iW6gV?0 z6-;Yji`r^$BylmbnjTbi`E1ZKn@~OS-^qyI-KgDhM-n(3_~s6GkVVuH@H$p8Od;Z* zeF2-`k1eu~PZlkDR0d-3a$}0dZKJ=~1QY@ji$An3!YlyKO~A0|SZ}@fpC-CXa$b(V zX~fB#kv&ZMA1rIPd+&@pId%Z1MwMQ&F0%8k9xn!sAL^>uoi7L*)T3hP_SO3QGdY$bcrDKRk7O8Bnb_kac|1>ocqe+%C{7^S@Z%u%BrvJTJ*dw&E z8q1g9&BZFM9&ENzHqqHy)z|EAR<0Ex=>{-}N1*fXp@IT1pWuI=wX2rNqghwoIATU@wd;L)*n@wP8HF-BB0>T!a$1g44{U&$_?8Zz6ZoO}G5 z$w9Q{mYoAZRx&avdI54p8glhb>;X-bC-q(A7vn?dI{uRKYZDG0D?#WlcC6VVIP z_r^2g=f7NYNB|34W@iIhHu7HCtCzi##I{lR&BmB5gA=>zSzPihH)}}KSvA-@XeQdwq*U!1XUAP| zyq#Z#@Z3mn4MOE)fj8bmkRv^=vM|LWVJ5(}tz1WM(e~QOS&S}>&Xapnbno!*%<&*8 z+Ox?ZD$=lc|dGf0m|=q|Mah{d(tzXRvXfpv~#xtr#ul{kpp~ z6YSs9qs{rc<3BM(Q7PXZ!VcIJ@92md8!bfg+R&pvi3kl^VWXN8GXYjDeg|OJk&}cP z)&&4{_PXk0-n4fhMjVRT+roiiQ2T3m3MLUO43jCNyMu{9h`G44oCP6~242oA^Jq>Q z8;AzjE>eKdEls4S{#_ZHH58c{%i(pC5$ZW19J}Nl)oigjcmxzz@UM&ya36LaxYTas zh3Xe=o94wU<|7lp{6@q;ga*twFEFNQ$K(d`tAL6usO+%*v=j;wm`cmDAS2-1heY9b z9;QTrEAwinyfIKdP_Or~ydH?wpj$^(~RL4!mtouoN{M`LR(qA&j zsL`nSsT3H6e*+TSxTfNraxy6G+dV~M!F>BE03#6&TQYr_+V}u9|52rv(uykjK!tI@ zobaIk!Q;0^ve*1P_Fur1KK8VIKm-=8K)c8!nrNgg#wUpXHd1J%!FMq6ksjj${19*w zC042LjV@|F&XSk~ZQz)}agfyoE8Dtl0GZ;bRsNX8ouk}bq%yNLHHbb=~Ti3KlFB+1PGdq8x=WEY_LVpjbAW7V8g zcHie1Y68Guf@X4$O2dHyMG2*jD*RZ=POIJd&AQ>GNR@g!d`o^IP+5KnFXqAb3Cht+ zUGeb4{*19uFgre>e~FRLIYeRay2P}(5T$GGSg`Zd2oAJ4N}L6@HR8(Rz6NgS@~(-H z1lH!AQFpkU-yj^XXDoGz5M-UafO2D7?bF7x2Ecp<_PL-h%P~JDI(jyr+I#2^`+E%@ zFVOL8_t~rLK+f?s7pg6Y^qX&%d$O;r&Y;_`=@ZGOqZKvO^C){t+nHsEV$kJ{bFQ_M z<$|dgSP$hSJYafx1y*Ng#)VQ~lHe)KX$Bcq{^yGht!AZFrsVpM3wZt3`;p9x(|n%$ z8vu_&gD3P~Uaic2gXYJ#x8Op;1 zu0}$Y({sjBRE}41{Hk0|>95OC+N)F!$8nGwo(h}^=Q;SR;J24MSY1>rR@97M~W0tFM${yGkhDWF#J<-p_`M1zP zVuHn_bxexI(h`_!-i6}J(=F)zrRnRX>1y)JL`zz4WrRY)UZP&vd^O8J(#;T<6gq8Jv$n*=UZ&iLIl^rG@AVggmk_Zfm9$70 z=r$||?mA}DS1H3{bF_n^=cm;K{3{ZvrDhgYWfJpM4Md@-xxOh;8K^caNvBVSF8_#g(Zbnr+U~P7yeqdu}(K;&Z zsufsuX@E{w+;V*h2qo~0%dCb;()?q5mw}2eaj4GW7xq>X?LyKElXoES;pdoD{VFc;`&`PguxR zRh{qKOaPk)k&?^!f-|jcnbJntUizjwIQQZR4n~2bA?K;pSSCp^6&;8ueHE*T4z3n2 z{MWwhPRA@8ApPwOP22H@g>$LtX$fEJ@2e+Z#ig?$`X!TXI)6)N^q4E>-nQYhbD+^& zxVAEyZC|=Ri564#lLRhVtau=!xX3iJdjhsO2S(+Us00OMF4`&%S*+ym51G{wC}e%? zNHNA;r1Y><-cI8hLw{krbR>XqmSCv%o|o%P!%j{C?#SvV8YlguC9SyFOE^>oolWB! zhOM`Z743{o!PmD8J>x?^+3*2k%Oicotr}H?qWnVH0^fNBk5PmR)isEp#*tf<6HcZv z%g%!*OTus|-NCZ_OHimH_MwjnKXiS1&OGuso+i9LS~tN$xP>NlM6?|7@o24*Q>(K) z`O=I4H=S~aK$J0KZ!iO2c%nr(eYtFG@$Pcj{XGZEQ;|^h10za|bSJ9MRKK|io2WUxM57%T9UYCI!d2F z+jV>hD^)WvKE>~#VCc(nb_{vJVKnBtZCwN?2!@-}30zOYJ6oJBMCn4ROU)xeKvdO7 zZ^SeH+F&0$VYF`b9#T34Pgld-QvuV;M$P?L337LwMMmQ$Tb7bkl@)8wyGB-u9*O=u z2V9^p!9=f_@fW!uD%xK?A!H z*bOBPhW56{(7>zVRA#*GkwPQlB( zL2r4+xVv>!m1txm!y2p8F61p*RPwyBEc_{XIKtg`0`5_=$HU#KP)pp5^EH#2U+9&dW5~i7CFTpG#QU{$l7w5ij9t{B{4E{O)8Lmf5 zr0771VoY|@FD|GmEP9yt2Kj|PJYaG-49naCH^y<%EGC%G0xocSB2c@)s2nob>`)kJ zfj{0feU0|dzKuku97LGCfQdECmcCRB-e4To(U}S#hoOAyT8@VfFpYR~T|GTZ(MWug z#ewyUK`JV?&83>$nt;9q2-|TAb)SUfw9OP82HQP5oSxuX6PMW)ZQLj)Y(Z3Uyn|)i;*?2VDRExV7*Pw_M&^ zGSSrkgTQ|cNN%rvBV1W%Xb$)9bfRxK1bpKm$yf!0*_wyR|InI7ajY#`{YRU@a%inp z9hxH;RFU3DQ%R^g`s@_h##J}H#nn2)|wppLk#ahvSkKkN88ohP4 z>C@}H1ZrX^5qKxz#`YvNoW|Sb3+HU<8;>5wjh=28zXiijsI)*|rvpIQ3W7WF)_*=1 zaqJ9NKSYsjt)3g&r8;Sr1weF^X`AP47CC>To0nfbojW~gE78mba?s>Vb~FT?Mnel^ z+@XK!=!fv=!ZtckD7lmY6|vj$E_X;JBW}IiF`mv)Iv2E7-l*>Ks!Q#jGMJV&ZcP&J z)RLd9n^&~^2_ad{GXTe^&+B+G;LYJe>t^4$EEqyUp*uA?;FmF7{M>>An{d#s4uT5= z?k@{;&ccF3twU-Coo$r-(N8%e1YDzEVI_#WcrD%7$~Zvzvu-NWQtsXAcFfV;WtFo& zEm*6oU}Fx!IHU?P|{=xQBw{J#q>i zS(7g98MG#0tN_q6D%+G;Y7a52_V$x{BUMPt2|ej+czAJ6`p(s}w%2I)ZN^p4fR-QK z#m#M^RS|Ou7 zdGyan-2!)HGEI9AqRAg5Z#tQ0u^nnqyjhY-RlM!y~IT&BAwE} z6r_o&^L`u`b)4*~4RSN~9FvDuKmlf_Tp0iQ5m zZFCy~O)V!JQN!$m)V1ix{S?3b>b@-_ZF4WA48vMmS*{^by;D>nmP3uOmdrH$dZOC- zaw_Nc{yLkxlJheRiVWoQ`Tcr{|7VNa#gX(-CPxp_LT8*#cIT?Ai=&7R0C>N@e_*>i z`NQYU(o0*;L(`kxZ*5(2CMKRmBr+vPo5BRu=FtiK9koK$1CF|oE*rG*G{L@JS5C6E zTV*&oEaDi!TUJgr>~P;JSHi7WLJ7(&zxqbpTJlK~aS>(JT53lch6V3?nKMmTQN{Jv zr|*}qB_L4Ij43SX*j$7G82+%Q6)EmSqiM)CR5iKw>zwFP#a#)XSz3wpzh_zqaKz2e zs7du!WLj*!c6ISVmiA^kFus4CDZNU6eZ?!4OO|H3q)@v9I$2Tg`aQpsGd+|asbuqd zbT&a=7C|ucnV4N9;D0&29&uwcO?lkptbX0)yqXkPJbf?jFJ5oJvv`Rj-5hmf(xLWU zh2%*gILDZUQb4T7s<0GA^`f3*)9Kmon=DSIQnjzEg|EBaGdEplDRg%o(xRlcUpJPN zVFwkYEnx`>Mb%21tSs7&C&@Cm(=)wa1#WfPMolHDd2$&pV_*2+ix0qkHZ`Av~hHE_⪼#zuD!_Um6Wo5bdac4bZ zo`ljY^&`y%GbLUEWWBiT7seu*v{mFQr^Ml!9df8XMKT(s`9uVY0Y_(@hn?sfUbC_er|E*@^$G>#Ho< zT9xDJfw^DEQt=1b8Pv%>+OfzLhEBU9h4<*~&eS>=1YQ?lFRdmO+0!j_-UXvt`|wijg`>Vx?YOEAid%u>0D) zIp~HpjFUq=1NWF#gJ zbP@(oAO+su8RX={&7T zLKu;ed{pHWo0;Gu=CplJdi(L$_BOyIt&$b+bWdiBXrjWu-k<|=&s0*9 zyjz8Knm4EXQ)4!?s5K_Ba}rTevB1u~VR0xd4^}`%My2HFSACtH0xKs)SC-%WLqPgc zFv+|>$h`-WhE4UDbXqs;pOT=~qf<0}nF)2v^xt5;K$!N>P|82Ch8J&hVG4;WY~+0b zl{U+aCJ=3_CDlt*w}ZDHB17zhDnyo<*}{M#$r7Op*jlgBL=_=Nri)YXWxQNCv0~(W zUR!@F&O8c#Q|u-lG9xOozqEo8Wl>$;n89>PRx|4K73msMn5uQv6!9CP&%hJ(TTi|$ zK>G&RDuu-H)wc*v45JVU#8!jQv$*tt(q*u-Gmvv$RDp;P=bonD(qcguG0e+iahQ_; zW#mjK^PfvKW|^Gdkx22}O=@%aJv1OSJ?;^#DtZ$u8+^^g* zJz!NB@uwvS%{A=3Z7z@~ynRU+05_uNCUlCyvWQQ6=%=PM?vGPgCA1#6O;3I&WC$_H zyT7m%AHXs2?t2JWRJAl(X9YCsCsv`<^o9X|Qcr3uI1!%uH&|o-s zZ9%cc-X!{RJ=Rq7>Ez;u5G4u76$Z#HuD@Frsyuwcc$$=-n=+;IpRYCOx-Bq9P^!P; zVf@mnCqWm|hkhkBpPA6RtPLp9zWQS-k=h5zGZ@$l?b$33F71F*eg3@cl9tILmZi(J zgU0E6#NJbor=eksR6l=O0@&D`;r7ae$8G4aPp5NQVTXWk_WeTJYmhNb!u9tO{8 zI4FPDP|z|lGoNm70his=$TW6X<9w2&9!FTJV-a(Bgs7u||HFov2u|S@{N8wjjtvJU zn9y{1Plnfv{wWw_SjNnQsJ2tUEZqgMfOGCt$QRL#6j8pi8mPli5WxSyZzYcz(x@r+ z$7i+`Ya(H_SPCf9NfDyd)p<3m9$VAwDr@I}fvckUT7xit$~h;{o~$t3Bd*t&UKw-) zxmj@A7QI`9P}?$>sau~4hPFVT8nIP3bYX~YxHI#vMO>_avX#j(!ce5pg3y$iltSv^ zLEn=TRUo;!=SQSUyRwziR5=8aGB z*Okg7S7#~ZD8;MVK>8V`3?SEDWi`T2jeiW)-C#(Or?c@cAb^$JlLAS zjp(?y3iW9e@=->3culCTfv- zC+Su4fGVV>dfR9KnHxf^2WNJT7?+^#`70g)bT;=5J_3PR;pyj;dGZB64nvX?^6cVzia3K zfdD&lBD*UmceTzHUYw?NuK=!vW-@x9!S&Zph@lS0UTMK8wpa5*d(kZXa|H`(XWQ_= z>a~u>B(f~(A-^uap#=FoA~u$nN#=Dmy~DuBb!PSA7w&sl@{kL{dGH|gb&=;!J$1vFjw z70)8!*?sMxg%2!nzM=Qy`6R5uXLVO zJH9wpw3WAzV<^sbW^VAQE=hP*P?mwHg$?`8h_<kx{y$Ga#kSLM}y^x_JeY}lcPt;GQtZ2p;# ztew;~iq0B5QeW|MO3~sYOUSM>yh_r<`dYa>%8) z@;6R*F0vND-WqqR0%(8w5eTaVmCKA&yrnGADdFeI)J&j7A^m6SS^! zA_&Pk+=3J-8c0b|i)pH9c^Yc9E=lfk&9<(tA`|eLX)4S9a=C9L5>S1lhMrkkj5~I^ z6f=+-qXz#b1~*jtCO+hv{#Owq-vv2LVRYwr?W55qXF1M|F28~^cMDxAdy|vZqrbJB z$Nnbg>ZE?RLYGEBBblJjWJ5_N|LL)nn198&hH6uFCDF{$ddxSq2HZC_+`mpFjl1Q# zd{;#1v#Nk0j_Z9P5t_s^wrTC!=tBIO369FzFz)yt0c(+GrEw=nWqIXyXX};n$iA5- zBT$`eu>08B>KHSW^9f?*aJn61!Q^$iO^F9EGm;oBk}5EMzTa=~$#%W07C+lQdr9W# zy-3SucYZyboY@`D$pNx;Al&V7E9QG#5GJ75p9Mda!1d^xld&(JZ#kV-!SGg6ssyR1u?R!__5A9N`z z?i(XAn%W@s4J>$caB?5=Z^6d#GwG-HzqjWZR%AD{7d8cA7W<_na`#2lqvkV*#XI<} zM&iQJwMcTdqp(=p&-O-WQ3+ch?V$n${8E-|C{N%aMR(m&?syWCh$~Z3)K!~e6`d31 z`;}uAMMXzi!(}BS9zfy&W@nMr4M^dR}Jd%!wnZWC#=5EWvSF1tw5wGH1tRQwh|~Lumj9+a$ij_ z;iSG z%IWd0x>Widq7I(m!PwoG~(em0=TV=M4&a+4sb>NTuTI^M;nQ#pjcS zR6x+FED`)n?ACKft}gK#BX&XXF&3{P$m*H5`(Ru~qU(nc`aNrIHXspMfExpn7;IO8KEu$XO@$ZnaxrJ3c53Ibe7wu~(Gqi;h_)Y^37h%N z*3`72Hc;Y)mKQJo5Z#bKdYag=K`y5G9rF>y5aLwSSdu|&@y4!=JY6}j;Y;X@=De0LU)YDU)>#W|%3zLBM zvT?iIwS6PWEO&26u~1fLVV7Z+x$Fe5Sws_QYfT!mqBp5iXh6_X0BSS&UNo(AjI8Y< zJmj!b(7J7D-wzJ=!7CRn*efKGy^lVxxI6P-bSkrc?In5LZisY$0t&nbFG+8Hh-mlR z(m%>P5=Yy?_gNNYR&Q(j9py)a?uxXhs!vgEw_xJgjQF*d)NWL)`70_reVz-fK*5{b zhUTXjv%ypBN3l=c8b;*t;d19i(7H4MyNqvF#AQ-LMf{uH3ku`Gw!w-;vz9btj@s~6 zMs*$&9vU5AAl`?S|A()4jFL3iq6N#<E`8zQ|Z{;+(V3-jiuE#{Yk@Ee4bSAc`26|93=@X50@Ak6-TppyBcTq2bA{ zU!8?Q8$%e|C0K(qIR2sG5mb|;s@KX~iC%ScW7tH}hJ1}EppzQ3r}^+190aUHZSM5& zd_JI1hDM3JyyD9PJ_j%P13EOb7mjA_+f>AcA3o3kUw4DFkO050+tW?_wad}(P@}d- ztt}jO_L-&#)6b-$1`)+*829XW?h>5>ufff%-9383>VC?xFa^ zo#Y7?>a_^6cCpO5bjndGg5V`#9iYe5=U2@x-gNZrDn+-7c#fj78(a=t9 z==OS2`D^MM5SpIGiME(xDDznBEldgfXEryd=MzH#y;VLS+t?po2mCKz2w_?|;^)Kj z=8uYaCb-^UDRl3yayJf(>9@=K!*%I3KO9Q=)<_$h&^0M@M0?|lP^Rn&ZUBKM6tD=tRpZehV7#0uU; z$jQ?Eml4J?Xd>(Up@AeJLLCo3NY=;3w7$t9=vc z?K2kno^&$J4Hl(wb6Qn?vSeH(lDYV2E@PYR%&@IVrdOzBTyDV-gI@~s{dRLc;#}UL zY<*6AIF1(&8h!=cC>Vrn^rG8cKfVoXx@mn3LORsn<;$q4h1`dkz8jcN6i?Y)_yccD zIxYeRrf5oSI#GfS1hWxbn0T&0D0G+p87C0|cAE}86{tr?AP}9{bZ$4SFftL~Fs5Yq z{Z#aQ4OGpzLF+V<;*B(2`DPCIee#U0B6G3Cm))_DmttUeLdoAMSTgG)X@GrkcyBkO zHENls%Fyl%)d~2&d>g9gDCbeGQmC5nx~4Iiin0imtMvRrPo2{ajhZuThsl4MPL4w+ zgbVY4d49Wl|7$k>N3j*U&KhVx70S5pmF#eVK_rAR3fa#Q4Jl3m_->PnoH07?Hw2Et z!9z=24prj?PP+hr5QR2`3ItL$U{uu_ z0wF4&=LDmrzXyxL!w~i@;pY!)e45dG>FqddV$ieKyd`BtO$}+4p2k18t$S;H&p$5I zwT-;Tynboz5jmU3I5)EqA7JP=3TBF)Qy2hjf?;`^bi@T+@X1vj;{nRzLk-(z^?tad zWUGqY&>S+6Z#v>-dkm$qRipX3;=@-!Wc=kIF6@S}yLnp1-LP)IIVR@Kh~4BW@*Tq{ zVj>DSrq>@qlv{2O5mSf{4Ku<-Q`a@a3j=uv zSx3@@?SX{@#oXCh4go+zPG2mVeSbrd;oLFEaKN5qx#7gViKnHR!a2q!guR!a2W3-I zS+v|@)~7z-cfNe#sI*lIWt_Q!5Rh=vDz6s0VqJ*8chSS9>lZ-`Q+(kevBs@4ToQlV02g^`kB zM9>8$#3v-BCV*)MTh6qH1d0fVAe%gMp-YnKMy@Rx<#J4O_M;+XB$aQRs|D(b27$<_`BQ?oMVfd@LuBcVkrD4Qubki- zYjE=K1n%UVBN4JYn)~`F1)=6ry|9n})XHRA8!G91 z_4S~$sP9?Fu;VtD!$oFIEMX@+*#HUoNc}79V6UsE_zaqoViULn9=AM56>wfAycKXo zWX(ubT60aT`NIy}ih$V$Kl|#&DY*;Dn$V?ai*sm4eqLZ*w)r9xKeDE19mVLi>U`9J z3m#jqJ%EHgE5nz0JQ;9LdL2xjlvkc1M3-PQY6aBD#&F3CAcQ{GFM zoopqH?5umM#RNK$Y_}__)X^jS#r>!BYHx?$D@J2>7Vz|)fV~~rR#}EF?E3Obo35N< z)?TRTr!2#a6VDdanhqyXwB|_pS@65yzu+(2k zs#wKBLv8)`V+atWYQYef2mKGrs+P^SISgPe zv1zU=0iLW_H1BL%Y4>gh+WGHe;>VH}h9qv+e+>2{6T0t@^^Cs*GZY0){qL|EhgZuW zKH^&F)j#&VG=L%JB>UFtXTIEUxU?4~_DZJ<%OC|OR)jHvX+gT#mXO)W1%~ZyW&FPDiKxDfiDI>L61e z(>f;?c8wfWw2Ge@gTo;%&^{py5?#NCnNq84Qlr4_>lLJM37rqqug2iks?6U~CFjM> zTapX16cD#}oGiE;S5RPK>SL28z^VB8i8n*MS%c{Ne`&F$Z1tI;kBWLCGoU3xto#d zac6{WoEKb<&go)CqT(KpY1|e%@>S!WkI1v29c0OV-1e3(tO{PIZIF_e7vSiw1hSlP zkh=GnJoia4Dn=b43afHR#g?V(noJ~ywp%JOQ8lT*SSAE*`e07iT+$lk%HcLi5W3@* zTeg5sdI4CFC+T2F#>9+QjA`9gqF#-!z(vtak4dplW?g0q!nE?^Dh01hXt>@KL?n3) ze)_+(W7k!zXGPhZVbCv~(9}5V6NEU5VKU;ky@2gu)Q*MGQWX}&P4+W(VWUnW2rGp? zW>QCQ(Df2Ti^gK2PD2+KXd0?i(OgKNYSMUHssR4p#3HMZH+4FXLfME5LCDG=VG>Is zFleG`Mon3}FEPB&#cHK8Yo-nPLbrQVLtRK?>QU=kTK9Z)$_%!RO1Iym%Qi2P%g|lR zq9zSTbjm2i#8&ulu6q@B%7nf`e(=OtI8XB2!Y!=L*+ky>jR{#uIDz7e1#vU&bvKsR)?3&3Zr9{$%)XvXO@$f9;ahjX?s4` zF7J2wBo;-g*;bb!gbB`O%??-(#lXBW!*Bt90qPUk@GeM3#D;tLDShCQUjnPF6#$OK z_2V{PX7Nj=^6u&EpBmwG#2~PeV1PMMzwACLrsRq`U3`68s!07polV!3u`AI?GOhp5 z*@k1uTc@R!-Ks8r#5Lcc(JT^~1<@yQmiOPweybAZQ3N|K8A@9W?qFL?wXI7|FpDWi zv8RvltW)JzcI}L|8_c?sO&Kr($^Th~7r(Jr`@3*~@fhd#vXjU@g zQVKmVJd8$>!UD34g6PT~sdN;7{dCOwx^THiqMOr16fxm%P;`c}09=8Pqp0sh6u-cKF&-B&+WCZ-|)qlg4u1a>h6 z*lNF0kOFQ2JEu<2l_)TR5^VjlJ%QSj$=nhBht%N zYr&-l_;N7|;ar_G?kEZ1`8x54w&FgKwJ6lAj!^}3X%?gS)rZ8c#T^3Gz#!+>Xulb% zRS^L}2}kpEF(UkV*F|<^80rnF#zlH)3G;%NKCqs;-%l0;Ady6-i+Dzzu-wj3Gn3>h z^*o?^{;)h8%Q6LroqqGsChzoiEz z2OUIiD3ifsjz3F`ZQI{nCOhd*)DO(&ZS~`N|D^BnGW`rLQLjrs@McBEW4d2KgT?hS zalN4|-X5n3S?md#lxh%rc#`XB=`|Lkwbf{=yf5xR1zMOLVb0A6((DU=@q!&IgD z2cfOp>$3N_mW#Vqdih>H&xit=Uw-eSi~8RVudPXVS`gbW&+aM=HAL|O84OhwL-J!3ACN6#aHOCL(!2fwQw~DD<<0N`%tM$#T<=+Zh~TGV z{%uXUz&?JXo}+K1)@h`Kuf^q-{G~`bLX6IAd=F-SEaymWy24*%FR*2%@pu@*(~=ei zv+gv7r=le7@Sh~W7Z4v3WNFqqTXY4dk75>%YK6JBG6<~6jJHtMum^tvhNX4H5KfLC zhO9MazmcGd}DgqBf-RWtL3ixqAD3C7I$qyN|(Bcm6hF;>5 z`KM(^AoW!UnRb=|0lOLGUm)|pQ_%{+Fozd@K_Wi(b zEtbir*djwkZboSS=?eV?H8c1WHU43+ZWTGb+aieOWZ7*3oX_YGw`3V8tyY;t&hJgz z!3L7j4G`7VLA&|5_6Q6T;C(S-zjUz+$8|tNoWr>>7&VbG-(z!8SI>t3`o2YPzG~OR z^N~pqhIZXYikNo;%WZD2(;MU*V!g)(?q!0^uLsRvEJANhhhdtQAm5MORyqW+y63Z@9$icJE~mwh>tT0E{8$+Pfvnmu(j{pKFI0TCA6bd(XkbU2 zEs(cW&&LfxTG%C=TWF-Z2JcU)7C1p){Bf}_Tol&^( z5IDr$Cpqub#Q`)S7$3IGc1k6;>Qr&U%J-NU--GnSud@tY+q6Ht<^4KqKZG0o6%O?_c(-XjR4oJ$ z&pLD;Hyr~TN#nY_U zWO1rZ$j`Qv4ezfo4i8$r&_VkQBp>^EH=%j@7^{r``{h#mk9hG^833MmS1-ptP5YT& ze^M#}w;E#(EBKcrwN=(}bjI2)A2yYGaZT&$(H)q`^vP2H8O%fuUS994dpljtA`#O? zFA#ge&H_WvQRY4u?Db~1A7X%3I17=-G8V*b*^X#B5ugT|3m*Gyoae_Mdmlr`B2A6{ z@fSibQc@oo;Qad3*9XYi4Jq?cXu*Z~C>yj8yhU zL9vRIeD+)WVVwp*kLdz3ijbkplz8V4c}Oa^+S>D12L-qXP)aQKl3E(m!oPw zo+2Iwz$~bQfFK&ek55e^-3NiK%4zFRnh~C^X(? z3^W7jKXvRfV|c>+a`L`p!gi?GU^10Z;v_^%t{iZ?!IKm|8Q_82KFT*Rq##9tE|}m| zQkLn!Hb8a>4Zx|%dAY^Nqng2gxtTHop<}p2`%;Dx5TH&_Ldz-xlV7Tm-mHHkd%^4k zFpbL#&@C#aVmAb*{%6VepA@V{=wy_Y5q0gx^3uo0WtxG{CnSAA-7>@Y&-^hMpbux+1!RnV3)v$SC*5~Pj){H72ho z6(hB-UtAO6YB)JU$+mT$e zs?GcjGofn8?Gb0fa5J6av-MfJX>cG zNE82b`QD}YffvGdKT)SULKFWKJw$pOm0~9<_19Wb@c&{Ksk{r*xrvISdqgghp9^!t ztz$mobkW3_T5qkAeqMCHz|~LnH&!XI|9G>$_x}JK`3=a}$Q<4RXZ*QwAxwv(Aw-4# z_4H20f+J)mr0F8?Fm8`Z zU8LN#w=-jrB{j<=^f|>&#D!x2_)|h^8La)c?EHrIC|*l$I^;;jTX=4SUt_u~L=oi? z*l+w??QBJ%yhi-2^F?98&?%M~3*GF3WjEwBaw)K`vJe5%Ek)=hOJiy<6a@aY7j11) zk5P_?0r6M+SjVzss5l6KB}q4{`TlJ}8rfBYX~vv+KHM_R{+tqT9$%flv_(g6Ww-Zy zgm0}KL;KT^-Ok&*ht)+ltb5IhC`;R~aPp$I5kgGe#QFXT)_yVt>qpH)ioA50cM_8Z zP2E#?KGlpXs%F*!TDSj{T@AsUF+hBBY{qRPMxdc!X_Zs=A#3SJ42Mi`$LV0pa~~3nVM- zK&R9!uDP9VCaR*AO^abNuKF?hE=GzV8k0t8!cm}gT0i$j6XGYXu~3a>p(^%L8i9RL z&?cGhoPVaL)gZ>V7xb7@Kmwcje0LP}lVUa^eZ)sx; zQUVC~<_np<#&=J3?>*~cANI4lvx@vg;SJiP9E0f1%Y!nh0Ge*;!VYFS@f+rOH;8@3 z&+hfk-xyu_6&u(48}l1QOz`EwX9GqQ)gS$;t>ny%>IP!RDVbGt49@RA$75|6>Hc6; zlLyPN(vG^Kw0QT8j>ytffy*k7sC>8&Aq&#RUi-@_A=h+1IZx3zkFZ%dMx97CVfdB8*chW7dQd(@_kBBb|C&T|z)iJFz z9!t{tyZc#vY29CG3%w6;k#Z>=j-$Fa5hbXQHNwepTGCx96ya8vus_&wlHCjSpPx=<Ys!;tMOse( zNGGlyW}#ZElUe(>;QfIbzMT1$y0bQjRruO{PXA{cGjaXx%UPPg zI3dg)En?ixr*Fst|Lb@}vgj&V=ScK6ta*chluDbZ+W~U*53{t|B&{A0@tMI-=E=6! z3-A;_;8;;<^$6v6P5y9(Ol@YEKa#PM8y{6}04m>e%V%yiZgWK+m&dK+>51I8EOMTr zF;Fjr({g_RZn{FjoE`Z(ti?i)qNao8YWG@{Qq zIyJUogKmrYJ#E1E`U||5n{i^YyIG^{oz(!CT2x+}(_{ABJHgt~8)!RHjq&zHi5^lR zr)qtUFCWc_eS<`Gduh*?5%o9j&dWC;)L4M@pK{pq@SA3a}4# zsD9;)Dqj|tvZ~#!5k^*vF>X~FjB7kQuH(+#)9l>+jy)M~glU|O*+NrTi%Y)|Ytdqd z9J50^<~5{jm&|o$%20>$p;y|>B47_AUKi<7R?$j-&kCSuw|ihHHch1PD)+4bLahBN1gXkdiOKdM zcD7a5fEz+(Pf5+IcW&ZZi2P}~|A|u>fZ=@?g^JSmgO-bJ!qnic#^!znh#he`atvA# z)U=g1fyt7{&Yek6t3jlOWEry}3C{xeg+kCkZopOrti)#ffVRcr%+z5;z}R^Kfm#Nt z$!pauG*;2(8nYrA&-%f%{vhj$ru)t;x7WtmnN}kPG1WjFhh{gd(E zwl}82z&4f{hZ0$UfaS%G`Xqak8ssqMDu}(vEGg+Zkp-~o*d`-WgACfA(W2vk*jNlQ zru(rhE`K`qw{GdPBB5(L1vXJ``XB31PTuJnX?3w4#z_00kT7$dmlnI*UCfm0oF=*0H=5*Iju%{ z6aHW>zkVBRo|gN`d>IF$P>J*EWs)HBoJdEv0>m-gG0bc83OxhFoIF(&^TFTZ-{y}SffZREWBh$g zvcuniNJDW0QX0bQx8PKBi0aj8P{;H!Uj1(b|$R+NTJ9BFje zIIuP#!Zv~6IDAxSW8OnHp@IeZGIMgDsw>sB*q|w@gb1$tMQ%(QuX=1xTs1K)Dc57> zd$O`C2drp0jW|dLc?~6OC(wT6zWXJN5udHYjC2>k=OwB~XSTur!pg27GEeM-k=g+n z9c*wH9s_8NS1xIw%2yqK0ztSili@d|aF>o?v}rSR5Uld|fqy9? z^Qudi>0SLJ^NG)#Mxdx*rphz@R#xyQvywjBV37-}yp=HEZRPn5o5r0}78%tOhMu9M z9fcEKG$Xt36A)33WT3Uk6=fwCS?&uUwk?pBQui&lE6UudVE4?~3x)1uu&YSg{D)l{ zR|n*-by3I9g|W1PMj;-^y=c7)KXROtsG&eB*_ER`?5Cw_^l*gf#aoMb_Tizsjaf?! zWI-*+W}~$@a_;-?LQ!_<;>u65N!f23)bPvYxS``=3xHihGHa_1g%My2mXQwtk4*T_ zznkE>B(rzJ%N&tdpqk8LkhYafkjFpWpf$jpDIXsK zAYAF$6jhcF^2pe@CNu^M=mwZ0kkDGeUgX}{nDR;z%vQqZKT|_7Cg47rUcYY^@PMTUM2C5G>o<{0~oTQUDEsPk5f&jvFuiBe^v9nqF z(^KoWzvSAn<4{ltKqwaswHY(JAAfd09`LxXphVYQOKmKYjKjJf38Tc$CIfY!Q~H^K zA7098UI|e4etIAdi{hZtYKbG)&}=G+V`g=t2`aWR)+R~dLj9IpcGk#iAo3#VJj#3r z3Y23RrkrbOSdejgGn6}mj`cLtCcpA@s@3; zOUcu;4oiygtpuDz5b7EvT~eX4<`M|@YsU}=VmUn9Bu1~r3(!iNbBpl9GK@L#!<0);cql~||G|qJkVM2Jh$q5eMN+z? z8LjYP2V0XKmTh|R*sf7x4n7R5?VEMQ*ZH3iNT%i94~*hHo|>HE)B66qsa}8_3sVHD zB@94967qj@0kj0OAQ4z=C3-bYr>@mXF8E!VG?Lu6%Jo?&wRytA8)3ZrcQf0R0Z5di zJTZPZw%I4<78_W2OS?e&Ft2hr!o*0ocmpGaqdI-O&;1i#F61EEhTt!j5}`6GUO40) zy1`ggF^L-W*ty5()0!}QZJvZ5$Nz=N4$1{*f!3R^0}`$a`m{hQ-Et)W z2Y11yz->t()?9vEmmt{otDNB9ea16>3- zvy8IbdXWRSMm!rHe#ePRb!*QmQl{KiR#sqhzEXk_Xcw;Ox&wFFfvK(!k!X$6 z2kiqlV<;~o>()kHK+tF9*I=7XTZ4}Y` z&E${MCOLWiJTQ5C-fso_#I_z^wqM9$Jd;O-O36vkDX4)tH-8kleyX|;CgBACxCkNY zG&C>slDkUso-MYg^J-I%ShiRV6OeZpX@54L_5AT$JZ>z$w1ci@3C>wxNHok{%#)<6 zc?V<{c_qmZSuSc98wz&t>)S|2Z&n(tU*;~zLrmU&IG4IeObkxPP|X|uBFo5mOqp!p zKp5xuW+&&n(;D|xjBbqkmp5`hI}9fbOA6NgC%T=c##|rbrEFK`trtStAVvK}`m8-rl9{?s1U>DLAnCryXJE}p{f z&35=-IXrkGtZVogJ5{?NsYPW|i-OA44!x91thHM(F0SVU26rW4N-^@qdk7o)eM{Gq-?>-Ajy(56gA*KPpg zCaYZ7@%$EcnEl~jRh^qtQ9TQ7#l_1O$DY2W`9i{CQ~tL~WGo<`_#_>pIY#*@FQKzu z{N;p2{i(Y**ul z#Q5V62140wxz<|cAp+ilsm(b-o^QRa5r*FNDj;)_4PEWOOc;Ye;RzyOW+jo8;@({7 zaN^#8aC(kG8+>`U>5ADANS?E$$f>HGdroo+js2*TTh9g#G;c%*V) z5}Vh1!e1cWk1qLZ41(~3S7P?UZIaY9SLPuu3FpR5TdZN8YP7Qv1d+Y;Pe6aW_T3}@ z_`w$QcV3eD`Fz6VHz*OWKx|r1-2dC#``;BQ{_FYW$Nxuql#zw=e{ubOGMqJAY)C&D z&XZ%H)OPwl1Ap&LJO0^!Ag}&17yShAh{xXnze$ydM6>NuwR~GmqNBHy+fc1JtEiMd z#@_hxJ-&ZH&-?T{2mlh(FVFTcm)x7XY3Eq=7+=j{ICH+;*!3|pl^IK;-{Pm?@a}C!%QhWJnrfn^lulhwt&*CnAMmGniZ-qF zinqpYTTMrIz~i;s=*~m$}8^m&FVP;W$Pl+x( zOdZ2TPnO_bg9rS&<;AI&3lP%MsaZvQ7K9g>M%nx|E)7*3duGL6}Pek;RUIa-N2YhH8MT0!jl}7Qm5SO;gCuCncH~icKnkhZ;vb zR?+-jI=Lkx=#=^@=Ve9(Z*3)V2MsTD5j2WACd5aTb<6whk~BT>?g!?(Xq&22>mOaf2mBau;XY&4APA>C zPke@srC?!%xFE2R8ZD5gMvCqF6pn!(k1ZQ$Lq_OAvd2CZAKo9&SmXx8i4b8+cp|1l z4$ksmQ05|&X3aSI0^nketS53@^OuSr@ke^Da8+Vl&`wrj1U<8ZxCGVW`ArR{n3r<- zOf6*Rx+>W|WG)NT38g*Pubfo7CnxcXX`E7fQ%C*2SpAVJqdm#Dx5TW!MeM<;x?qZiJP(qHCAc8bz4YwbdvjQ$>JY4@NTdH~bqP_9}tB+wRrxvqK5t z3DC0l{B1$m`C~x@(fMp7T8WO6%&R1S>aTDK35cJi?jCQK4LN*>hlw;{5ydatd@lh) zan=6Y(r6L%2{>?Fn?#tHp*^1)GO<_)uQCV|iW`b|$9ayk>tYwQv4ryae#WBOdNrkm zBIAH|qEZWB5=ypY4{Qa?()Rh;3T|=Af zI|cI_41!VPuTiE`@!Lprk^rqCV#i8H8-(>;k%2)PtKc{IM$dqE@+7UJ%EV^vFvXcMoR6^GsUXg(gm;(+2@%57Dn%$*g7ZOjXFK?1Y%jb7KK z%$#$lZw_HYBxo7lQr|zgU7an+z{Zz@H9yWD%+~Fe+pp+9=M{p&2Y7DM<3SxsnO@I{ zoeQ10p&i^7MI{uy#cMRd8FOe#vy`?R(oavr0kBL_0zwJ++19yJ@8E}!2B=OTj>;nd z((rP=MraQ@+N>~LVX49Xv zBl*zf{Yy?|&zo&MWxE1!AxqxI31W$95B(LFl=yDG`F~S(+}Sz5Ua|tlzp-16aHTG-2D*bVTL1aU*&m zn5%6VJv>Y$7l=tm_ZY-JCui<8jvoi$;&6>JnnP|3xL8i4Q?>*%5RFYnBmFgKih0a- zpy|v_QvD~~q<)3^io|sz4ac$lgHP$0dw--0PEgP_Y?85Q%dzEX(IQJ z85G_z$yk{j!PWGJm#m718*^+oxAV@>%>sXHzFJYf&aO>$m%nmT`;YAnY&!HV?oP(J zypN3<*fXZewT(q)zVp4Io!TaE;I-ObJG(=0lEH{qEZc#ZJ7{vfTmI>dlD+kbuwTE- zw}=v>^o6CRube z1%O#hNT!p~4*mRPayJ3lUshat%6qOZU2RuZMQ-D(b_7%I|dXR@U&dX||i03H5+QF#^MP`?>{*=2c8z>%Bs zTS9h_0FaOwPu!!iQ?^ki?CrH1JSJe10`u)sm2%_NUY!%a)2*cs!`QbJpX_h<<9@Wj zMuqyTs-VNzUlkv0;X>5vI_gSYXju4`@g_pa&`l>NDz_bsl?d6(-xN4l+G&PBC!l@3 z=I>P20i_U=1u%sfFyG7HuZ73h%cq5R73QJFy~`;5D(aH`wCk`q{k7Z8T=YZ>n|~qKkb3_f`ci>aAYzc0R&~_$(Sx#7 z>^Q`Fun;jR2{|T@{;K~TWGOuz-dViZf1liO2M~l!2bj&7_A3m1gK)mQ*jomTz&iDY zHX7Uuz1it15bMIypAd1(s{4L$DjWKEzj^~Iex><7a46+JRrj4G-p;JK=1y>2=j=B~ zVk^pcy;zEyylviC-5P(NPVDWY80@>MAb~}Y?zytCO8JdK90Hj=rPEs;bBaT z0@&yowr+Sn%<5yDZNi3oU)M${Dy_}HQv7cfUdkq2`FNlmE-_*D(mKmSRWkof9)(g zIxfx$@)gE!z7ryB3)XqoDAsN{oACU_S)R@o{CDSdsgk5?2~YX8`5!2oKIxnLfVg{( zFi(*brUz=XzcszGP~&D@*EK%+mc=#YELE{pC}WJW=_f-#^jwDlST=>H-frVq!zgTKUq^| zJVokXR2i4xR?^7SQ@jlNoJ?5{B76JJuXZz=5&CIw#sqD>Tcuz}N+Qad0KhkVB9qPr zZHmi;_yju-cVPGqwVM>KrWk3LJP7H_h^HB@rk^|sUzCHkug~vrT&5!llA2EdL6_x z39Qjs4acP#)w`4~yzzt0UyP$V@@ekWTEbOY?tE!qxvzj|dZkTiFxtkLJB8KcuH3UD z29r?K=>urU;XiFY_KvFU*EMPpRCn1K%iT{I74lS!oS;axv@$~s0C)DxKq$I(i7;3# z2rY6HW=ybRs`0h(5nRI~p6xuINX zv>WwZ^osRfuMe+Nm~>#DCA+)bzjqO8hj2S1{65fPSkL7aeR+=i6)Ra%^ zRX0L!Oq<*ng4;|plaRkKozo(l!RXFyDHno)0zo|V1}jd|3iDG_F0ykKz*a?;*fU(k z5e^a$#A`sTV9Y6AsR=1a(y})n5WkRGKn6R>?7&~vMw&!9M!)yigjy19aC&xmS>n%a z(6*YtAqleJLejEw{@)=9&>xY^|Ary_a(@!g984VlTNGk57N;HVhgR?>3ZY%usUm>b zhj)G93)-8?P4H27p(dbl22}M$oimjLN`lNO+c z6wpuFF*%!sUg;0shca8)V(a$_!>zL7#u~h*9|Q?NopWCU1!jY^nO>%um0jJ^g%K)i zqG0AbQbjN^1p6)mm>7UdQ+Th1|LCdz{D{~P*Fad$Rlt85SlhW7xK#^Ls92CQ{48D_ zSHZ?#3&dJOgtJd<%F57na~|XOIUL)8DvZb)3lfF^s2wXo_yqiW;rI7B47$}kJ9Xg7 z>mlh^OfNvLSan3HN;A!A8nC5oBx&mV@p1Qw-RZggyiN>oEfb5&S`EqVZZMue=l_0u z@*Zh2li~bUf5rb+@5W;={dRc&m`%gylXofK8u(8EH7|39wm8|Z8Tbxgn0$0c#I(qa zJC$}yy;&%42chZ&uSc}>oSHlIuqeS4>HPg+xu8?n?zs}dR85;ecRT=No|9A8qzoh}ejv~M&+ zF>G&1Lja=6CIiEAmgW1}VK9)ZAPHN{`ZGk)PTtA4i!w zuTFWNE2WHK>(F;AI!A&^)@BqbI_2yNw&BTk18X|4dDYxR39^JlI>-IyIR0~>ni?KPfRbis8eF7_!F($*-v8;{NSwg_Wx+i_8W|ElQsOL2d8tb}$;RGxtWDIE_+HAxqsiiz6>fZ7h z7@%e;MbXy{ll9t+$o+t5jn-v?^pU(CzjgR~(lGeHtmJ5r?W#34wZsx!Co8%YZjCW3 z;!c5o@E6`=mK(g!2uS}IU*8;@YxA@j+dOejPHfw@ZQJ&f6FVoiZQHhOCnvVGdEf81 zyS3kLZ9RWHU3E{*boX7;_ti7g*AQ76Bvm&hBm@51t%<;>l?l`E%ca>Mwy1+SE!Cxx zN#;(m6AdUr&pI5Rvs8aq29rdP)bhmYn&4C|?e*e30ORWvLryW!0Z^IZ?q_qTRzRYF zTh(*hZ+E?G8rcGM0vrR&1Sm)!0#L{t?Eln56P0CAB4F?o%1a=M4XEJKwJMB-P{W;b z>H@Gy1XH|wVLuC_DfqNUpv zXjg2HsPpY_m|FhI?dztbbGIx(n(2V#{=cF?)Py=SB=cz5el~fa=}-%V0T~xVM=>mcEG7MPCke_ zb+8Z(&iSB^>IZhf5z@XjLWrH^*m@lNtY_aQVaiO&hz`Ze;6J3*SXH^yrs6-!sZkBC zrUNBI{Cixs^4fYTLrmnfF_EvGyc^KXT!FL_QzFr%nJ}g6221{afbN6k=ddTUohVMD zN(Uu(md-bgyYPx@d(iAPE{{YV zyXP$s!(l~Vq0WegpQz4azPi{GBykU<8OSw{E+#Y*dTy_@?Y19 zl~6JozRZyOzog-neJi*=bYReEZ@zi(^ODfqGS=I zE<*6LyVTdwhq550g{tZlGOYzLr{m@*ji|)tAWGl365C-&G_yxS34Gi0M?xHS!r~+j z>#6~bB0Bbgw%*Ou#B8sKlVNj}mbLU=X#w)_*;vjL9Pv7r_yZ{QQf&4EaRXg>dW583 z2`WI+9*$8}X}rl9o7B*{@ut^Ne9=an#9)xH7iwghe*igvzlQfEAsq=&Cf+81T~F@d zTY2M4mc)}^*cL#ncy>9n%X3*RKZ(8Y;~6bHlKK+na&hD}1(z{fYsv{bwyQFzEKbsW zk-zrR`sDpn{6k;VD&f+=1gsc$EER7_n;qxkrNkA;%kCNq*OHGJqWF?v796C`P7>c^ zYQ1kc^vEBfr-C1t*wz{FOm^E8V)V9QM;nhP9P@? z0z?Nqw}|NSdTIvL&Bj#uI0IDT@$Gu*k+A@OrEm^9B#T}X`U(et=VjR(!RmO8&(wwi zlqvSw$-m-1Qux&3?WqBmZu?k;19Ax;>nC>+OFH_?5krp*xG9la#9qt~^xhn*j9tJ9 zQ5);^XTJ%5vjY$X27h zU04jIAn>5o1myt`yar8F&lUT8-668oXJ@h_lxL!%>E?0iGSxBNnXaN$F&(EoKMGk0 z95S7vYG~ID-)^jqX)m1AQIKS62-B1`sEeMNl_9QYhRJpn=(`m6-AKVa>jW}Gy4H3n zI7lIO7v$`ofg*M|5ax?wb=&}LBllz;5~k{QK;|tG-4X(jQ{$`U{x-I+m}6c-?xI4S zJ*t$+4N3hKQ9Q~1$R8+|iNoTDTYl>veEBa1TYXu@b1Vl9 zPNRYS#$X-+@U4p=XG{4CL|Zu4Bb69XH>Dci7|iz@gGolzvH1(xKJe?+8yS3KJIIwk zT6i^MWr8s0*wV4EPdVn?VX&Y}eKXsIixXf5tFeA05GA?VjRN3`> zB}*u42(i98;k*EcVa?m|N>!-g>aNqA>=-$mDESADOtn`FZfmkt+qq$wvQROGH04n; z`Yi{IYp7i;lPTMb*3sruB2DvzJg2SUG?{sAI{6-VJ>kXZd_+sz$v^7kwZ(?sERvw8u6}%0_@XM+HOVp`8ybpLZJu(RNbR5f{*xmG86hoT28YG(jntbVw+OBCRJiTNc6_>}74 zAo{OFUdb&Fk+^hNDa7=VP97|{$OXN zukOD$@H+QDCL+Wa-hBM+C$Q;5>+VY%AfJ?y#zyvk`{Xz%CZU?zn4Lr1Cug8lwG%Mv zOHVzqBK?S>=Nc7x4HgEJe&{C57Zx@6yni^1!oAsP_x|kWzQ;!(#@+v|=2higobGM% zx0MSwxnn^Xx$C;n9Q!xWd5pCS7Zv;}POOw~kA{WYt^93N+q#R%FG~ zyZsCT7O$zM?ZP|~=~;r_J*AUbv>t42+)D85jtbpOl zlQ==)+R@3EcmOsD+9cT@v9_h2Lb(!VnMrz#(cum=3j63Mdc9j;)lZm~`jL5^QAx@x z@71omMr!Tpf5BhP3SC$E zokDZa|958oRa=r~WS?cVjbk8NCp|yH9&w`=j$WV_KWYRJu74_(`wCm?ZR=f1Z@~Tp z)uy>b400B?hg-Wopm!oa-Ql@>%_nVsK90{<%jxEk!}@Q3-rO(qZG7$*gd_>DeSSt; z_69B&vwhtq6WHDC0Ghw)xV~aHd|#`X`di*wvC3={#1CygP!r<_kpmf>^kN+@l{*$F z6+Ka}1i9^Lp^nglkl1AX)pX$l)8qnW<2fA?PQoIYU>S#DY>cON2(4bHhH`?*QfEq; zpfY?>ZL6uoK6-lAW9N#G6Pz#u`dIW2#`&*YhIdW=Zv%UIb_KYyyaS@imjuWKQyib)( zQ0GJ^$#ZIvJi(K=CiWX7vi`FA!{TFR^0IU88{@95`ohY95hBNO8K zzd(~StwjM#|7r|W-Dy3xNGRNK0)2niKcY(4r#)K7*PgAHO}-2n&o=o!@HDRUj`#J& z)Ic3WBY%-5@uX+QL@|**t(VmWAYo$z1~~X8zO1&AO>#IGX?H5$o=$<7fVzC= zS{p*<76!qCS9DacYK0WDCCo`PbnAJyqBZF2-TQbVM&&fB z=lF<;wzFwbD@xkODmmo{7bxoD1ang3#g!>F3hc-phF>s*FJy^F4;+a`jR)RyQB;-u z$R@iwvqL#^3nC=@r5`%rvN(oYcF3&a;kZpu6K8@NP)Cklroi!MsU$fusRIQWC_SV>MYUKSnUXtkPNOI&0#6Jh;-OzVx!$sXX}scLxw{6-((;zs-y6dvUmuM1Y2pHLOZ&{CvQ z$o5({bn25G6~OaUm#AmC<83F2t|lq|e4ocjj6_Kb3(Q$#ZknGp&VgkEyp^_p7vVwM zj?>ssbqjN#)yg57zx)AXuQz2V zkh2Sx8V@__G2=ykF@PJ;8x-Ch+Ez+RYXkYR>)!}mKa5Dz-6Nvl*;w~h93$Q@E zdtB120f!hIC&}l@qtz%0kN%9(*Mw6$HnvA;uL(fTXDMw#StO5~)=-<&h9LNdf4~$W zFhU7t)QUxrMU0v7v=y|~-d+w1q*9chB%Mju1<8}vj=NG!6d<9~`ltrCi>F&2pA(pt zo%tFt-jHWxkjbj0rb%ZK z4LR}Lv+qXf_9}F^Oo|JX%a+d2ySzMjEYC{tsQe~2uw2?;d)lW$50~lDGx!LMo+ZvR zg>yC(_1Y=-ALqZuPti)o^ta>ZjKTw?M;9>vXJii@q|h}r*FxUEfM*;?u977E-cd93ZTs>YQVD>&DJ+hGNAF}3MHcf6 zDb(_mOT`Yl!|w(}r)T1ICU#3dD?rLJ4G{;4K%SHCH0SYH>TgA&hOugE`@*DeVsJ zdYj59VEWB0t^h3q$nS_r@YW9vK2brE0EWvb;mfG)=h;|POW>HPH#Gkdb(r$Ej`-BP z86p<9zqHJ<#)!)7N7Y%`Sr>F0j=Af6@8vxRY4W_(-cM4r#IqVE^L0o4?XUn(kvJG_ zXO$Acq*|sTIU?#~I6qsezfJsdmO4&s_aUgTDH@X0&;TcClG70jaDIr)S9i8G(@932 z*==>*Fk30h7_K{&DYPQm@nBO~sySAZ6(O!tKG`NxYd2E~(q$$oqF+U*N@I1f_Up(7 z+YzCjyKz+w23%Mdm$t4LN|Hm?RufHq8O(2wt`jjwiN>Zh)xyH+{0M;eRcgni4G{woo6Rh{5ohTU^#&BeQncL_m%wJ%ENmrTu@#8g)^rOTTsc90m z-3Ir_WF*f)d%;?UQ9MdI#;5S@Pxt2oX~Zg#;g1)bUxB^fxaGc2W)QMWG%^Zft+R{nirK|5_bde8s1!0 zw|mm}0dCI$qYu||#{3(}nK2+6uEHx%M18ITb!pIsZlbbJoG_YN`HkqBGw17Xv%KG5 zo(WA!@t&WU37ye!3*{_PAAi!{P~H;jgm5+Klkxs`(h<2A@0r>Rh&kL@@JxQGIWS3b z0yIDR>Aka&Z54J53;kU#?p0)wwbIL^dR1ZM(&s3J{&xInz{_`SUcIRzw;oHJjoV5L zw`xH8W}0=WjJb7F%zaRB2jt;}NG*?#6xBxfZ_nhTo zZf9FY8Z7Sb-JZhW|HgHwMPV)~33*aPej66?_Ge z;noFvoYAEG@(C(-htDQ2zQs~nHUF5`Up}TYcUPi z$Io9We5~heFt%}AtM%(*1@jZ9jzy_g?J>V@upfu5R?Kqw`SiNTQynSo02`UN1`(YZ zG>I(?%_B=}ly`cdK)K4OKXE=`gvn4Zxe+h~Rx~S^ovv2NCrBcCiJ-J15|1Xbk7(Mr z^b;B%!?z|{Q+TE18I1Ls$9CW*jR>u72J4G^9tDdYAcHHcc%`l$G#`~l~GX)~m zH&VAO+}K!;t&k{r<5os`04GaCQ`XB~tT4};nggkWA1C70@P-3>Q}?n?;nyrs9C#Ae z#yiedH~953-zx05{UfFD;e}NSWT;Q1QU{cg8`;&B(I%@{v^q=8W#@}>tSM_*9X?9V z7~giFMWTY|;1&3DvVbWgL4MDAOm3wD&DeN#unoTH)_I-jB0yWHe2WJ=k+UymU@5Y! z*$jo4S1oiIwzXPBXB?I-MtCQYVn`mLOq3tp--P^5@j_D?#pij#+$O5d>7hNd7aS)6 zv%_k^9{TWzH-H-HP$^9;wRM=WjN*Gz{`Ct4_Qd1UWZdYWI6{uo^%`Xy-YZJS_ov{Q zG%j~QuP-}146q&90hgxXaf@vgsiigO3KWmM3kLZQ8ocPQg*RO?g+UM4(-~`KH9>jX!t`ChEb+4MRSl!dTRtfn$+mM7Kk8}+qq?n*w zzKcTPCc5BFDk{`$QJp(yJ(p7N9BB8n-Y&k3!_Yi{7uK^MEgdkIK;$fa5(u2%-=aOp z0IqZm*h@d=VWw(-E*A9AU0w3qo=)uM4*orK z6EIAbt_}AN#5vqX`C(xV$OBO# z3Z&Fny01AEnm?GrL{@=Oy|9Qfmk^Y~p?WC@M4%oA>{r9cy)v9k&ai8x0A{DQqB!r@O!{8(PK}hgt z;6I6ZUXWrK%4+3lxz$@Qeq{0Jk|4f>78cT}a!mudCM`|ERe7u=u2+N7PZ(|6Zo8421a5h}j1b!=nO0|<+SIp{PY%{w zT4a%&Av#QYgklI1ZpfAy2)^cG#&$(XqcSHl8e|U|{obiFT>GT2w!@=bGDIW@CMRKw zEoQ4Q8_G3xSa5{|I1xi$MgC2=fI1lZA*ZB1PMUHl`4ZC-|_f^MDT3TDDb31LhZH@rl7LDVs zrw)G^lu#xwb;N@?Gd%w?@iDPqufUuuDlZ5B7K?dGV@m3ObD9HuauPVV0Qzm0t{iKe z%8-A(jeye-H+VU%6KgV%^BZ)x;Qp-9V%Q>6IGBrW=SWHQpV%{G;srD6Rm4@#D!+-% zLg_fB4vjlY7YT&FU18|PuXN133#E?;)C-yLH>Jp2@4V=xmLt74OlA_}*{~fPve(8P z^vp?tv7XLmS8Ap4yGcFV1&sHPBH&1ED4oxWT4dP4**Nj)MXR>Bhi;ea(%H^v&(Iw% z?#N5g>Y5J!-VARIO&mP2^mgaqY~dEhmD5AuZ$;kg-T|2z@2b6fHq`gz!0zS-R!`b3 z!f)$f6y(8`%gV2g2DLU;+oPq^rdQ^}={Vta-#7A4#e)d~vqtJI1SmZ7A3Aop@U-bq z9wHmi4a`b=XoU`m{PxDARz2sh^|AjmA}38C7nsI0Uk0DhLZyA=8E0m8Sr;qAJ_-K> zHrvf&!Zys19PcV;oS`{QR_~;(J}NqK)xEEG`FkD8^p=aYwRH*BP2!RmS`QT|F>HGng9mA;yPtvq8Gk`uHJ_rha$ zWC_)HA7o{5l;=!Y%rcl7j|>I49>|*4iRn^rUnyFdr?Iusjd{-sH6@;hyb3bNRt zCn+7y;bAtvxvWN?wO@J>^y}y$YMYPwJF_Tw@VV6Pv^?w|iuYJFBP%&nLG$72eK;sh zyltU@zFj2lDlkrL^k2w9MD|ars9CP>`rRpB{Oo@met)gBZEMRaJE*r#9u7yWZpDRZ zZ=Z;S%x>GW1C*t-5=2z@=yuX`K?}F2sm7}2qUV1&Dcgmd4b{7@ND7Aa!;jG*fKsbZxA)y0G)D5#z>NIYTj}|UhtNZR8gscpzgA?6K(yoqVi8{=R znu9;oS^r;|s!HYo#8u01GOnfW(HUvYU=gLHuIQdrjGX*i1M+_xIxfVT!%Hfsp8~+o zqrbZs7+swg_@NA@+ZoPO$g~>b`K{AjF+TnOdw6}Q{P3P~rP}XKwfrB&wT(uB1q(pq zX#~88t6IK|TCss%`{iJAaYEPtdV~D$;8gyP=Gu!bnfiDs6;NyW4l2LcjPO<}p#b0V z;rR)nGU$y$iDQv7X?s8p56ZH7T?o=y-Kd0E-XfKQO>(QhW|KGXRhS4C|^y689mGLIQZY%C6#fgcdd8B0@i0l)*kW4`D{ zWb)1IVzzDrYdXzd4521+ys|)~NUS{U=NsUJ%pghz)5_sZaW~!ZBDIloN?WaQbq7eR zfgd{C=8^Ifb}vR`fzg}xyFCnV0~R%PD=y2CeINMb@(vE?uP}|$XDC7G@j>eCQXIRI zgLLLM(gK$Q4#8l76VP5lQ1!)TV&ZBk2I7j49G=McKbx$)q?f0$SCQ+K(jHTKl>ir} zsa)$6z+xq>J}##?a^L9xvfB7ba|N_?o@L8lVlMwxh+w>7y4V>FQp7)+;NOO)Er+ z8t^}W4D1!yAlJ~aj&InM4&l@9UP!&-agCm*@`jaOydo@K(l`W@$##*GP8NnzuUj2Vd&{Ot&^ z2wbdEE0{UPjnTmgtAj`5<_mwIEd83%9r8J$+YOWlhaaDewJ=UVMNG0GA@xyIcj15@ z(}y`bJbZ3IQw7j^6G6;no>lFb0;e}%s1&t6b0qqJUi_vY)gAcp%DNo?Na-GQ%$(N= zl43L4Kr=O-BXmMxXh|ZzBtuv34?0nQnc|BksT`nwGR)d)L0w`3&22X%{GfFLnU+yR zuy{~fZY5D8V~GuWhU_lPXOl%($W|OHFDeTzjUFmZF9QJ4!pW$?KRC31r(GdUXB=gP zA?c?gB1|LwiV8ZMk*S@ePal$w|HReX{b9P5#nuhg{yOv5@S0eFz-3nt{`FaN_@|Qz zux}WX0pn-lwVS(mk_!|4hISn{wf2A`2FZA%-R-`5&A4O8R?O&aa~&=-$E0J^XrkJ3 z+)nyEI|g9s7d?(~;%4e%?95uzS;JzM5V9j>DGspJbtc+rOYjGVN89(!8CV z2=~Sc-+xwG#MTkBjLpben|L3wJ9k*NPN{4YB^E0cF6q1j&x*6ZWw^&80@POz%oTUl zugB*A?dn;WbTYE_VRpBBi;cv%GL*RA4l$3H10WpvkKU30yf*lT`2;44l*r5;*Qbgo z2pLb`PWj~Xx>qfe!|PNDfo03_c5|6)f?B~yH@VC^kL56GXZ6c17FbGdVSvCj)=52l zyO8cbOV}jMiw7mC7ohewRF3Z!6{Kka(yixC)k(`ZiqDrYRa?&clNoF%?hXltFG2lKGC>=sj*Ur0c@WxxDpxEwX->HjLIBKr;l&_CArT=v6S+Rv(m0)_*mk4T7Q_g0u zlw%pUB(8q-xG=bwY2i=Xb*hYfTnSq8&K$XP<+K~2K)w%WSco%EoLZZcL^9~w&AqRk zmQk1<4ni+2#8xE1Xk@?x5|1fl620;P;9hkPw{>j3Q9tIDOcYK#cXHu_hA>Nq^x#mn zE5b214Yw`Z57LuAYWZJYuQrY@wW!Omtc`{r6wF;g&;|ZvU40$ryq|q3{lV0 zr~USIlm*Jfx38Z`iz9;`pt$vME*L2vu7Pc7rKl!&huLQu*9c7H0aP)}Sbt#zP;jT% z5pNwkw#L{CQ#pnh$i1{XfoEBuji{;Jyn-Fh14`@CTzZ(>dg-N^JcwKung=08Rz zae{UN`yRFJ@qEdm7f_5^(qiIce!!DFOSwI#BwM@}mPpwQ9(7#wB<-wg*WPv)z~^kj zrA^-SDWbP9Y@PlI#ksz6HhufDJy$5+Dc_wuf^ER_wSe*mkOhyXlEUaq%WR?2AE_>0 zh*1%#zhN02NNUEx$VI@xz?H~b8jMt1vvPB}G}_SLcOte*v48x-eKE6TlD&{@wMan0 z_mb8xGE5TJz>kgzt`G=i$?%q0M(}|mZ2})dk(o@uvR%d3ny>l+Sw!7_Gijw%`uVd+ z1Ue$8lgfM=pk>YhUT$IKAZp}-oETsG5xI4$M0J5mEfbzmN0L1x6B7h0&|R$S!i( z?+hokko0$_+}>7~)A}-)>=OE{Omd|G$gpp?;Wd%7rA7Dh$Bnn_@;r;_Jr991y6kN1nxCJmi`RNj`o;cE# zii`o;1^z*n#ANi`SPEvXGts$_n53>s(S<;qrlVD5VP)Suak| zgN@v1bjze-yfgHD?K?aEw~vG5Tv7Bx-QxX74i|eL>>oY&pB?Nx-kt0&jxlOhxdSg0 zfUhHRo|zJSTB+)8wgT4tkZgJYA6<(pG(N8MVkU*I?~Vg5+1#l;EFg$?g03v0vy+*#Yb;# zNr(Am(0V0D=UBqqI8xs4VnMK2Ox%7{h5J1PTQa}y^}nW;yjj;TE)A@um0kTc?+~}8 z8S9sFErzf3EgCsnSt7V4T%sWH%gft7;0iG!UwBDlX(Ed!$$;gepqZ^6^7D&YOo4yb zwe+?U;kQ*>+|65l%>sx3*XqjNRm059%}J>1pBe;Za8K`u8m{i7=Gbmd?3V?})#XDu zq-|@wy27?!+3sm63|MW8tlEUzspP58x5A|bDP{u5^Y`M1Q*z~GFhs+Us6j-`m%9vS zqJojAh1|@l_$X&r?Y7wm)zc3?8IsJH$sOz~UIYXPI4}sQkbs3(4PqgV*5mF6f#yry z+rVTFOo*uUhSaH6F~oKeO`e&_OhOFCM-*F?h<^}kmroi6&&GyE%xgNCYu4f6T!)u) z52QD&8^1DX74I*8Lj&Rp$O9MwrRj3TyK9{l>U1k2?6l9r+2CoI9gIZMp;7B8IjFW?cxOyFdxNf7+xj(lJo00SWd6C*1w-Yi6O729p>j#=;HZl}>htxFWHby!SeVs*4$G0! zP!XC(ZndpRfkk>&GI6Ord#DdV1u`5n2Xs@ZR25;{fTMoIGH-D%tEjZO?6h(EZE*nI z-lnz9r6CRfHuk%Y06M3JT7~YT)5D_gPkCS(Fc;un$2h!4YH2*ZyV#1#q5!sPG%P^) z@r-Y20m}UX6ij?IG)@3kp`zAywA&1e;4=jVKLMO-nns8vZfSvM8eb`YmfaWq2Jmwe z;o1fUD5>`Tx=h>?clFTdY+d5@;c{Im%0dnYJb7FIv&uY2r**c zoiv2&{o$YN?Y$yiD}47&ga19$&?uo&a?iNL9F;>wg~i%X}5gh8o

    E%1 z@(p{{ReZqU_k_*-;9P`yQAxE06BLcR(j-h}twpua(MzmEg=(z=WR=gA-b zIBpD>Dv+6(qni;myK4cObXXw`saLO4$z|u7)PO=^E$*6J_#AO7GSBfybmZ<3bkFn_ zTy%))K({R2ls@AXr_XkG0x-+P;TQKvTxjlk^;JV9&3e3NUU!?@hHv0yk-A5(RpPlS zK6N0bF=xlo?p`BZd?9V`^2l|yXSqCNkpVUj^sGWGojBbd3)TKYIv>43A&dcWF#aOk z3__gm&@+$HgOebxUl}fWjYY)y=widm0E+;lG5!m*IQ>re?tdOH065Dc!<9giWUWWO z6xksnCnV%D3U7cSTD1>V{z&u|eJ;92+{HP#6PQzT)+KH)>mNpgJuoUjU4^(%{0-!; z26WQBiCAvFO^r-fMi-Z%woJN>!aM(4C7ZMxvkjIfNX|u{<s+e0D&ScQQq@TD8GA546q?UBM+hG|n@E(i#*%M00&m4G0)e{nda&8C znva$5mquQ$B!VBzXLgR-t%UEK*lnCnMvVen($JUW=NsO60$N zB-t+T^p4Kj(KUx@1KLF^Z33WBH9rv_g6pP zYio?W&AeTB2k}7Z{`NRtWbeH3D-eKGS)%vk-dTqDC$bFDWyOy_ z^Ns57pk~@H{luw$cW?`Y-7EO2Ygv&_SiH(ZJCPpD|UU?zyW%?2shRz$vA z@-OIp-HX`LtQa?WSdg_~c@QDGJY=;wdS?JuerwXlS2%0XjGV`7XSGieUtV7T z&@X|iHi)M`y2Wo(1oz*I*`9n`tE;R4UI6cxR`yimljr%zDdHQ>r&o*9>P$kOQY0Dp&V zXOq^w(-hQ9r`d53&2`o0by9aorOLWpe+t-Ie5!2y`rQc7Y5wemN3`*Njuj*D@}57U zk>h?@n4f;PIcvJ`9}YAW*_L|K^F3Syt;XZNf5o}5!{@zSnr+_Z zc)WCAzu9^t$aufbkKuc{U)bj3@_`^O0|2@8qsa67i?sY8=$Tyc*L@`A>f_xX;Q%Z< zaOn-Czfg9i62!yJsejj`3$^jtT5NPz8Z5C}bu^YY#;`1M_N1BMSx?r|Ht|~c47K%> zt_#}iHo0r5Y1yscyJJ)j;Oqm?RhP@#|%54Z89xXyFN>eRi$1kz>VhDY=m_2L$_j0z^bLb7|JN-x3t zxzYa-_Ga`Xc8Rzt2SA?LWi(69(s7e@d%Udw;#ISMT&kx-F@qQQst-FpHv>>kP4H>C zvYy?)&TGkTgWA7Z_y^B77Mo?r@@^h47!@x8Ja?5pD2h+eUopPIPt)97E5={ncG@20 zRb4CF>r{37#@&sMp^DP$V7dX%#snKRbi*M#(6`Zr-ajisstvFzg1vSWR$%1(q0=M= z+VyF)0|7mq*Mt@Pf!+Nv*MJ|^0f1h+9xZtoyFO%g2(euo zcgU{a8ulPtLHpOZ6Tz_deBMA;y>Idm+r3XUD3m$4NBro6x7sUUi}J86@{kYoh}b#E zwn28e&=@`5E%3G>LDxjq!GkrS9WMyah|j=l^pH-mKgFO;THw^|*#Xf#vFtD#I|AS= zCE#>hfgbGG!#k7g7%nBlK+HSrxQN|7)hRKk_C&IMARXXj`)JeyrQbJbv*VfRBe(7F z?Gir@OJ{@)s{0qR!-6tEnHgbW&j$AX05RLe4bHi`| z6onDlXI?SL8QI&dPYoC{;9>3Q-bL|7(8~d@H1BuM2#Ip1V%_!D_G{i1Y%s!1BX(*$+sz=j)2B-YItn((4ac z!9m|x&|xS^Lpm>^&`6xdWYg0l1qt~ zF=J9kcB)OSNJ*?wWQ~|KHL1u@so|)IQ>ksONL#GYR2@Fm08JmpUahPMn>71gytn?@ zo=IaEv5Mjf*$#-`9K1A@T4ij?sNBha`Qgh%Fg|>9!<{X+gZe_O+heyI|AMAFQhaN% zF%Z*x^6Do7fRPeYn^WyuA1E3}m-+=l-iZk?rQinaS4V zg8^RGkH;QrxzE-eU$2OHUtY5E-1sN^}W6)c8^ zlU6WWk_hW@I55r6FdFKgYWyM*`&mRp=Nzo*QJ#W;v(+=6n$xr@9e%GwnGEVCG&8;KdRoU}; zHnFtPElc0tL-9#i8-xTNh5^sy=65qK{1&TRwe}$7&MOD{uW^%7T%O#y;ESH6r)&Z~jkxN&cHIMdr2|uoQYUuT4h)A%SH^Lv zNm5Y@gq?~O=5Z+>=tCqhoHC5-5#lS3s87V5tI+V61jECo;_@ab6n{j)k~j!W%qr3g zL}B3_{p@Fq6yTxB(cj7Cj@Z@D5&;lS=l%NgbgWU3d`I0uGu`)is9`Uc1+F_$kIM;I znRnb-%t}he1Antg^08qZkMOd_XiEp1LnrxTO9|0d^W*Q9A^nA3T{g#BQUk+&);W*S z6ZO_FtS4er4Vi;-udU7f&HTl)SBYSL(cOM5A^m-0N!hK!r!AcIx~z>l6N&SLPR)^D zV#UNwo{|x)cK+Fc!Z!F=`$-C9HOUkfgJr zN`+QAMHxV}<0>z^a0j|_2wRU*&3>B0V#4-iKu9S}cTBDC)=yK>Y_RR$zcX{n8nN?! zLObeXFa8yA)-w<4XHRnv2xW_IaZ#=&AhgB7ef+%4RRG^9NaIVcv&QKty7feHBih8J z1e@loO0xWvEPI&lks@9Oi97cNthfg}Tm8r z^p*nO>tikWxY2^l07L_146-fUYfMBbLX;p?6PJY+(QJst%3u~6xrhCy2DWO zBK*uOx@39A@wz(s(q;OrC9$iS<-e`E#cJ%de-xIm;Y-Y&wORQwM*?%@#hZUaq`^AD zFBB%D9>RG<0=Ok;6Yb(z93}ittcvIFrRtc7iRPhKrz*}TCXA0?x_o9@Hx69!+3kBm z8X#w&Wz#d)TkvdhITMPzzx=#*LB-T@EipZ5y=Zs$@sqvxBvH8zWeIU`NqtZxvgzY~ zq2J<_*8QBAnWPUx52T4!6!edu+uLKVwb0z6lF5fh1i(r#VzWRS$fw&%yA{;85Z4zm zPTogw1qE^u#HHfKdEnPgo59|Cn-(DsR<5B!qPcpe9W}A!CpoNB7zCC9|qFN zwj|Ecf>)|@Tu_Dve)(FaBPD+vRWZne;>(Z=EPv%Nz+qF1O4SV-P}GSd7g*p@P@uV# zalSSf;jKv^@BU0fXjJs^Y`E0qI=kh{LSMP20PH2euW#wl1022Xx_q9#FHqE(?BY0G zWnxJWoVsM|zk3bgqB|;bZueH3oRq%rPSar0y5e8<+JwuF_1=p`muMqXV^g>33#P?j28gnS)5;$D?ObJ@nE;>p zDP9M+c)6CRy4Z$kNlA3FMITSDJZHu5z6Wmb#@{NQHvG9;6DF!7<>n9Biqf|J)j!uW z1^M<`=9B_1PMYX7vooFf0DqBieE!ZrSlk7}C!0CDi~Opj4p>BI1aL&B!(&H~%EXsrRXbQ%vZRTEM~$Gt z22)r_Ml%Ye28fIqRw#hLkyBJ4kx@ii$V+iZ&ryyr=gy$%!`Xw;V^FG``V3znOikQt zNeuvWDwSl!#WCt*`5nKqHv`t`6E`)8jNk* zHg0U&wrxAV*tVVA*!E3sZ0E+d?M&XAsi}HX_04}>-K+N5r+0TB?A>d{!|gvp4}<-p z&_roO_0-L1sE$q$_sl=@kY`gL6dCZ{J#*=5PVmRpQ&t%ek=t?UTtrLQFYAo@E!)-o zsubT=Kdbi3j%6H|!%M=mHs^g{UmS3Gx=^0jmF6jby?OpRsm5JZ-Hugb=QGRhW3JV) z9(v0;dmnb(e2ivR=D#z+I`7@s7THUW&Itj}gcvo&dOQ>dn`KGIW?eKdXfn?fD~_32 zcFbKfXWr1T!$kW447nHpw!~gczdl^_%UrK?={Qz^OYBPtbi?bb4KBM}TN5zVklUEh z%KR+JI|Rq#4Rhx=@|SRN;(MXh7QKosfgwNK~Ek zCR(etrlgUy{LS0-Xa5n*tJh{^Y9gPI%l|BGsaD@AGIqb0hu2SSTR+k^r%R0A=sNZ7 zrY2k9G+co*YTtx(W5l+{TmAJ*mqJgG)|*3uO!^e&Si5+-2)AmV2^}yszu2H!mz*om z(T8S^DRhQPu}Pul_&s~|6==TBkeg^nPtvPB7Vk4_T~zr{AHGToc`MX8=i7X>JgY<6 z41hi`vWns#hKp6zqEppspR>(aP|^sgGk?5XP-5K=O*%#UYhKu<*|Ditys2wE~iiDZh*6dA@{rfeJ z`kZ76;W>7@3dNs2bIgkbnnA{_wTuHo!W1PjuC!JjK+qlDD$y^PHl|YY%Px&UO@N3f z{!o%@ZLZVktvf(UbCg0V^o~A@x>M>+x!SN)IaIfhc8SrPO&QSRURW#N$5hbvN4Cp) zGD;Rhtke1=qZ)pP8#I-9x*3#MZY&tj40uuntsJ%y%nWi0N*j-ix(QScGsktC*d}^C zPQ?w3<1?Zv7UA+CxPtq(xMRiT9eXA_&m`X)C*GK%Olj6gK-z6=9x^?ds_h|#zZ;Lz z4`Gi6a(<>(D zax%YimA|(6%^QliH|UDLeqC!J=NsjNu`a29(6jd{7zcQYqbLTy{^Jx=lt3Qcoks_v zpE7hJlRx2G zUADtrb^uuP@CkV9kI=!Dc_bVs9FHh$0lt%;`ClVsm&7qIxW}N0XSa=l1yu^z5^!C` zxkHV-i>r%^%-l0PtZ?FC8YnM{PBg{q%!w;o`9fJeCk z#&CwclvxY>l$%&zOh9Iz^z88SEj|iBq-{hiWboFQ35_ip z8|aLqCE>G(I$6Z54ujNS68lDNo{Gwb>8&z@lvJ4H$bV}tg8jHuRiivm`l~aMU#38? zRA#Y9&-&UnL*hPUvTxf#@b~R9K%SNR?flaj>a=F|6N2{fq*?jci@HRFrexc3(V;87 ziW|C8XsIvctx8qu2ub1M;oG>yM&XG=yLsGU)#IwuDYf~z#iBOvjj)>fE79<)#g1D3 zjP_89v_$A3(`ysK#cESP`_TN&R`n4hk0a#8%@xB%jrz-TI`;G%bcp#c8vOr?U>jS* zurZ}K6a!NMnEtnJT`y_VI)n)+^!gsHV?&?LI%bnTqJEXZbB@sZ9VjbiT`-o|oYD7v z7`rPJ0~I~nOvV! z@g3;#r`R|@)HJ`v4>?~tgm%H{(b%kCleH>4JU+ncWln0{yd!GN^=}5>l9m372Du}r zyz;**B&$;Y{z%zNdIhRN6`{@rmQ#2OCIy|us3L7Th<4$Dz5SDC@b}xWg%yz!x70R2 zI2IftMJGoeiy(q@zE37TeBio^j3S$n(jT1y&g}?m(%+-^a(mQIW)jZOi{7 zXRlT>gQziEz?$y91)>DP!kSJT0!;qHc*l}{;{=TUAL_ewr3(<1bnR^rsvin|4z~Xx zzuVMXk0bs0b3eas)&;1|ixL+KWYSXIU!F;jpQr&J>>rT(7a>&LW;cFhigpw1$f|5p zmTe<~))0vn-5hGe_ov|H_i1YG*X`qB8>WO(ir2vPj{w`J!tZbGv!c=&+^;V|4dIvx z1%<1=zE4*e0AkmM-(jHB$?}Na16t6MLylY49SiqTw5;Hml6kB1@K4 z*=H}Fad0dr<=?A5uiG#?vy#ng<9mBU`gXs+QB`OW0o3V?0QrtDx2i6a<6gh+56_0B zriBqkMpr`7R<%|Q{)>8|0SbXHuQ%3)T!{##r|l{~id`+`cZGEelU6kKpVRQN?Z={ls2@*@+Gc#C>DZI$YDPp z*;r`>%+h|m+A!Zp{pE9VyYyKH1w30Q14H?lMP!QM!VVw zXnVCL%ZH2wpDo9~SHE2FecAJNF36m7OZ;qB z`W32GZuTS8{%rP6!Y)cDx}Y`@GdOGHy*oK;t13Fpqc(d=GyB_cGa{}%xd5nWuxuQC z5zjkl9a>ze;clI+xXhS|p#Ww>6Kp{TpblBfvwTs-eOYU^Xj|Qr;eRZ_EbWU4WS$|APo1@U$u2j ze2_2&#EORL0IF%Zn)#sexCkVyVen57rYINX-(n7y8^JWrLfF96Q(~rx;!I8K0GBz= z>T;mc0-%diWA)vEhwwII4jzzr^2K7wG9`s#0`#|kckB}^R~#iVg`)A3S|Vx^?G`bJ zW~(F`TP+I?0MWU%AY_!O)eaoY`3I-5-+zi`q9gCodotL=4!jI^5dP^T2Cwbg^41lWh}F<{M@KMZirx*Iuue}sYIP`BazZfM2$q+j8e z#iI(?h!I-At;YTrD9HeG>n~Y2h}pCmymZiPr51xN_oi&H2A>dndP>j=GgUYW)-wqL zz8)3g}1U%nczBl%WsLw5H9L00|nVpHcz=ozx!66r}uCE=NZN=Ie3`n{-(mza% zzgYvK4#3NX{>{N(V6LUK=~yWd+gTJ{*2cN>`)cQ-T@T>}#441hHQNwSAOvDTSRyq$ zNwX94BbS%ld8xIaZ%;EdbGE%Z44dUsFd!xZWDEZH@g=4cC4}+dODw(GZA;Z^)0X@9 zsc)(*Gfdc)$$2$%aNq1NJU~xC6+GFZCTkIQy>U*yX#G>Jxv7648=uz3AFc$^*FyGF4=!FE(3N5Q;$-L$-ZPHN;UXJQ&I{!$F=z6Q!vtRBQ&>ASjxc{kh{%RN|jUN(tEEdHjSb#xc>9A6Q+4xt51DZozyBbo*v=D zYff!g+ZG>2^*JUMjuNZwx~@C2Q9oC zQk;1la7M;Y;AMg)dk4hl{suA@rhm%bJe2PbXYL{0^Nn@|R+Jr1Ok~j*D+V^sGF9P< zBoN(~#cie9G}yn)6Noe!o*WJY#7(~PzTVI2I!iksfL`ZJvV+`lebD-yt3!FpJ*LypXaf`{A)>Dbq0v27GorJ^xjpJ)N!h1 zhS8`{9|M1yz^7;%a5+>TXr;aad&e+_XlB!v!3V}+XH;4-_U^5PYDv8mJXmo<=# z2+54enUEjp<^g^_#0;>pZf0bj^dRCQg)Ib&ng?vl*riSr+0Do2j);;JJ>+vPHQtq= zh3tEQhb_czr!$)R+fKUBZBhb8n|znLY<;>zFE7(S&x3)wty~AQ=-`RD!ii}w!S95ov)V& zl@(gwOb2g@?F&sHm@`##e{d~8< zdbhuurR?k6e$JR+^I?WW)=R`NeIt^MdIM2Mj5Xjmq(f$0-$QAdDOXE-Pv;;N-Sn8f z8ViahX8@Y=QYV?G@VKaeAwXG%BqEH%`aUvQ2nN(4x=z? zDZGCmQJSeghCIypDn|6(6j0d9YJYNd?a{$AS_bg+Rt*?)ak~r%YNz`2f#`E^djxRp z%x>t-_=7-@YopF$(Jiy?aG-dWq?YLP^#I{)p^b20wzA5Bj4iCI-5uv;y7Xqn=-+M~ zRgq>t7V^*)&Kfl43{B2xOfBF%oE*7u)68i3^Og^5iO1DvrL_&kT7%mmL2YIALgm~$ zY$9`-=`fo$ql?`-Y$C+|>%x}){nbDKPSf0z&6ciI+j`oQvx)QiBpVHx-!gzCk%hn4 z#fMBxiQgy@G-v`shBs;VE zw;u`fNfUbHpw{7Q+8?2CMt@w@i*WL(Cv!J?pJ2` zq*j5@XUH8~Us~tD^&l`#ygmR}U{=pjElyFU>fQ$;w>yVYz^8gd$o-6}yys5h; zibIu|dSM0v*&AYI5h9I+3G>iJDSh&Uacez6X;FyKYs2m-^?y~^DSTT=oH(n7y1^kL z($jH+$;MXs755U?bg%>&3gBH_*1fRA$CjMsn0+F5$#^ypE99n4@3@!`T_)Xt!n(Ou zF;4{rj6|RJCoeUX-~on60yXv_#8NCsPLd?3TC!uKe&f32@x!E;gdJDxNNSlTW3hq) zs+Zop9z?e$ws-=y4%jpL)g<2fFC;i$Tp)+{2Qw0+>XZH=q?YNmmwL_YE+Kr@l_{qA z0>!T^$E}cA*!PtXSXanHuSH8O!M8+pbOxtG2NeIZuA{qH5&1N4+|+`CpZm8GF&K;z=-*Ad}}99M}5n>jv~w$W|$65v|XZ*0x?*o^nWx{_N@j%K^;(%zRgTBx4d zEQ5=0jX+%r0oTB;(bnJ;o7f5#(e`GfVZOH7SnF^Y)GK>@&RGH zNyVd@%Gfsz5vg&V>v7ps2Gt>DSLx?ZeW)XIZYsMw2Be%Djn&J#YkWTX4$mc-#}+rP z@g-JREaYfC%*uhOG*xf)A?q_+tw0$o4~2cl|i7Ts>W z1W9h}ZZaF_G3PDtaMIE7E4J?a^kubnW{-SX|W zYQvZHLc(iry3qmFJ)xMP=l0@;eoHLe>}^{vuaW+o*Uxl?buy|1aFN$`LRdj19&^$X zq6OE-XV>}MEuet!0K^+!YnmH4;A*b zahr?gl_#;t^7R5I>^YWPh`e|Ag55If5lQH#+rzRf%uz)cBV`D$D@hp5=f`Er7 z+r2KaV}|puh51jwzj#ye=aI94ocQgJQ`jS(#0U8B9K0X&#wxcGVzoDn7EQB-FI-}8+hgy4sJAC4hm228y!#1W$ zH>M(O?2x5a2|=J4f2j1n@W#i*&L`5Z^A1ww4y%#V83p)5)d#lw48EvBS^%BCuPez0 zC5qy-e%(wq-o%HE+^6g=ekPk=;&coNrz!Xq`wO^Tw&UEzfVTb6ttT3DrQNBrkCuj& zhhaMXI`MP20s!ng2So2HT<08u^3%Zeu(c*6N{xG=R96NQXEyHHZ?tB3Yv0PdsdQra zIb*#P-A}bv;ruhmKOqPM0ygUr>6B~>?}ql#&&$v*1<+P$Zs^mikNzqby;2fuy;dx(#iA}sj6xM9 z|8VFm-@<}|f`#tuFN2PZ!pqZ(sF!5pQW#s4sNnTglaw#P(4zHXwPF2+{Zbk?4?ba1 zNzl+M!$7t_u~m?C*i_X6?u`Zg&HUN)#_wi`2qn=`05Do%Dbwe`&87wc{)2Nu@UgNs z)mWr3hU|*KHV{}=8;^8q^WDIyNfTL5i}U8G3$$NfwF2kFLuf?>P&1d#A8Q~TY zzLN6j0f;?@q!`%_t%69yyUb#f|1?^A4ubh8*+0wYT5@9$1?p*3lWYe0Iv}#i>7P;iZY}jH*E(lTY4IZ<7 zg5NU4E@qI3;|pO8gelwX2xJ1!K-E{|R_&n;7^E>3u2{nGW4&Y}gMW78* zUx^bD2hT!Voety!fRq$jK}z5}1vJCO49a#P+QR~eiD>8lYmGy6Z5$DTUdU zp%ZLH{PqPOfWLI$Op$4!kI#yd=a?jHX>l(M@pvlIz*T73XJ$3C?@c~64qNug(L~lXP&-p%q{HJOFYXho#3juHP$Rm;Yf zW(TRhi#SNQfUX*=I(vE}sx;BpP?w`9IHK!MIFmfj36 zS^BSaq$TD$+A0cEMHdXi(f>dJKiI^JjpcN;WNeu{aLwaOvXSn*`e`q>O?^V1CF&ov z3q{cpS%1b-;xaXCk~4*t$4)Knl4c{aVX6e#ImWfOaLxIDd~k!j>Qok6%mFXQ?LQwy zOL9K=`6$t_Cy>we1up!s%^mCm=s;9&$E zM{90%yxQ&`-baBGFxS~}l(?&0UD7Vq#2~D_!Y1raT>gTbE=trA^CW!~lO#PlI*(Xk znVP{E)beqMp&3gDAZgWW)&==gqDvA@8fqH$!;$$lUP0d6!LD;&WjesXEkog`V=W<{ zBwUhocyHTLK0dn%cx~J792*Y^a5WElbxLoxUZ|ovAO$K_8B*9w%UC(LC-w&yU zn|8Ed!7ds0f`wsM_dE4Hp{i0isb>3@som_xzuS_yH$N^!ci-AVj^h#CoN@LKV zZEL4k;&MNV+>tv#^eRTHN3g4vC<|hW#u;VIzn2(Ji`Vm0yKoN8YdDPIZvQqBd0-Am zazdJC!VE}KDv#ZHwOSH{)%Uy+g_!Bvv0*zWy~zA0Xx-{a?jrCglR#?aM79vV9r*sr z?;W=MY1aJ60FmWtz3YolPY*wNlA&$&6-m^WR`2_xp|ff9-6b?1PHU#C4$p@$U9(dC z5baQp*k{%2tTCAHRGfzglFfNO?dz+<9~w1|GvYS(YHA`gcf z@@Cs_fmT|SZ|8vkSbaHKlxj3kS-4H2AcV+!-M$3Ejql@4tTGW23|gE5EBl@s0&oxY z{j^ogpsno@wC!}kwyXqP3TI@Ccj_SO@m?@+HBhezg*&|PxU_;#M90i1lVoshjKjCI zk56%SfEW8kJvOMrQ2%bg``e20i!Qpo5m|i|W+1!@TVkqvFHy^N5<@x3nWYBAq%dOC3+& z0BO%;uO~Qu$ek^+FY>FSf$YB*xQiLup4^P-l~sZ;{St_g;%_!B@EYX1 zH44wf)k+TYE_akp-2$H}DCIGnn~x&Rb`(nW^Jo3lMN_>rWF6WXwJJ;aS`;YI4=Cgc zNkb`59|vL}@?n~s0G&uRMdVmneu-#(d(VznL?qB%{th>{w$d0-NF{VE>J=dph|4_; z6??{oSaXc6ftZ45FTbzBYvn-Q?)>?&d-bm|WVRP2V#ymg58aLgM+iW`@?7OXhuhM` zS7idLSOXVp_Kuh`xc_l;23l`M4L~?@c5v?_Dv2A98XtVVKuL<(50I%QP;2d`V={gb z;m|wy{UOQufg5}m0`^Xz&<<*0CaG`YEg&1$aM`aKG5RrgF{>W#f-CvPWdMj^K0>A3o z5e+Q|iFciY{nBuu5~V}&RoO?~yOHY~RJNyCO(XJ|AI$d-#=v+U1)zWb2!0T*_QfdW z*3=4baVWm>t2tiJY*5{Gh|2_h{0*xiDtF?2Ssao$!J4bdQ;l|1l)IXk7 zy)%}j{>$w^`L?(R4;Wi+@#(p6&DZWG){>k_Ob>CfMuNdWaiP$bA*!QbP2+`a7$+?{ z$8eBrt=&8iJ*n0CFHkDNEm*NWA%irYM7m~uh}uOoIckP0O;s=xONBbEoxk+iAufAA zH5dQ)z2%)h7&Sc}Grnf0b1rJ+Kh>kRU+H#-qJhs3`I~_6=sBM!N2x(NNSMN!E*IMY z;YJs{2?D%h(LL7G4*sdb)lrt&AkH9UDUH826GAo}%*&7@{L4y9L%P@dGS{+9g67LhJhRER2zVH`j9 z%&KY+OI8MqblgY$-EhCgbmmrjcFB&4##8$>a$fZd&@P2JJQK_~30|&+De?!uy_FKt z^4?#etVoRnGlwZ5J2TE{@qlR94BOOnqWjR*oENWX9na+2mkZ&1#)q`(;B`5_VKoe) z9@Ays|9{i|j2}N~e^w3-*8g2t7=h)i0gce7b;ifnQ$8!h@PLMG#}0PFPKTX^-|Y?j^!@PB(8GeI*0zWrHV1Kt-7 zw-J0Su`Tzv9k3D;^YlOZ`o0_^5&J$r9srk!2Y2@XT{cposXa9D`Y>I9VHLE8E2hx!d$^gB-Zz~JW`S#JJx${|B1*&Lq zH<1J4Zrr!!5(&HSWclf_;{Q%#WC0D@L!(0Fs=h=jw*Oi<9kL|xq_v*~7H&0CJin&L z98Gkor`G3n!{?9clc>cNaHA1V!BbOE?4~gxyb{5Xf4Ijxhk0ap>(t5Fl+i7A!AryM ziC1ioajgb%{T$7yl2Lh0_l)3_gw>UM!Z0_)vWf=sZ^8aQefZ63u{E+Pt>uF z{aH8;kR=t&5E<6(HikK&;s8!k@w2`hjy|EJ)j=r#%c|*Dj($s3;A&zRnxu?)le7+H%TtIdJ%)N&2J!e!6 z8k-KSv%V9RW^bBYsVz;Loef!%{x-BK~zMLy;d$>hCLk?CaBy;FyD zA;JJ8cF*JpGcgUWqWOoYwK{#E*0m&T;ir0emn{2~?9spFU&-U9%@MOs6sg&!_zu*G z=9Zg)3-Wm;W;+10`38qvxe+6;mh6iDU`RE6TE8)=-n*QhbMcTT-^4u%ePSmwD~`)C zsdW4Z{;{p^oCYYOl;QHM%JR&+TTNFv7lnQ?W{8(fW;fZ4(ZmUtR~%nD^cEQkL(hzv zJZ>4+J6<^9Jf2@IWZ|WLffKh0uIagvLIrJ&{a!ky5vtYvZZR*=?A%EUB+cutV&f+jQ7DQRX`3z2JtCne9P0BR<>8V9&oz@?4U{fGdugzK_Od8k%TC3`z zNzU^afjQ0tP5cYdzhP$_dhPaPJ>u=nB##uO@l^o{jD4wp6yN*RAqLmy0h4n8e3u7D zeU)b$!yd z$^fYlX2F`MvjBQT+YPY(5xiM5&}P2`JIGbb2~xXhHF99UBcQ627zrdl6CwNp8#xhY(-NUv;-zD zB~79yAQ9H(cCP||A{f2d|iWpOe;Sh;)8wl~m{y8MDt6RVij^g0rC) zBOH36o=82uKBs~DvdWFR36d90SAT1cXXyaJUL=S5=y!I$5@vj2TF*14t z{s&y}5Fw*FR4jhh!YP}P78;#j=*~B<-3b#kYr|c3Yn4O^<+DW+pVI z*+pA5J`^Wy=imZi;!W)}uF)w-K~1gtKJeYsvRz*aiG zJp}zY0H*@dsr|=?u^%5s9lgtxuy;@}lIS$Yc+`W zzeD?BYi^Q?-has}_moH%y;D`&c7Kt)eu;GA1xPlh@)gI@`ad8c1Q zl5LKkdB9nqchJ=lG-jWgjhbic<95la(%?wvMx%c!h$8$Q2Q3W&<@$JUFH`T$)XP+r zAML`&T$Rt}hO;=8`KQF7pgP~hBqJ7C61aYo?pa)ffgclIYjf|r z^#n{?014EvYrsu1M!l7M57w)+o6fDlrQ>2tPe6*yXj16nT52XB=^=(N9>8JcFq0r(53=}Nt-l`7&DlSXam%%#7pIp=uol&Sx(1rhU z=_WdKtXpF;T&h=GaK#WBV}dlJLdSF441_&z4N~de+dIaf#{8Ab0qLD7lUsRdok!Bs7EBq)wryxL@n;S$Ca?Y+lU@WswY(FA3%G;{7PQ9c+wxQ6>EC!h z+#uQY5LQgITwq|>?wK$fbca@>7_fk&&&+^hr#)kq4{$Drra2dq12ta@m%HTf+CaBx zb5W@9W|>Z6cGiuw4oGf!{)vM->jt)Q>5Fazxtxq>q<28_<9*7{S-ow#&Vy`G4GbUd zP5_wNBNa^`d9SX@QgIo=^a1V#etc!HUXoX_+8X)lRocPn_21)a)jH!0z3UhB;)8zW z$CC;y;sg-GF0M00S`#Y^1no-$T6-;rxtfjm%7vBzeJ=6wr;V#$TnsQ4Z{qn}5XB&* z4aP}u7Czv{K(-tN5u0OtQyFzj*T3 zw`u_n?P{0KU9|LYru|gI3|KrVDX^;!Q(&vA1jwKG%^Es&yw>jIzYdq39R~?$5{Gwk z4f0bFP)+~tdFzX|j4zTE_o-Kdwo@7Ms#hxD%74;6mmAda2j9h?Vj|qCjn<0Q2B2yN zZ6Gm8U+&2E7JlYv&{tzQdaq4z$ncUiWB`-MQ0~h@jE2z!8X%fS8-Y**wPv5_k%dr= zn+lJX@hkvgVPXE?z1mXt7xcZ**2lsRrfK+qo1uO2O}Gy$kCTye(<|my&J0en>D3`g zR|h?UI;2VuSt31vm~4*!ky$F;JiV`q4#IhJlrJ@QUQGUn{T$fG95lT=_D8k~*_A!~ zcU6AdI(SS$S9{KKdSqsz>vDStQH{jBmV$zofWwLxIo^;O;6$YUy?W(0Y&No+R^EY{ zB+R@AwEoN@(%qGdh(|0W<>80+OBFN!f?Z8D-@y|24a!0{!5n2h84!S?AF4N)^)<{L z^K;jZY^rhGe}Or_a^+!Xbkp5p5wrL}@c1#J_x}kv0m7&1l6Aoi1#7{sq z@NCiB?>f+P8OgdOZ}lI&&WZzfo3dK*WB3PmRh?^T?F1{{We+;WIj9A0ax|c*CE&w5 z_MXJkY$1lmfC2V6A1stWv3(6kSEvDDYuTmY&qz3cya$gCA(qP?!i|my1Nz7<2rse5 z?Uw{JU*6O3Tq$QRUaTQlmKTJhPpDbn>foi6_}$WQFbihA#48_fVo z)yCF->6P*Cn0!%;b4r?Bz3&T;9&xyQOYM9GVISCYR)-0--447<>skf+J@w`cl8HNc za;vJ$y!~K~5#oH>msFwf4@($L{QeaK)PCdL-<{60PEmROx#c4KEbG%<9dC@z6Z<}R z?Y?^Hy!=lhvWRhpD(D_=}JN%RR70pvr4*?GcYxPiS_@Ra@LB+YeV+mHej9s-Zlk%6Z7xWk0(>8UqiKS6MT(lC2V9w)Cr?Q@@Gn_2|}{#Pf_AQ zWt9{fE&9Z82ERJ|-0=Ybv(y<#M%(n?g16yPbE9ot?5JCTTSH|e8V4o4;Jy@oGY!g^ z^i<=B6~S>e(vRiuj2tYqBQy9ue5OJXU+X6w`MM%ZRR-H6KtHA25=< zBIAt&(i(ts?W+B`z!3=SkJI-|Y-oCj0onD1M1?3@JICy6WO z$PU2yFLQ$%c!Z`62%*$sb}A!exp*O^OKJ|&>ZEg}QM*JF4KFZX##LbO6a2tw69=Uc zCXxYSlGJV%7O`v)M=~E1MQeT6u!IgtI>?fGA^(dnIGSPzJ7iT-aoag+&NaehQ&_8( ze3g8b2K}2!icqEDpq?9pZ>}aD4IhXDAwPig^&{jgX}#HsZ9*MuihwcWU+!XpylYei zMr``?p1|pT|3;x+0YreV$#cz0@o7+P&+yfKgvbs)vsAFYL~T0C`VGU#Yk(Am!0n!I z2Af%YAaqHaV_10>V22BWDIgNii%({`Kw2I%DA$UYf`0gy97Ub-}Zk zpa9=;-5)Q_Zt%qa-4nSVC8NzcE6$J#@+JOxPIQ+iOUgHFi*X91rptoHL<^{Y%9(ca zGRc_=jo?I=l4f&f!2)05%0|p*wgA3mDoNDS-B=WbeX~ zohC)4je)icwAq_I&J3lu#F>&Y6jj`2-zHU!$@#h_B{-~5vql6Eaj<3&E&u?f3|H&%`H1)pdE_1=qQ`5BneGEX%jI^z2N`%)um`RnXK`Z)Y*Y zoP+LTA#&Oy+Qn)aO)8@nrl51kRgw{Q>m(rs_|bn$BFQntf)9|+M*!)iQUfUboVf*~H6XZM0l3 zQ{Z_!*(r8H3mJs)jm{J)XmWK&zC3sz?C00BHMta6jKUBJG20mvv5~=-;)}D7)~u>_ zu}-}-sLvA7t$jTL0f2Hfbf&vQJj9V@|AV5)R$)^7Cd;6o+L{I8NR<25;tY5UJ373I zBYJjv?$E0ToZKy-LhI;AY6M4&GRm2#jJ~cqw|2udGr>XXEC*e>8P@Ia{I4+tt`+7jCW`;mIq<$l_n4p5gJ97RG-)-Q4=9A z>Gg=4M^D*}uzU@k<2un3pXgP^&+wF6@CC?I4#=2SY44MJcn*GF2M^#AuC-^PA6h9^nRC zEqih0Dom7?+~v0t8b)$}=;+S~H++y?Z=RScWCPJozE9q^kp`^(pHCi6+eShmpy7=k ztA4b1*S(ATjH0XL{#+(OR{VnV`o?u39NAecWs=gyw{7_ky zaq`R|jchBX<&v}*t&EaAFmca2aR&_KRCF(F2x0O@R2f(&SxCpI3y*m4s=+y71{=8Jz&If@5V&}3P>#1u6~I8SPcf;5=a~xtTkxUxtv%{hAC?!E$~Y5C+5#t3ZM+8O*mlM2eg3s!kVH-oh+ECT@) z+K{IyD0(q;38}q{tLnDIPT2(B1FzQDgR%=?0=5S2p~o(Z#Ho$T(s^!0|0YS$uqSx$ zsmU@=|I@#VOugk@Jy81 zzBFhB*B&-47MY;L?U$6QdCDS+e85T~ELh{mCRKwI180vujPH-31&8Xs+-U<{E>cnQ z7pstKP$t@_#MAC`gGz(MFmZ5od`r42#gX0L^ipk&U zuj6BhnM=$Iu8Fe$gs)WWd)q=MXUBb{lq-ppNA=}G!^{o3{#vx4M?M2*VD&0j5yW>3 zL~A_n$Ft~uh95J*I;n(8Rod%v_W^+Sv`i9R#KvQecECTjncJjDh(wkBUIOXM9n3O| zq=N=A1GmZ2#)f%KW00`!gN5&el%6vRkAsi`0=Z2oTd3WCeV3=l8;L}<{Zj;5CqoWo z5?P1a5zhk9k6B}LaqQx0vZlK>MR{K>@PUAxd5Jh$>+sF<^yX+0UKD3brv0v2B+N|J zdic`bByW5OP9Vk(PcSL5Lm`OC;5={xTJeanS2Oe&^%~)sM_(A7CJssHldKy%!jZrE zJqbLB11aSrea}qB|ISRCYIs-fB@VhRg__<+naE3r`VRX6gwd^7_s7if?6f>gG5t+@yNF|ev2#w9;Y4!!2$58Mq)sKTbMw^Zwsd|KjPO-wT0+hcx31KP z${UOVIBn7BnArqUd=F^A`pMyt+zfD+)=oQ^O>7qTqzVHew_}oGS+P$OgQ)A;j{R=8 zPL*dajhTnAdoQ*CyyqT(XvuB`O%1EkR6F)6)TTCy#&3|J495aMD$7yPnr3>8%}1l*YqA+JB!A#{*6$_s2o$U<*A=!~4_Kv!i7y+{=PgA>;?=!~Tcg4Pd&PS{ zxz86y>iM07&`xd{fuT{xd{qVSX-p-K^5T`^cCMh+mpUmQ3tWi`Q9ig#_t4z9Xkm>edU||3kI-l$PUJdQM+g=? zBu9Qp;xhLA{RreNdZFeng~HE-*Lsnj;h*)YA`O{gyMqXmup@{~e|@9Idd8x8ca`*F zS4DbZU=%3;!<{Ev42*wo!iZyL6aB17i868^wL;M~pgNp(HGT7tA4cF9%r^Hzmk7?@ zwkBV@;pTW7Y>O6RU#lIylY6D@$sUX!Iq2hM%*#Xafo%T9j3|wSxr1$z*3z^gFw?P< z^-m0&o{I6I61%Qo(`G0Z- zYq9&yNPb&2$45Zwo+V&lz~<&2?^%WczJm1dft)|Hzkc+|BU7u|Ud>nYBesP|dyOrX6eG-DT3@sgD zd|l-N0G$It27uT5H-eRelCSppaFNW9dKZ@+SsXw$AWs>cG}5WgpoS9OL^U2iG`lKY zg9x7!ZQov3tfL_+Y1QVSLTqO$R{z-MHY)f|tCu_7(NJ_HVNE<;z=)<|E%tR=ojl#J z%n9`s#a&o7Q^oza{CQ3W{^+)NaQR$$2B1 zqjFa2Op(~{P2J`&hICQXJ}Z!w>gp|c4@gb$^+f7bh~N1UGf@zhY{aU`>ShutB9-2N z{E8J|%~3%!3Y>t2(ema(enA@s9ODHjBs*=OY|EeOG<~Y0^#W}Gz{|kkj$RJh=a&E= z60rC61y>|8gsf^8S#~Ml;H7+>Ic*^D@wtGqd{8lec0VoOrKi`;9XFmtj z39o$F=jmn0qEF@T@bWY!%n;lc>gPM40iFsK+P6Y@+|vfQ9r+Jlx3hftq8l@Dexm2b zMcDpzpHrqJRo~Th0Ec4}D}8-ttJAF}FLIT}rUC}}BRpHFDM|jOeQ@KvCL{g|YeGCN zRMHsDEHD+g-e&;p28)G~{{k>icMUn40LvpKSJvs3!HQIDpsxxoE-2DqToZ-F{8KQe z%5_R5mS6KXM%}1%yB16tMDb@eP?DxJ=ZVcj102jkTveuCz(|{4X0b)E7eM?K{lZqn!Gss2dE&wkfr4; zn+l|pY2sLCNkqkT3jrvFdx02_@)QwihgX~>98o&ZQ{30kW=Cb~F&dGTBAUkbnlQV# zG6gwU*&{4TPnTivp&)~~k7kWYrC)0;o|P031VQpK9^6T!Wri`8^_(;)Vv=6)D9wjf zw36pe#>!szTDd!TPLU9i**U@1^&LzSynAS)P3rX{_Vk;Q<*RtAR_nlfA3hTA616fb9Jm)(qbSG7m)n2u>f1y;UZJ^Coaij7px%{MC;b z>IlDZ>jhZSPMb{Y&Ue9e6G@;H=YnR9Zo!za+F|AY-9cqlI%h!~)*6#xDfpMl@L-mR z+l8L7X-U&JLhjuBBHxRL{K1`b+UlL--aa!;#PGrVSeA6F$lbQ)i1{h@87(#%uK=bi*jW)cABejMO=aYs2s8g7d zjz3j`*(E6rq0__6rFhR}Id#{DpUz3}dC~BSwKJX|2wjr&d61N2b&7W^yQY6ph#9gQ zRYkHS;ep`%XpMVW=78<7oyi-ItS6|+L-kY*eTfFD;sz9t-KvLd%8=$*@UaccjraOu z53&GA#EY-(MnX`ZpanEz@|KFcIFG!jC545_#-Q%`7@-@>vJ!jBV}1lilp9Q^NNY2h zSbv*W)+lu~BC?=xjF;WSXT^I3bqw{U^}}>L$XS>YxO7RQcta?%L>mK=e|pwT18o~2 zWca7SGfHYCq?D$|4&I}fbK%G2vxbnToHqirF`-Ou@N+maCn0*fOlwfe&+$g-U9pvs zX%{SM+Vk2VSQ!Ebj5Xn-yO2Q&=Gc+!FxR{CE@OV%Jb+?zD)(_Hmq#(@Y!c5m#XCy1 zsId7SKci?yN%h2r1U`djz~L6(4Kj=bYaSpi6+snom83M!ZQ{!wZ$PnM&Yp$JiD3f} zBtzC4P>N^n|CWchw|IQPQj$>!#^*lb2ETcO` zs6&Mu%C%g7@IT3Z6*|%9pCW(3QZ5D5(F!8gB<8?27_GSU&dDvIAWU*kood&Iv6&R6 zBRv&*lhtr#Li7%iVPnXhy#~iFy?~9{o<=93)0zZ(uz@bPYuU>EB zD5CphXDeMvJIpIU9J(x6TAx9^1^hyP{UkiQATZ^-A1Mli>iXN@U)C;Hz*PzP<7mo> zvDv22B!dIceygeeRJR6WOSf;j|8tsaY%DPhxu9V?KSAKT+SHQ~sFk~P;U0`Z#Z%QK zy~Qrg_{7j~4I1K9T?-R-PF5N~zFRfU--@c{MR)8Sl!KKZ#F`E7nof3RGA#d2Qw{V} zPes!bH&RjaVw3h3w4F2xRUrwEk;|J{np0>j*r-4Kupo-Q+}D4F4T8o@2#2gvpn<<-MH^OXQlp4q{?!i{%1 zNx!EP$_^Wy4m5s#zDYRwoxTAxSFG`x7m<8orm9&f2pzlSmds97pALxi8rHG)EOzA9 z;^->Bh;=jjt+6xnuK$3(c^>HKY6pi+NvCbiil;Fee3lFK5E`Z!XyA7U1dkRy1i8g`~QSuALHe8`UokE(}Tf=p|YdLC!Ct0yLs5c90s zrSY%n)R)4uy_=r^2ks9EZS&$~&N9U}qtz1n+85E6P!Q||qbr_C{!qfM?I4ErUr9XO zCkFx`g;eLVBhbCcG#e#V{h^%ZxEZ)Y;+%)qi)N*ZT{Hq8Sk$@{=T`J&j-+CuaemA& zTBP(@4LCKJgjh@+;tu@V-tRVgD>!E#j%wBPTj;)t^$q}l>n3l{nS*Q>F|VIcq(cYG zzT(D=Qf6|;uR#pwo5bFvbZ)Fw0bSa!d}_O-^Pa>74kQN2#QWJQA%-83u&Z#esvS<` zN#||Wr=};M#?~nECnB!1f^k^(lW5ri+L|V$NImru(38c2C8Fpzw~U# zF5g1aTyul~zF*hJVKEDU`I=32dcy^rRS#3>+2L{oG3=xtEq4_wQc7P_&m@;V3r7g% zOJkEI)z3#(#478yVfYRwqMQ-dE7!IcY$>u*E=c0VlL$h`x}prOY%gMEEv{ju-?^_SF{3UtX9ba&gdKI|M>P+*KEOm zKz{f}`r1{93nii7NZ<26q|cVtAfoFx3Ew9TL0!?Cg}1By?Fr)jj|td~Je?OTZP(%v zL{lqL;yTCT5w1Xa&3G?(LhjQ>SNpfMT6?}zvQs=$kw$Hza)lId$4<+i8YIGMR%$8U z(drDaJg^*y>dcB-)?ojm%kzTAqW|@{f*Hp%mZ^He6{RgDV9a)#Yp7MdN}}s0VDn$w z`1LQ!%6EU8h-H(-&Fp{Vn1ol&HN< zeJ_mQc!v=+3>tzIAMhDRLM`2d7dl$BA-pRBjxhf_GVU#=?;|4{H@u@9{dnZ~zWVMc zDT^lyli00biZnX_bS0;8_6d8gtZ%D+XHzQ3k5wv_wVMuvWb$jmL|8f2%?A&H=Yx7j zb5(sV7~eFg&!QAr3kZ7tv-&dhAQ-r+edKsRLV+%DUwDUj_GI>4i$}~DxlB=cK+f3c zKbVk~LlY|~HaM=qjPnH~Z6lve+AiyDm8`yQ@N>H^DFQHhsWU1fhjdEc3Kpg}CG9B9 zO#=*{5O$uz1r;s7kg@9wD=jQ7GG*ZH@C5vYhLap3*ZY3$$#+z?#VFgEW!LYOGny75 zvbBuNol zj5V#`gbT~Cdx878JpRu8Oz-eMf6}tQaB(;a1a;IqTm!4x`0J09tTQQ?FB2#-4aeZa zb<%o4l-FR?B(8(q^*9mgF~=(&FUFvnl0CgH0x5vx4ahe=JvKPLyf~%idmRy^@e7T; zdCord`MF$bi~zzF)^AA$6~3uWg2yeW$k58 z)=e0dR|8GB3Vhq9%ROlOE~$kBQoeC8V52~3hjKZCS~X-aR0WeRCemDH+n>XVnX^xC zYYlLYo*<<=q@WM;T|ns8la5{Hc!FQjLJ18!Tdb4W<0fz!eD>)p01U) z$6dG$`cRQFSI^2e7Csl1x2!MLwPtOZq34;9CAQUZ>kaz?1|ZP!`pMQGtk4$35_Z?v z+)pXr!B=voxS4q7ick~bOCZPkruWPVZ4I~~dggSfcy`vmG90#fXE=bmrJuLT`kCG0 z5jR@MXN2Ud#Y~6#Yop9u zM?X#^ofHUSQQ;_Sd=$t%mJOPv|0JYO0>ZNh41%-9ln50CNU@EIKCH0)t7oTkNFH$Z zn~a|1!EqT?f4QN{*c39kG1F|1j3>lJhB1e}Y7B6ymrFI>UW+^Mt73nlP0jJf|2DCt zHlM-T>tbxuy&bVE_pe4QXGRncQ*lg3TU%3s>r87;oY6FkOZBw?k0JGm-Cqk#U#>DV zmtHFR5vTC{7vJc9BygC4mdzAuBwN5I9q<2?Vw{GB-`m~tuwX6R8`I_?W zK^dkAB8eZ2093Jdv%{igVD7qHf=FD^J{g=$+rDBGRdG8^u~W20O1mT{*@_qlY%f)y z(I@8$?DvJ^4LSBEa9c^zPm~02)t$+YJOh*qsXnCqt*BZlGk)`|c!^|>YYDhSLY&x~ zNuqiR&iLjA7=~+%znFkAhf&4caU#<}M5nHYR_(ad4DxPg1-1Z5;M+;6=p&i~Wj(p0 z7q%YdD=ABRiV$O_7Scnal+waHpuY}3^~oDqApbqd`yzEhsu4pFSVO#DPt}~c1u7q^@Di~b$oCPc8LY@t>YhC{d2T z#4dUA)~7Xx|DU<8RhwLeUq~{Mq-vez$aJ*g_9xvqnzt2}9H+U3IYxFB9x1a9_jSu&f_a$0ylPTknN?aeiYTb%4q68wI&v9`|GTk}ORdA9kik z{A*pOYz23CQ$Ie8yd`Q*?{pCC1R`BnE*czJ$E9@el7iqH9A06(7oG;oAqehX<@}N2 zP*oJWZ`nTd6r*jawtPil3+-B@pjjNJ<%p-lx}Tp%j;=S4ee9FyRF~|$UvOT#cP7Gi z{%~2E*Wl1^zY?IBKac-kM5@ELnkzd~>b5>GU#j5%1VZX1ET}X*8wV#nGaDfb6DJ`X z7h~$q0EBXC4g&~gY7HDHI~*J9f8VmR5VEl+&LESgUe!aurpgwBQ~!U$wh+FBObHnY zl?fTdzsp!MvM1i~ait=(10#a4Gp7=@0~7u8p1lIh6vl}F`uzfH;Y0vu@koU%0jEl( z>IOjqTz{Osp)tQKVJLVUX7IsGi5>v(^-n`cnKFQA0^Y4G)Vf3&6dd5{;Cl5hY19?Mh_ zU8BJ8xs~hRI>6BLd4K=$o%S>j(B;UYB&QDreCItWzjXTtDk*lD}psgdN z(dr51*rqvDitO%3Xy$2%UYLBSZja#VnTH|t8)s`VnH4ES6BZ?9yo!NnJCWmOj^ob| zz_6222cwkc?0ot%lLp~U-C)U6euPmZZJOBk$rpT672>*8~>R1 zov58GDvrKnxM?dmMJcLT^Xc=)fZy9f*ae#5#p*I$P1~gvsRPziux2qK zW+^)UD7vY#OL`l21~eLir>K+_0c4NAWo&cW0=Wr_mo$Ft}-1PNJzVTCX(SYAgu ze|m`o%Cm@~ZqvZ+sci)yis3G9@=_H~YG+JW6ox41dI`T3@}f?nMk%F$$FEKGS6F6T z9;Gz5l}i@o1udtU6jv1r&S-W(n{J~lMhFEW>ARP_SFb`qw2VDDa-Kyd0sN@sj&w?x z6oV@cf;!JIT!7Qa%TezTt_UHB1CdP(piZSMj0*;yITKsGAep0^AqXXh+~H(NW^-r~ z-_H{UcJa9eHl;U3Grmki(1ZX;v%@iWUynrhHW&boW!=Qy`8lpn5#5{W2A znvCi4E7d5Om(utxP;ycC3}D?BNks`hUuZ%YW?he^vQVv4G&hpQ|9jND64zQ+2-L8{ zNLJMgT1j0#x?ucgsv8(DkWZI%gi|gE_1?Ah21y6*PIW?C#?~y<)J2v84$7iPN>R8N zb-KSDE3mv6sri7d8|#p^sMXHbO9Yk>9yW*iXrNTXHv~;4dBQh7~BP%&5=i9 zvq_|K%WDHf-j8hiAg)a5t8Eh}TWsiyq@6O=w>rxHqr1Hw^Qg8XLw@2o8x&mPdJZbF z!MyEacAxQ~)Wpxmw{uYEE{4i-V=Yh1YMNxQ$ zFN*$3Z4SztTQT^f1;}k}G*97&T8W88KvbVaE=%w*F+j zJ?H0tM7wdvb7v?~nNqBq@CI2YoDR3bjL8S3A<;Swiv{HVxpR3=g39GUo*Pb&#vjL4 zp0ic;)6t;Ld(FbX5ba}kiLu^2Oqmz)2~Jv9SY|#IK5fpoKcqeIJT}hCX)36*%ch7Z z`Q%Sk4aC@yXh)|&Kg`io2cxB8Oo)nt6>ZA=F6{F=Y(rZ^8gapTcXQ_WJ}+}Vg+pr? zQ!AKx7#^VAZdUmEo(p9^8;Q>guVgNXa>tV}cwaW@^=127NhW*0`?t4IBCHMpZv?Z@ z_Y?8Lw;58b_4*jvd0_kS^4#nGq)RX9Jd@v#rQVAdU<5RTN;w>`uH$I1osTzv@_j#I zg3KM{^*XfJzuiw`cwewLoY)G&;rgY-WO6IK5dqN3IcXSYWEDO4msH{VC6O`RKY7Pi zmV@;r!qlbcbUjc(k@-nnL<0`6m>7 zv0QN$0gU&WCXJsOS~qF<=PU#&PdhFvoTgrq$!&J=m{qYZV5_vD@bJ1F9rD zs|Ijcp@#BHyN-D>ZmXd9uc6n@YCHCN{?1gJv_vtn zBJu`^pB%tEN-Pf$qy=i~TSaAQj~~!I4FPDi*%aG{$n8LFbNe}nZ-a@i5EKH6twZ<} zR?by+Tx|#iCxOcTr`!!ehBOouq_X@jDovXaB;;lF`mxL=Ai9}Uqc(W3zx^-Uf1Mz6T_$os5D8kz z&r5kI``>;;eVJgR#~`Qlu_m|^viSXtM}SB9-GcfvD@u6SxVnqs==7`g37|Z44?SaR zs%4^!1y|$!Ta9_@&1Vzvgdg>UXsp#)B!FUcZuT$%!xO7SiO+jgje(fnA6=Rz0=Hrb z7cvp9>tev4%_N(ovzAWPFUn$tQS_D|{96mU9%({WNQBZ9M5L+Qk-KdD_=HXHc?dlp z<(;cFDIGUiS%RAu zHTJmcqvS-TUzY~u0EZD$@Qo_4OHrFZDHP7WeOtlhq29Ya1fglob``R8k()L)Gz*=3}yJE(sS18vgO^MX+htNm&12}UdmXIiB|p)O#W%2hFaHZ z4J~8Bw6vM(@_=%v0!Zv1Bfh&J>s9_p_F#!5f$uL{|AzMF%jvFn`TT-M>xLtR2%jVz@wb>7!0K=S5usXfB1WTZBrqyf6Y7*mAq; zoh`9Sk@EqjZkhiya-tsMY5B`MRbvO34I-uO^oZdXL96YUhN?LUlAP}il;?XADq@3Y zk|D(nyp*i9BwAIHzD=1Xk`k>2Q=HU^;jmEhA$8UIPH1_+QU)EV>VD@XQfu0eeX}vX zdlTm&RFDY(3`~Oak$b(89#T{Ov{48Pw07Wt(c?<3b>wyei5g$&U-g5tGz!j>elM>0 zcrk@8cln&&WSmeF=n^$xq1I|UuF5h@)Tu%7RYDW~!9X%(yl3>OlbTiC4m&bGy6CKX z#7gB@#cmy#tFPZP9FOVP0gh$VRjHegswA_z=sO+&+NxVxH7tj#sIp6_28stdqsNsf zMw$qmFs{TIP57sL8zTA22xFQhMV>n%jWx7s^KqjWxyj*uj#+Fn_39lba{9kiJ-KoR zNVCZuAvcqewx$7d@&v0o`6JZf?XV##PRZJK1DeN>UQU61t?%1!SmCymeN zKxJDPn~J^{+e%)ej#2aLpHaa^u>=hhHB2Vvc$#7NY=c#1(Ca1UveJMvIz0TGu7STE z&pEkzdv{sZ2u8X&=vw1|>!BZWhY`MJC&HJ2tR+hvo>iPpK8kMCo2C)pR&tCZGo4?B z@7IlCRlx&^oo3rF1Jx(fwy*IgF$%ZZcg1+~jAa=!Vq0D$RwYbm87j1+}yFnk|F6!B^?I97nc* zw264{9CWtX^X2R|UVMFG2B%?$a8@~!`N39KWjJt{r5l9u@&S+o+;RV(PK9N*N$*;b zo@$+9eGRUk^#PEKBGdt$MSqqCOw$?Ja8g&SqeDkEIOga$usweLv6|+HjuKsM5H$TV za!a|JII`f_-F%B|M-**`Dwchp78g4NnAVkPyhc*Iu?>zP4DlTZ%?nK z2rb{8q!1UPK-8X1m}Yp)=}u`J8q9!kzC3;Sn z?u~12p}#P`%u4R`UmnHuv%*Q8t{?p8TbdMnq;?_%M#8F(5-9Dy{f9wiw!l_OSEL6M&Vus0CIivu`w+mB6H zuC~5HboIaRuD>w+MRZ?Mx0}KLf9i>R2SfRQv9htVq^>FeV*^sW{*8DV`d&-dewPi2 zzysU-w`_<5Spup8$I9eNHs(!VhjBz|xyWfPWx~RH-+Jy<>)W{f?rjT$LJz-J#11i} z|J(4q!I$GpOCr5`Sm({wRd8eI%lrH8*ZaY+Oy~2(QOOm+G&T2YuRLMB^1R;ppLi#O zB?U!nGQfAdlm0YiTNAk?N68=k3@^0Z5S5*SyYJ=nIq@^`!NHw^!aJkNty=B)5raae zQ`t12=RKiq^~?3;y@p~6-2|0I_{!ri_SLl++q$hZzL{-nVXB;E;ePX0ybf&v`p%_o zAHIicXCcO5@alw8I^%JyvLZ10)$$;BRSSJ~AppdEry7mQTRQ};h#gRGL<;Lr#XBHN)rz2z?q^9@9M=3(^(ex zgOfxt6t&7jKJ5rpyG^Ns^F(7mjX;mFP+)Y{8KN+~;a*+xh;Eo2JaRP1Lm$GZNc7z^ z%GEj%N*pGrvZ8r4$|kQSabTPTgi}~x=_IARn>rbg>0H2X-ax~7!x21etl~`_IN~_E zf3O~38<)m&L{0|Dmxy!t3)%p&9*C4+Pne#=jYw<_^imCS+Rpl6#w>xct7?CK=?r{bwm`OahQufUd{$-}RF6rL zXP>%e(jlCW?}Wba>07yK<@n;-^({l7Bo0|Du@gS|Y!+rYQu<*)9ziC~yc}j42nV0t z;KqmBEnA@=pRb)QG%40g_(q)R?6H|X?F~Jf!pQ-qAlTJ4e^@{JuSLr_nk-!|-@Ccx zaX@3|q+4e zLQ~||+>naCo-_XtL)DTID;!bNh>E9f8q;l=<%ZFdzZ?J$4xueOHB-6xH%8e31Uom@)|*svx$#{1rpnrN}) zCu2CaXEJf6bX7gSK!cpF$P~&y?N&}t+oCL$|J&}r+w1tzg4_MAaY~KV+*fipat*R= z8uW0HXkTv!dv`s+hyF4oA?rwn_`bM}JxuH1z|6A?@7g&X+LW~I+30gteI69%8g${L z&#f!i1Kvba1Ue$*6l#Ha3ID0INawdtB-l#(dL0+Wmo(=Zu} zUtP4j2TZpoKULV~0&S-(=jUisYS0Bj0~ASJx=(tAncC*#51Fv)(V@nk8BM3CS<)jO zsXNlc6$vki&M4)IRX(}-2x4qplki#NWHA+aiHbshz_3x=H;>SWkj29WB(;Xy%1Z^3 z0!-QRIweMM&!GaO;kqXt|N2?|PINECT&4u)jU#GJ)7>_a+Sk~=md z#@g&6(qbzd0U-Ly3P&ZXW*h?G4Ia$MSS;W!R5}T1w*K;xkC?=84{#DTUBLM+61|i81g#}FbeB&r0f=)$Cc{mEMA-uW4|npa^(h1N3=;P z_rPRhGUP?e#_WlSQQ==#z^%|%y=68P;dKplYN`DS2z@JbUYEpHeHp6z@ylwr{W!JEdUUT^)J)G+84}xF za@pz0saVL0W9Nt@M5+0cOf%Hnj=@8~NB8b@`baYy`vZ{p072+E7l0r3+E2I2Q!*Qy zaudY1*Adr!Qk}lz!nT*02B`JJnS(YCe^hd}GoxJ%wb1dFM@{yz7HREPz(PX?=DTc z+#iRT78;~Z_twb%zkw|r$EkPBS>_UaXvegIJtn>;ERQ_i&2;YEeDjD{0&md@K~J8T zev&cvV^=O9Jnm|7?MPz%dL>%sNI2{H-25@JJiuJuc{j0oYqfUvt9CPQ=>b7=JwFU~ zGbb56a2fIWPh)V?ZvYJl9-J9hj<^?04i5KJatsh$2JcU=Y8FoN>cJ?yjvFnp*!no@wrEM*uXDg5Ll$N;o$z zl|Hh|i<{CjN`MG{KXhDo&Cq^#K?QSO;VnD|r%;R6U9ZUqxb7C8;{ZDTF#g*==I+V6^s}jtx_$fU*B`#e$7`{7U&CSy}D7 zE{KEwN(|t`7xrOoKYoUJo`n=FM4}F3!~QODu~n4k;O+4)3=BUS=Ns+NvSPwo|MvX+ zxowiC8AqT7mExfMQ>Ro>HTxV!MQh$sVGkrISMU2_H`Lk9elzC9Lnq5vZv5;1o3HTQ z#&tC`Z+=ezJ9N8`t;`R7OJMu7fs0XU!!sDow1CcT;V z>UAZ3xHI1AQHWqKjHBAOlMeX2n@%wgfI7!C$?tHyi=s)m5E#lNz85 z!XJPF;a|kM!HlFH>Gcc6rc6X!9$fdQB){wUtaTB&8MbNfxi)&35iB*w)*I!S)5T&` z%7zkaX}?he#3l?g`M9NT{*X50!-^TveGZ1&?6a?1GGw`O1#JtvwnhH9R@efqnUooW zO@SLSdXY{QX;)We#G+LAJypN8w-RWLb}&G-OwGJGW>IV8+zS=G{&)Sqz~vw0^J`Oo zQS|H^^{5ucXZOW7D~gq?Qq#Y%-+f2gvvYPz>+};~L#5NM5{;Jx1TdPByFg-DNWQ7AAGbkxBAzt+DL9-d! zTm6Oy5`@<0 zI*%pV&9KHhTzQ5*(t$*F;czV0QO*lD%L3poihb`^-2Al6=gP38bKvIgk#FV>y!FVU z&03x(RtT-F>oycD7RW4rEJjy6Z(LrVi4GMK1Ry#OK%&1QD zJAi^sTA7s89a)u(YL4)qJ3luuK_F@&b@p#bL~(poEGlG8qHl--uOlCcierxe1bFnJ z_yZYmRw`C?Ds6i!X=Bs-lSvBJa@jpzKVg|g{(wRR)0(OY|gO8sG z4h@fRYqx6fFuZVaKu)5wFHn2OVCB@(=IVxX(RFhUuazHS%TrdwJsv1A+gIuPV+jvskhlIk} zc-T<4)#n?;)mnD~U0w>bk{E4- z7}cDaLEyTT*6I#7eypA}uvIEU0^4n!kldXYh$TVl$*n{V==Kwsr)$blj8i)I7ohEo zWqdpZMxM2~quYa5!Jv$LY6N!9?zVu3Gr6An4z6A*P3oe?x0hGE0M0~ohTI1Qd1@S_ zj(A6!Pw&%EV9i;gKmrzPP@C(A7#VA&(^gr;)2s5qTRwQq05f(c=!^1h6!G6Unm>XSEoP>w;2B(Qt&!n?(_^QS3mW5dIm-_SQRIpY;ASgqbd$xrM*-9A$RS2&^_wp1`A* zx7pdZt^vRa#+crzRzv>_A*7NjHw;b%;9~h7LbG~n_N3qSWtTK2zU#|oK9M7W#W&LY zr!+h8|0vA{KUEWJVLOLL9#qm+E>s>Coz{A`kJu}p*LUPzrM>0Wz2COfAoTEhMws(L z`hN`f|Hl*Ai-&aHJbCC+qun+{eZ7n$q@eiSlOrNS2oyYt5x)OxPtydNIs4|*DoxgIQ6K8-E#%e^FUIrtzH*GP}f_KYos zVuAM0I7BfUnU45xi0`U1)&;$U zZ#xl;#?2yDXZn<9#lw_B%Z&@uA0YdX8IMdO@Zu;WlAw#>A_+G!SJkj*an`EFE1qfY z0agO!J{h>$pkS_Bh9x;S^VnjCZ|`QjIkREwt?>n3k+Et8XL*+AMq$QK$990BbBU!j z#{?vgx1rq%3+h+KffyX_;5w_N?MS;Z+)6Bb3$iRbVb%jWl3lx@=6<*zFu?409`!P% za+kW=8?C`-l2t_}Z9`PtO=LBUI4;RhjHC@3jgvFUWG%;RBB@@aaB|q;c1OeZKsF|D z(PkDr3aDVC*$_U{Y^_>G86|-2_#awU)Ch>PqZj7U&I8an0;DRk(`ck(kbiCCvPx#; zDl<9f65;z`v8kN@PEWU_>01o*`tc#9^k@96QJ4;~52r7&P*c5%Xj2S!HOJI~%qzVx z5j`Y;ayQ~*`0!TLjVQJyDZJ?}TmK{apeN?xz?oh$Q_M(gVuh?q?MV#43q7@fCb4Gb z=9xR*d|~BSkYbt#(+Rf?QqzTjqjXrowOo9l+$8ez#}b=M)G%g^r_Mjhgc+*tlL&M& zI~71#x9o5@JUmHVa0?cdpqjs9ezej?It=W6q+(R>SITrwNm)NYJfFd+3)6t`hZBJ2 z;?d5Z9$mkpWWmE~5hDjk?@->eu?y?AFG2H|rd*I?#P%tg(2+h+{lmN9v17my8|aY{ ztCgv_&j-?LSIr!lVo)IkOQxtk*3)apASPcn{ks3xjGrqRA?B3-+gpLIRQ{KmWl^F6 zjd{_V=oeXXS7nqsiRiat#y?o-+x&fB);SZw?YTfK4M>(g(0dxPMbOA?coe4nj`G&R zsL~FXdD4#X{@0W|4eFYS;`US{R!-J78?M)D)XpDY5ezr|hFE6>3y@0RIv-LF|C&_) zf|ei+x&qZ+Y8M+Gljbm+5iPj=f0-Zpf0&<*|HIZhM@ROA@4nH56Wg|Jo0Cjz+jjO$ zY-i$RVoYqC6Wg|Joy>RLbMd?9kM6EjRoz`(t5@x+XTR_BvHmCg=za=6<%l>#!n56Q zK!k;A`02#?K{C{S4~AKPA%i|X-8(-Z_m=T}mH)!`??J!<_kv)hFHNk#*P$u!$~?%e z4f)3=@bmEh- z&ZPW&pjRa;v#cCC_nhqA%P1_J%t4MLR=PfqjkB=qC9|wgEaV{I-vnJxRA=}^KHL|n zNEE!hKXWJT_`Olh?X5s~zS)=j9H*&&;amOoE}k?cGxLUKIRL^FULqoCCxrp<_%Bc| z`0K@6apM=zNFGsvD?Sbq@x=4y=Fv3cLB~gD+z*@jdkYl3Oi0hSnUkb%{vGQTH$Ow3 zQk5vUOb~WS${^kiT=;V(b#hrGh%TU$$@itsi z8>3!ynp9+Fpl0dYh{+Q@+%rf~{cR{5g?k5#(TPA$ndRHMvZtJfRQp%pb6APbus0_0 z@`^V?&o83OjJ52ml}RE^fiG z*yO(gt{J$vOIe17vD*@Y-~@<$1H~7`2C1s?`1)x2wV6OgVy>Mg1aifMD2F<1!Xm%7 zX`PchsUBq^s*2(cVrv6lPLh4C0U;2*%$L&ly_u+L$F`l$hdnk2@~c@p`)KM1Q1OF7 zp5{hJ*?7jgt9@IGeOFWH5(1CXgXcWX)r;cW>o+v(og3<}*Mml|pbKP=#|$$*wKW}MSfP-{i_yAsSyjQSkQ_fcs3wr5R2T7#4>cqhtMEe5&o_C zg>mfkZZA^CPeQ6m*`$N;uRykEz#VMjaD=;ejlcxr=JiqBHsFKcMVCY4YF4#-GGQ#6HSA-1M)9IQ z0S1O?c#DA$Gc2-0bEW>@U+3+8+`T<*!Z|6=CrfyUE-Pxpa*U&Eo2#Ax8tWkJQ0o|* zj_}9>|5pmjSpev`uh$O*W#?7bdI3GhgsxreoYDKGC!a~P-?1&y0(cXb->bC2#82K&2^d3Qupn$l$YU)>GWv)o)Tf@e; zdEfMRw5-q83zBm$`}Ce#>(v(O)sU;t&dD~gF&?cI+tHGA_8gS@tRe78QVPZ#dG$u5 zvEnAP`yy;(F$2t%CFI2B?MSZV<`JA|I%PR@`N$pJZ|jr8zn?C~h9fQgf%7{Bim1#x zmO~JALjp3YcGhdwloLAY#8(a5rni#h)e3&{?clLEldz{5l!2^fQq;$#wL5!O-JgR& zUq{s@^S!-VMC6Z)Jt-3Neo3DemtQ1oaYs?JJCpKwf+BoO(_fVG)rdB5kMy#l39R=*`RDf)p)~zP4Nc*8jnWY&$u) z9j!y~!)w`4N}2#;p3Kpp?w+t30GbSk5pAgVRES*Y0lqgFD{bq!hjvr(}P*haDVv zU{3QH^s0x|pR~DPHFfbip*>22pjs_c2*lN-ZXD?L4AZuS3#32Y%qdNAY*Vr4G5zW#|a8LC!K>8_tqi! zMV^#d2Bk_WYU*uERvvUNGB*URTPpgutvEoHo&?Pj%`KokLWS0a8}~8x^X88Ue=!a= z&5AXt<=KD599j5mRM)Cf@j#OLp6N@0?@^NnWm~;9#Wl%yze`P;EezGNAkD z&32apC`#dMurCvn-ct1!J<>Yi_0L}mpW{fY(-4a9g(T0v`*)T}aPP(3OyMqNjW zh7&lvm68o;`Bran{FT`NcXtw;B`6xkw!u%%{K!uqBqW_)_PKWF)%m6?HT&&3c_Tkr zS>`ps^UDiIQEfjls|+2dURUSJ53e?Ujl8A4g)5v?j?I2~`ra;SdJe;fg>lpyo8MeU zaVd0kMi4{@i9^_!U1m>C7}BcIwNk-bCh(&q65!iHVRu487)KdE!It}cbk25|0 zv((RSk*{=@fr-^J3{apfL-f2Q&g>!hi!$n?<2G?)!$&r@Ly;&W@RFz1;D6=PQ&g8L za2I>dOtFuZVES-u#;v|SR zaF|Gh?FDo0B6)e?bLX3pb-E3u67G%95cB4nm_dy#NkenRu`>J+ugAT)Fbz@JW8y`_ zQsC%1-DKil0wtdZ2VEk*_ycLq7q0C?qBd6fEQWVRiHBhX82*&}Z`!fkYsE^PaVeQ3;@DIzpN2vq;R(d>;m)#^57 z)cMpncW8dEjv;`2zjEees(696aN?>dI(}VsZ5A3n*=R7SJ9$_PY@WJHYg3on_|p}M z+9(qUs}*!|WbNZvTJ2##sg-YF`S&{^MH`;fCf=nKEfhNJd}e9|>o(onN@hzLe0vu% zZh+v#*Y|{H=e*q_yj{+un-EJMABO8+*%7amg0bNGl~F!oEcbW)lTc2Jp}ZZjqUce! zuQ<;`+wONI2lhAc(%a%CcqQ(be<4em*zlQOD0=|VEzYaa|9^G{SMpR07+SLE!WSA) zmSo{KPzrEnCYIz&M^N<70&DU=kDKJLi(jY!Hs=4yi}?hxl7E6&vx~SE;#T)RB*RJ0 zM$fNYbCa$?!gi=?NS8bT>PaEaNgwBMXD_n^-IcV=LL92nAGtUkMvp;3ADuf}geU!b z_MLoh&uG-a5lNT-pfUeItUp^c+V|xglw=N8W$uE{3N&p*yrAV{rvoFiRw7(@8feT$#P*>2 zViQ6(!py$#P6jfvnaVE7!J!ja$S)xy+KJ~l>cg5F6<|nyknRY;I^)0i-}S92bUj} z-*h0>BDhTbJY_m(It33Blc~{f<|fD&1ntK<_!hDR1$_b2WF||&ko{9<9=5FJkpm{# zRM_GFVo;dNv6UHK)wU>K)fjo@mjrbMK2DBi%te5tzx0vTq_=9U2?Z`F`VOs!@}R<1 zTHxH8eF~l{vrkqIHrA&!4P&LDwlSTag_v`JgjXyD7&%KuskeOfXNljx6X3T87{k9NraT)dbl0aE3B z`Hz8@M}_jY?3<(#V`uElk!Jpw@VeyNQGviZnTzcSo&mWE(p^-~*K*VCi&*`?DrS2H z(~ER`vfTF~=cJ^&J*mk}F={(`zt$wm!;Esd7G#-a@0`b7L>{EPs}xCIhv=?l6>iG@ z(hA?|6tKvqgmJ>FV02)S)vN4>h2SNLAIAelv^h23lt3LL2de9$Q@If2y)c-4$Jo^O z&jQP3PDR)w9PiQJ#K05ll;xD;xr+Y&2z@#}sJ(M)%#`W3bSs4}J&}%87H>+a^b^pY zT$U=&JgMEHuKkTgUON#!29mlaWdk`<=ySq4BC)SEMwbfpojEYcak|3`!NslLRudjT zpSai)(3mTdqh(!;;~j%;Y+9hWSap|K0JmaZ4*6J(YgdZ%y}XHzgelO~*E+6u!SY|G zHk>=hGBIrmvK~)elQbt-{tWB!{&V&Y_G_{^(0PZzba?iFlr0fsp(X z$%p~cS9QI0J9;!c4w-f$0<%>uI)Z7S+)JRmKCOTOGs0k8OU*Sz2p@X)$5{X9$$q$u zvQrVOe)Zb zjaEuw)~Ud+(Iy%p%j zFy~1q!A1F=)TQ`eW8pQ-QI@4kexgLad**`(IPgVvSrsMMORp#;y$4b!mA>RVhD3w< z#gwQ~``cWRnKtglhmz&r89gK%O)Le(=`E3_Nx3(#1c}JQDu?7>$2T|eeiiIQr2C5E zLB*$wgPLbE!DgPXr5Sx~$B?)LO7+LJC2?;gZUSOk^UN01PaV6+@va0WB!9M5!{#iQ znd?vTA%t%(%H{RrRB$-R2mfi6XzP|?YS-X=cQ`{}6O}35>atu3$Dm~UU4iD_b#o>3 z=P>q))evLq6=`#-%M~;H(zO+rY(?qMj;JQ%&O+gh!7Y0)O0@c||Go_;@HcZF?KQGQ z(}CWOXT>ASAKAYE9B)$t@+p0SEF9WmmS~3UL-k9i!K7K&tvcwj0vU@9ay~M721>sTRSO;qEgLfM4=!7Vq$Ic= zY!n)$_OUhD5$IKw)#1wvNKE;@raWJwfed`PraWo2Yt4=%(}JE)%Srsp&3Ux6D&F67 zyRe92vuPLqm4^1S+7A{gYVSh7(jbwN~fCx;A@6EL`ERY<%ZK03;6B^gz0>`j-X1mzid* z*tP)483Q+MM`CEER=S)!@0jF1nuRoTfJd_j$3Xha8*IbQCC_FR4v2^Blh@Zf4Zea0 zo(Af{=@k8_cd=5diU~W)DeNAgZgtY3=Xp24oXpuHd~eVdMqMVoXT6xDb&NR z911VWULPJC01U-9321xObqQ$moje-a`tT&w_?2Zk*Wp_BO)JEtc67d`DpZNJA5fJ8 zQmT;FNt~3^LZP1bMG5FmmEAP`mXNg48a9c`@M`h2`%Bs5zp5fMo*+TH#nCCg4l;s3 ztBKUSAZhg6eYp@}of{$|f4kp?pOUl14mFF%hQN@^1a3HdKv5oxW1bSGWQy|nd|0Bx zg~|=rQe-%{((8}GpmmfNN=@Ym#@(5xBe{?QA0o^j{Dx%4J0T#f{U+cu>5MYCmYsV& zj6A%!eMiX~$5rEq|F|9PmSKES*Fl+)7nUG<*H$${+k&Cg4I0e}7H_Za?U>;|*nP>s zA6~cofK^S&xL9!bn!GoS^0Bz#+Xh^S@XnEeJ<-GV;P-jSQg@J)$*Z}1iC+`fZ9Z@gm0+G0g(ZAm0_@c!{E$tuh1ka1Uu#(wGkpLK1%g&wvyrEx;C5 zAqI`)$4e^M3@J$PzTs^`lWv)9ytari%9v>I2A@hCOQ^Igx+PM=w&r-mZAM5VsVxy5 z0KuYG3(aJ+W)Nl>NbsHZ@%K=xic3)-n*P0F=a`=bA6B-Q|DkW1TW&7p{sn?)V#`C{ zzVSq1V>D5y&2nQ(=jGN&?(XF}mdUhShS`HX2M)+dA5rFHMvP^zZpdM5TV(jU5B2Ou z0@>|q0Fwil55hAi*)1_SRg7C>&jm;ezzH&G>ReKK#cOJ7Yj0a5+^o!X$7@|kXY$pAQVy?I`FN|ltA zeS*%P6X{}V-GrnqV_W=CX7kFPUli`kirW0u^!(fL%b%O8<>Rm_{&HAS%iopJ07UvU zr{-gILv)|V7rhWY8%w7m_|`v*W3nh^Uhk2 zF8!%07|#4;+jcLkvtE|gu@FKDK_NPY*=kO0{ci}D4q#_%Z|1riuBF!U>>BAq) zbaUTnco&(g9sWo}e_`1q2&Q5qApP-azn?@?dfDm5XmpuOL0uRgC33Tq>RNK%z>45Y zkeS*QM-C6BnKO zeKEfAX~>_VI$ytP8Zp1j-PsbG&uFky+E$I+w<6TBm7Je7lWg0tm3+%^1~Pv)8+@B+ zAZ?b(#UI|b5AL0F6Jza2kEU?!fVDc+gWr5hJnegK1N9iT3cZvm(Qln{X9cgQ#@6hJ zA8prXaUZTta%>zM>bK+|mDMQ={9`MD;V`Bym`!hK%ld4$QML8p>ig)SV-6Bc9O|se zsxpKK< zh|6iCrBf%9rQR{!y3$4D>N_=!h57-HORIF7G$x`XD!tGA{og=b)wILt5l9XL)E#zg z6-@E(tXMqMlB{uHUc=Z{k?pU6*xWBF zfst>PiM9q;);NwUJelp;NfpkzsRW559u<@%)lTJQiySUO8#3#S{p1JHhhXPH>u98|M245LBxkZ@)M>TC*utxM=Mp4 z#v_S`bh5D0^~2E&x@)DiMtFiwul(s4hk42O=@hiadNW&;qKFlZ(~s6z0;fhS`-`ew zt(G`)fXs(Vy(HDo*RM_KQSni)ozaJ?p`f)69;#;(2|XHEH(Bgw_K-*#Q9>Z*VM2kH zL|k(`y8RF`Q10l}q8B;bx2RT=Ma$!L^_dgVd@E>;{ASdS^{f{CFK!0pS<0@^Lju9eV zEYbQ9hxY?9a6a9#$mTnag%?D@ER#myFjp*CggSZIDKmj9ITRP5Ha%dt2=W?4Fm2Ld zu=zSp(5>e=zq^82iD_a3`%5c$G0UQRQbL->MKrr1(x6-w2HD3y{nT6FLG>rVL$dB9 z?HoS7g{Y4z1T$8&V{g#-fc5qYi;x$(Pj&=>vvx!cj9pX@R&;*8A|z8Q3*9A#VmB>L zd^AVQobzNQ+OBsCTU#5mqN6_44pA3J}%DD*Lt(u3|Kw0;&`IU->UltVMLy%-nA&K zf^31-bnrmV(eaBuXR(~aEV-Z^qBOKXxISXKS zNfZAK3dCuPJC+G#uToHnXR|9GRov!4RPWFXkY+;Xas%3^gNzWL10aRPQpJ=m9* zx>X;U_L6+gAm;;@sQe?)b=AbAOXSBB>t(YT8mjKTj}I9{e_!zN!QQ2Bii*_Ju11+?&cJEj zP^2rrB!rFTztm4IkY)YUEt266zThVRNAclg{?C;6|EyQkLMnqYC+7@6QUUDjO#ffN zt*-5-*#q)>N2ig1q*J=P1$8(ZZ^zw%808)mS#;h|w8_DT>`%y+h+uO_Gq3x5hUU3- zj=44!bVXGm^s#TFA3lR`fEz|p=iBr3itG<828^x?!S>fX#3I1^(Bv+j^ZiW$i$Q*9 z;@j2%qhJ=W-FqR}>GMI#`}RtxAElzuoUpUsm&%b-0SHlP6NNi&RhTDQsagFT54J7P z6e1SzK+E5xELr+a3a1fd15@k*j)lWLtdfmh<`2V4newaI#{UVHRzs;_4zkf27ncR* zkhbh6NIE=6I>a@8AN7!WBNVZUOybj!QpD3s`b4`*c$i~WinAvXRnp$$eC_Ge*& zaibG>;^{l8m9#*OAYjZ>$Oi8CGJLOZHogHSa##cTmz}J}e?QR21-+wTHY!D4HX5Pf zE_Rm$^mgd&|NS4tKTuo}7)G`L^@B@3V(p zEH?pHPMgH!PgDvgvD8OAwjP!P#&kLWS_e+6O7^{fKhQ0~@xB3TC{oKD*bn$^Om?td zglImq_MI60A_10mN)rpsOo_s2Sc?pSG8s0kVDNy9>Kf0HxjizP&HR_=4$7$6Sjyj} z6njrI>41(nPs&;eX-_#EQ-Rv7;o7i!m>%-cl^=uGdUm85z9jz9?p75;uoEr7ux|RY zvFwR1V)5|d(ucF_jUV}G`ok~w2AIl3x0h*>c)oA*UJNwVW6ukFL7Dkfhbl_QO<~sK z*yyM>p56UqDYd_pK*7SvG-=u+S#`$J*OGa18M*;1ieJ{e)tVeZBWE%_%f-7``4ajd zgKRWEiu-)9%{1aA)<e^^5?_zjectVC>z<*sNCD{zF_bH8Ll&!Jo>@nVqwk zShNF&Wl^9izFb=#6f&_B}Bqivrm=W#zAwnNnlG0a}O{Z6khW zpM42V@ps_lVZU}dWtDAcd1Ng~u>y4vg}e?3W`TqbomO)A=mmGZfOSsEZ1eYIFxO#` zB5Ddd&g^@49MUgxa%#4*tFsb3i&63`q^iV^WTv`W>Me3bB?J73`Nd*6gn8rNVpE}| z+oP>N^VaH3ERw=%CBOLrOjzW@268nTFC|2?HeN_lM!)C2GB``vPbc2+VG=ZIs>sO5 ztMQNzQ{e4)p+lf~8ZYUD01RN35&3 zPlr_>EU&Wy(>B3p9lTmwOvW^M5)p;6du`M{WgJzQSVW<&|M{XMIv$Mf>+OSXh4Gn_Y~5CpxG8{ zhoE(itOzD&z09NoNOc8uSFu-442g-Uc2j_GIt=E7Pg+?d`u4s-N}$+n#)WNTT^P`0 zQf8D9DxxASTus5J3m_syT6sSfP8l_)p4z0X^nHfz+t@#C;?r3?{jLzlXk#Zl;PWg@|o17sGjwcHzh?i_^RFk>>0<}K&fR8mXlVl z!p{)~%c|@L0G&PE%vf*;r z&`atza7@Jj{eN9UY8+a|%3-mb&Ls_DBB&UvC>rm(YCcn?LLb1aovaZ99~1MKe&D<= z|0JUEPINUM=Xk<#Qlq0YfH7VB+);G=`izPO$lCsEfW2C(R#dNT=vEE=OJF*cQfu20 zu7&ZdDzL_4bcsV>oL)mlqeq)<-zL2hIvXEOoZVVmN4&VK>huM@O-+Q*WU%rwqrHPH z!Y-W{(Kp(Yz}*D-*a34~$20`4$bj}pCv#E{d2MITh*J<{K2NXgq8C=6GEbVVIZ$ za3Pz+!`DnwkQHvbSR|IuxVw~vP^bbkeWu>Z$*nLp+$__#Ro$iIQl*7o6AF%rBg4IM z&CoS|V6!sZ#(qBA-l?Fl;shHWzltvmtA6-0+lwdBf8h7 zA2Y0}nhfCtZqlx;RPjxrPngUu=V;<_Uw0%|=RlK#BGN;Nw7&nr`+g&~tB@+gO=#X~ z@@zqz_~#TuBn;-ys3R)6aM)#Hqa6NtFu@aPSUk(gyAh&n;AvG53$I$q4h2mh3iz*# z+b0V(KAN9S?7k>eQ*E$#oPg3(!l91S^g*8GIflR-5|xU|^1m4Y1eCjzN#(#gxx<)-uM|A5 z5=o_;*hb^k8z2t6b|+cY(3KPHUw&PVj*e`z)RGmkcK-La{X412D`6QjbED^$Tp#j3 zbF?Vlak(V>Q_-_=ymmxRv~gBt$J(|$!nSSXNqZ$m@fxnCGzWaY?QPn3?hHJPE3Vx< zj8UR7Lya64pV|?dAV8>KOTrJre!tesNkg8fo#6QJ(jw6pW2ZS{r7SnOb4e*f$Zt^O%^! zR9l-Jkr)YUJX??Enbm6qGQm0e;UtdM;IpD~tkhp-;gd<%w&l9u4z=l#yi zfaN$)jbaSt+CioIvhaIaC3uHGzTH@wpY9BE(o}-5qY^B*QLIlep|iLmyJ26@M7IH= z4xV9xeyx$kKg^|875NyE+#QsPJS=VKg^{$aCUc7YFgr+Apm76NT}+{?xg?hL^F);5 z1kqnOZy5Yw)y2o$?n@nvwh7YbpN7wbfr6k%3DKC4WE))$10|5-?`SzZ<5YdIS9?r$ zJ2ONLI}u)NPUnh0dWq>3ncZBzClmC5rW*)#$CBnV>w`+9`1Wp5Q(?fQ-BV?JvFz$r zRKc3&!Fl8+ki0onG;FgF_hrJ9hig<&w2!W+ydXlj#?>=s9oHmE`7O;my4WrL1US0$ z%|Y>Uy0#!+{wT^rsBeVRV8iY=F&{*y?8`gpJ6}9`g|LZnpBK+O;fIsie0x{w1zF~g z4N^S%eIAg$K55Y9ZY^xRR|Tz+FF~NRuX|!@p&vn=^a{dsATw2jyR21f1FbawqrSTD^T!#1# zP3t2UWzR=jxypvIhNQI$!{S46Nib_Hvzb&l?ZWmwYk;)bZ|_>s#of|T6wq;;pzYvA zsD>jv^yB{Wk*{#k#(bY6z!?1rYDp32+`iWxTnVvrjG`|o<$@UyHC&DSX^ctJ3$E%l zk!3L`ZgF8)0TP4|b!%wLYs38e{pUlX>k>-;I#NeyOocN$a=b+?)R{&NP54dWeS=L_ zpo)5Dm}>!wdMb!RT+A(!3gGYY0BLKqxkKQgk10?fT#mSb7qN!6c@Iwq`pr04KC&We za4>pQ;MH?}aPip>Xul{9e=Ch@zn0Igmt?s32yOkcW9J?~NtSYWwW1Y*2)F(-yy%-o zapjR5gRR`HYk(2O4CYYF!2EI2gaJ`rr%nxzi<5}->kn45-RMq}Dj+Z_W*XP5@0i)f z{tnHkOmVRnmvE;snPC6xPjqg!>?)WUR@;|tW&}7BECh!i!TSkzp8d9p$#5Rd*Hy6u z2o8ta1``BBRq?p)Y)_B~&=piBbtD4cN%Pt-V(d2s%#BaLQyVjRH6-oLqKhSa>kbla z{Cr#T;{OicSg)fp;sT$y)XUdA?0s0uMr@7oHpb^r``!DlW$)-sf}D&T$B6pg@5elIre1WPb_^;=Mc$3d_Ua$-n#UaH}S#8 z&&U=81V@;C*$DumwMV~3_dW9IZVF=k<+Rc--4{$AIv463>l%d(lwIrqS!u%W1^>oY z%26!UJ~27sd|lZ?`$DoaVq0iy@iAdh!~WLi<=NVC-8=S)U+pfh4NAbt*9-i-vCBSx z2fj3>1VRtFL*0aC73;_A^Y6aiaj!|BlIwwN{31PoMmJ8@t5xON{DHUIhe%($pKIoxQ||_0Xl0!G606#8ejsA& zjU<%+j$7Kj`(hg1L7C9D z%*}BfChO$cUC^@a<%=^6CkkUh3G087UEwx%0wp_Wd%mpEu2HwwkemJ64aMufqE-*L zT%3*fua$pe3&d^W%zcxh3XMKW`um9i#QRpY`_b9PTP-r7&Uo?8sI0Qx_rHT&lHKzl zF_KU8K6Ro`^HH+orTH&3NS_8J|Cx_6u`#d{v2(KjvmaGR);jp&fy~0m&A|Ct$-?}v z2MafIf)XD2Klf31P}cvW;PgN3N0S{t#i!(_>QB4UGG;IWfa`zAPnj!ry93C<7k6mR z_+2j9=@9-P@ogt35OBMoC@VrBP@y;PLR>g9GyJ=p$Jx75%VS=k-t?v4=0cuZk1MUb znRc=XPaiA!ntBEOI$tK%t|*6FiU?n?M%FeyTpk}DXBY;HHu&EjppqdM2!Ra(AR2hT zzuCG?7W8Xpd^Q<9N)9m@FBq$a zE9#8Y^>}o8*fDpm%8_-%`Zz+=_iL{`sE$rrba=deS&JR`c)6bF%^s9_(?`&McYQdL zm9+#kmk)}jeL2OFGoly?dwOqyZV7Ao^9e$)MTu7jThTnH6)4kobI;Ze=IE_g>k1LH(k;5tJTg6@sPb7N&h&+MD{^rBPDJk2Et2A@J%sg zv+-)gbpmRX?GFqscW^(D*xb+?VHjQ}N>kdn>$iB!pEJg;;j24di@nFQ2h7ik`=XAF zul7{tn2f4Ze7FG4bHZ^#qkFsLd~3RE363iRYMuRmQKJvb>iibOKU z#>vST-?hmNgPnb<3+1RbF^`bg8j+Z$$LOKKYywf{%GAlvA9^(`@JTHEZGB9?e;XOW zX-o_9?fN35dQ4eY>f)*zCWDEP|2G~k_y}|x zN-234olC)&rii#GSJ?nZoh}dcdU(e$<;{v!sU`56UCICpD{9US48KGv5P|&Fkf1?r z$oBAuNf0kk-wi%@h%5dw=4w*WB~f2%Gx@y|KZ*a(azI_4#s{g%=KMu+>qtm`nHLhZ z_@m;MguhJhXy#OONNG3v0O{=E!!`Ae^Z7GZ8Gq^XNS+M!*{G?dfb!+(AyY zL1Fp%5<)kf?{vs%7ev}9yWm+9(=udxsv+a70-&5rktZCR??G-C-w)*>9kCVihAbU_ zIjtF?EBZp#5c{=2L_vvHcgA=N;OnrhZTe)#n6%fQHXmI=Q@AldxIvOE*L983@*E&9 zUdg2cn34C>qg>6N#+Z?CqG`H62fRgOy7QlEph*ob0v>8-)|M*>7ebO{9ESs8}DzhpZwwXfD57DK~<(59bW$@`we!)Kuo4}~pCMf^yR@6Iv80H3 zb7srTKp?nB8$Nerf%Yj7;A$Smm9=z9cgMQNJyrv8jW=Uru_{Y)6L%Qt!;-7mEZ%#7 z=yJdjV>i*9K7U1L0%@Bt-6W2UHpul&g=F8s<+$t z$f5+Oe}v?WtzAnet$7&XGyJT~g*g<;dizsDG@jtK@8m!z5)Q?@^OKlDfUKkMGwPL&LWw!C& z$uuTWUc;Opm9LM=s7o$b{#x#Qu-i)7fxl>9eaJ8Z!ykVHRQzJ)IUYG6+4|7y&ls0u ziwjHsnD~`ZFsAfCdw9YzFofG@=If(iUt$=_GM#UPvsGDq_h_`yvqDRG z@ghBgR1qUGt=WrJN-7)1zy_-aaA!&rx7h9Nk;!q)f{F;2W-jzR+pY9k;Kqird7wQF z-h?b>w+E=!{bBT z(Q8~IP6mm&310DQ?^SwWOHn$0qui(uZTTtx=jU&gDX6dEt1;~Ud>BcpK-9E#_1WD( z4}069pj8VpMm!cmKsAyF?;r?{=a=HT9D27Acg@vsFImyURVx~w6!OJ*nL+$%=bUze zJJVDnat-8?2JZPiTy9#&L};V9H4^9!WLD@2LbpadeWvu+#Nr2Ptk6ggc%2)qFmO`+ z=x;m15l}lX;^{|M`&QA^fF6j)iVZUlQ}oI#H5>FQUnln6?f#9B=sululbK26G}?(; z5MEZunVjeGMFZvrem)%%^RA1}3wfa@IcKj9o|6m4I_wZ+Bkzesw~3_#?rV$T0Fx~% zW&IV6+7B51=nHtM91r9;;au;0L&fMnZ@KiY2Tln``IbE^uM6Zq0ApO3ZmOm5QK;OM zB5QdXCa|#5FVK>{-UAz)zlTidYs1KoaRWobzsvJi5qj3;i_d4(tW36YXo1=rZkF1( z%>9fvTVm_PZK@bgkA*N2p)~f^<#^XpS#?5EU^Cf6mJ`2KtcyYC2h{FPkp;@)SRNuxF%oKA+Nv`(qbhcqh^=r!@cs2(d9`j``Gw72l@*YLvN>pB<4o>j^$R zslJ@lpSby1WwQDnbkwD#^u!uRRvK}-ar7=Os~k;~ccbIvZlt2la6GFfiG8PAzg6hr zQw4u4p=wL4FdaR;#X`vAUX34VLcqq+_S#t!8^Va(=>YyroC*+-w^Qh13h#>SO1gMV z>7`iX<^Fc(N=JWaU%{VcsZ>$r>rk!0t!ety7y43)Oo!E$tW8Ht^*B9UoM0Va9Wt?J z6GL5k5F{z=ah$e%xDJTOaM{_>os~j%8k= zbLZ;t%QyQTBPL4y9?wyx2=0sznEj3|C#4g|QHp5d+z*1RV5(mYWqYL|tD7%{7IuogR%0ob(c5dl}^JjeW`(l!_ zhE2-Cl%LwZy(ww~^&NLLT)DQ>>0Lkk*i6UQzitBy~Gw>F!BPm^PBohkFqjJUg&P5+T@CCOrFgx=K^ z{`runc9|o)eI>SzZg6D!qjAdld1RHY#GYx&iM%w&uqQo5tOihyauZ<%UptyJhgVto zF{-(C!Q7&5g!sj|-_8;hdUD5iP8rad8U#1u;YBA-vuY+s3ccxygO-XaBx1i$E|$Yz z3X>d^n<{{#I1CXOT6UYH@U~08j++^TUo zgZz85iuv~sxltMH$;;dC-a#Kq#0k*UQU5%l%gDUgrz$6`$#9MR;Mv3aG>}gwQ!>>% zt=B>BQFA-R=+x!1-pZtk$xr%EUElkrtei?kDE6hA&;A=$4slm3b7E628GFISGUJn~ z7K36tn#SE+n6GbV8T2#hFD^*WtEsn82R?#3!7$b+1>B$XET9E^+a!eZg=sk2okH3? z*+1#IM63B^;l{m~TbluRF}8T|`;m_2T_hX0T)Sr2^+Vgd!uBN;i-kH)>s{is zynETPdJWLX#SVZ5UL{@&j=m`kE zo>?|me2j0^ZxeRT4nZa2jxAluFh@_Dm!NS=-L%Zflc5>NRHPVNsph9e@^M8BmWfUOC49tqgHC`)svOhqpRor|2w}4;^ z`&s(OFyUnTzZoXX$rd$`s$W?+*oatJSUxob7S05vucZIU1j&p2kktP(D&>EQ1pg1C z7L2W=dv-#UX>Q_GN$6G2z0 z3-W3ZdBzw+{mkqd|A5LppFfYydoMf*JspW$0QWH0qF>i6I##J(JYRji(dGSMRPcL< z(I@otUIb9IfXB@TK;ZT4TkFSYHisjZ&%@(|yMV;S{f52!OLnJUC-3|9%LJl*hkI-G z2f&Fr6GYv#wiv8?5?sZ2Liu|8D1D(NDDctGaQ?9fv;fa{wvF~ZSINyV7XpH9PrGim z8-a#tAGq$>fR_c~%W^-5T;=pCFu6dV=ou zHCr5e%aGi;JYfvcUm-q~+)ifP@Opj#uIB(>Y=H~oofltOgea`mUfGy0W2DWIE9srB zYat&Dwv+ot)ZLRWSCcQ)8HcY=jqTpgZkUMnF=K3xn=4x<0q<+qzwwvn`>(FLp%H^I z2U={i_g^^y@R*iYkH!0>t@l#&*sgc1+n|CNIQ}LM_P4$8C(vq$`-&I zU1r~gYwS`qI4m#iT)k3PSYszgtLdKWjX!(&ehYFB?gQ|>d49l11P}^IbBW@bfvLeK z&qgr13_>ZR?l1x86VbHtIuyXn^b``OSi5kKXIEHnfB1-iFKO_(2|B~0jICA3VEi&7 z3j;zg9c>XqMSf&Cl0L-P+t%59>mUJX?rWg9)S$ycD^NpGx;ik#++|mobfurbL82OhY*YB93bX@pTo!>Quo`_Z+UA9@ zdu2pg$Kc%#amPz&5g4;wSc@fA4#kLLYIP0v-#lYQ@)L*8H!KQv@ue19bqr+wugcCUs;;Q}?m%#NcXxMpcXxM(;C68j4ws92aCb|vi-q9s zZsFn~SW>=!J389Yhqlk_?DKTSK5Nh4oNGgi8o8Pv=Jqq{S=w$Zrcp8I#Gd!-j&+9d z{`#5485s5%SsTxjkcEHV%t?ybJs-@D7ZV+WsE67$Uc1?Oe(LchN(vwykz%a}YpQMI zgO>+RSOx2H%bg#TphefE;%6#r4EcSZ6^Pt7R(mOF6f*;25~$h-r?#a(wZp?D17ryD zdbmiSL*L-fPA>yu-sDq;3HAh9XW1U)-HW3P+Z1d1OCnxarw{UxiX4@i(`GB`msY<&?+S_6V|+HM27<+`}D-?8#XJmVeLA|Zt)udIlmtejA$ zC%RWw2u@j3<4HgFN+EwpLafaqz|a`8$&Q@VXkKzlkMB$0{jRCea(Cf{r%a(VUA^5n zG!t998&AZp2;fD@UD_ff%MqHArRqujxI4=-5pKZ2%p+fWe>DsGfV5h{RkIvr=ZIMq z3n!g|CbswKAv}`vU1TAM`){i+d(GgOe?~0YAx+HHYlT_OC6|kVvf}X-KzYscI!7SZ z%3Iv(A0mRz9cx4)Wbu4f=m(S-RQQhx5$dmrzu=|#{iIJ&bzx8Dp=`dP<%rvs;Zt^) zR~H2?fY6aX&Ca)U5qI5wWBQc?^wJtH#4ZvCg}q8X2=O{t=pBJ z)U7w_mbJWRP3CWuwK%hi!s}um;NX6rK3-e3l!PJC*0MvAHwk0Q4>M6~+-IU0RhAn^ zgooGBgR(Nf1^5*ckl^P8)1}ya)LYe?<_k6z!$|OgK8kXn7ONZ@4iwJELxr)*LnKG* zK{n;ZJgyV5I1*nfS7p_$uBd0!97t8k}3EMm4npm<|9xVATlewR2r$&~eiPp@o*r!FWQ0DGf`;4uQZgUlFGVi@&u#ZiQH6 z;dwSYz#TR7P%LV7#MG7!{b=!}S+@562p8ve-Gs+{qhp=0RpF$@8pJiGz!z!I%mR+~ zm+h!noBFZV^^;_N@fMCseAaL#TiFPw=xw!&{GR15WRmY;L!{(q4*foX|lM7 zcDlItJQv*@=9R2r{xFW@B6FxfQS~tCwcOE?;6vp||x{Tq&r(_-jy5?;rJ!UrZX$zrtVk@@CqI`dQ{! zrT;x#0qi2x89)8lr=mBmAU~<#8@p+7q9ctrl(#D8dAa1Yg{GsT57Xt1Kc@Ty?=yg| zOMeqBhE)4HeeZ&tF~I#f{)^lK@@!^=l80AnzV)h)-SxrbLo3lt#&2`54|{>OWdaL5 zhqiw?MonS1Ty!Wli3_b0>-geBk021yfh>g50YKOf`g=KmDph)&XOw={Id&3rgFC}T zP3VQgMUuIE$@GuT6`jR3jLuz29-sqdevz{!U8!|M3L)U`&>ZUa8SLNSe6$nmjD1{t z)H&>PQjK42@-sb@-r_S`y~^_f_$&YJI!DHw>%>w)O=Z5V0XnW$lIT&JW} zOz6@f9j(UPitt;1tPhJlN^7!;cj1t1Uo?FF)6c3QWB6v(s2G_njjBit^|Ylu96Z(; z)-tBx64IZBva&ucAm5?zy@wF0LuI338Ndec?q426)>yd;ODj)|GuT*^Oh25C#HXN7Db~l#L03-YFI^9To8gH#yRU>2d0a68 zXyI#f6Kjb5P+Je!-lbcP6}c;Z7ck65u0Vy-Mfqwe(>wrKOb`6x%9j@+yj6h4`!(O#52$uh*K1^Myo}Poz_;P~Zr@NB&K~B2d8($*a5Ky#G%kc@-ce;P z-uSz>jxe*LLLE93%SIM)g^D~`Z?^t{dG-5^6n-HC|oD70~T3b-Ko- zlYWLRYrJ&uxigDqp-vddZD9~qtU5RPA9~Yyhfzi>TsUkW#0Lzk@kI6FHqb}^JKuGG z)9RngcZJD%v4d$$GaL=HXnjQs&vx3z_t|70Z__Ovs(9Op3$GAU5##yzh^z&<-*-1o zPD>MGi-VOfxe3`TGu+t1wg9P>KKhOwv7Z>E zFsyIwp(cq_95HsLk2KfEP$k0kEY5FK=Bc~`CWJdb#D(d08cV~9nKeUlO9)$?_sI$# zdld&#FRPvVCLN z+&?Q74y4^ro?E%i0x;pKBW;_Kb8IXF7FF1)HgRXoq#*{(aSAXI+P)5Zw1n&{?Ul1Q zW@n^g@IWSg9cXt#aKq*lP$NTuzg^LLNd>+1-gK$LSt{o4J(MKKt%kbX(;di`^arm> zOPiTZZJ2WR+!q{IzV|t|7wl{DPI|aOGz%*}DbH897h4YvXdQpoMon;HFeu+Xt`P99 zq6jUFPw()c=s`G7Asbi$GMk3Qr!zzy_4vUCTRT4AMaqdeSE;D`LOh72 z#VHOKIRdMFIU&ckkNX8&%Z=oEU0CukODX~Z>5P4fWtl{+VP&U8wSK`E7q@ro7%H(l zs-^Qzj7Da`TI59S&viZ5L`$3t+RFuY8CS$%W!Pj}xIrz;_}Z3Y$sw%=anGm!;Q#np z1DV$0$$<^1pQL~uqwuW2*%5diOm0E`kK-$k5chwl-5=MuVle_eM&R{<=fm)7m^@tn zDf4l1{fCM3aQ`o5xM6rhRNfCt{&D#I0Oh|5<4X%pZjpK<5_tuhM_L{$t%O z*8hO$g8v^7-OC%A2_VQL^uOmf3O5svCO!cADbvM9v$rx+B`s%c(W3b#>K|y=>&PMa zrd^8qiv?A?ln1r3Vo>cx5gCVgwsD;3*nX-6^+u-2-{%^$zcvMZi@X2cPriBl{1)9A z{CB?#F!;Plq5jV(%niK%?7{KxT}J@z>V6l{_4Qr?@c!)cO!1NUI7yZ0TWtDgLVn1w z8oSv3*5@lDC~-;fwk-BMTQ zT&M4$&p>%O%Kr24+8_78MbFR$SOGzeYsfhso7s1({@}sAe0M}QiB}E+jQ-(str~{QdZs!fjH99%0n} z@~xL5`&>KNB-=w#e9F7Je139qWBBvYdO5}y4U@Bx$Jit&$G)o1i)($56LV#K;V@j~ z@N|BPuq;6}K{AM2J7|N7xFAj-JnJ0c>iaG2K3o9yPx9h(=cbbF(M^o1>sUd+^UY*q z=g6;or@$BcM>mXff!UG_$yVn!KKRMzL&Gy%xn+ z$e-orp2x+gU?^~SVkVfiP9y`MT&qUs@p_gdyxK9p5`bN-dn5w-O&+8{aeR)iwvYOH zJP@EBAZ&?JzguC5YD1FOoXydx5Y4uSsZz>q8etkthC0Va4rWItEzu3eBBey3=GOLc zQf}HKdzTX73CNicmbNLCrCQsOEXLKyKqBpFlV+1a)~!Rk!X=V9kfH&E#N?utqO@u^ zuer%}!`JANea2*?iY~t(vT8l9A$Egs2b%Hx)DeM|%tf27DjtQkP**K7u%!{3tQG%Z z#)BbFP?6h7DTivGzx7JZyJ;KP&K81W4EOiGr8thA7XPykucjz|k9>EiCIFNcZ);P7 zh1}}q$&U`irB`{WG$aSa>&zP)kQO5Tt=JXrJ@XtO&k7a0PDCUzUH!u~>vFLrkF4Bf zv3Kw+Yz_eRbh^E?S$iM;rOpjE*?@ZT>|J3j<3_oq^#gud>$T5)asS0ud?(vQ8l%AA zKWCK$xc&$k1YpLydd_8(FV647%H$4wwPlJGvY@GrH-nk}epCr)a}%P0FWvCH3wyf1 z^Z8aD{qYTa!zbIeQxHQq01Ey3?XXQtdBfOJPo<)c4ZHar$V+E}IE|2t!^@d4n?X8l z$lp3QszCP;)W%vX}fwhhtGyZ+?6y$h`CGsMAF*c7 zU>BkDk}8t1yUV_s+Z-U^0!n(7o|U*lUN67Su{@c?{}MOsLCrl6sfUo6O6o>q ze_uO;-jq+p%oq%ISyQ0TA{T-mFURNB9N|xOCRtgWamF@8vjvD14q&Wf$x#eSnC@Of z-CsLuGPXTzEgj0?7n$=xA9&%yeRD_NRo(HY1K84wdhsNyRgO<(aby`Hp<@BCh2wL= z%bDuEFr}SPXmF{rCb7pNgS@d4RQ>F)BaoIqo#9{++n5tg8?ez<#l9TBQE$Po%Bd}? zxOT$0lM<9bA|~Nw7LkC}#&dV*w+Ml=^hjVX{&eS;h-xp`&sZlMT zVl}Yiq%>t;t?{pu^qrf1q{eMKe)gZ4*H57phA}&(3sFDFm!il$Wd;I7XXTZIAt_+J zCA~8+OrGU8xLJ$ppE9D$-WfPEvCW7=0RNyJN^AjEX!*@@^d!!W$N}pZ!~*Fun8RBj zjjdci-KX)C`!L-Vis5D1N*>W_O}cG7Fh5<$%4d(cQe8Giy*CF(S|Vhb5>gg%Qfti< z`B;Mi+!w#+%&k1QcmA@8DYYu6Oj>Jef=eY(vR;+98!>$pOf~(diz>Hx1_AIYU@PuX zYlM^I_2u_9cYGBy_Jg%;Awv^Wt;xDZMiM^A)jZUOdSnr1hKpM2l%$(c z(3gLj>z6Zp-8D;8$HnNK02zc|d!J)W!Gurq=JTQ*j?D{Nn_O=&4(DI7JL{K1%+J_s zs5b3N^YfLd0$%HG-F51+Np81-fS88>^@N$Uj_xlUw3F0SpH>eKS5ye=9FPcaLQN(S zGfjL>Z`xAU`it^iC5-aHJq*1lvs78=_| z&0tYyP#9-?!wSgz-zRW!_9zLDdCC@Bn7(Sbnmt`mLVD=K z7hr$62_rE5DZBR8NkOIPtew95_sjvUs|!>fIk#(hOe_2V-plJ7Rl~kaub+|6>hr|S zEB8lB-cd|^{ayq5IpdoF_~&ua62&oJxD!GDi3c#Jrrw|7R9voKwVeLDLs`=)=A?({ zg$m3*SU=}$Jqr*o0{4J|D1rcxk*rO^gxxx4C3amZ;9^!LCZ^)JoW9=6m&o`;!5f=R zpY@%wn{x2FFMimO8^|m#Yu$44fqzVGEDRgNHqdBlg;2>mb@T^-^SdsKTx<`UfT%3rmz;l4tNpbrJ~5#I9I8FKQtN)=#>F-7^>u@++32(lo8?*Jq z&*WQyYEf;tmzLdVKR=64@yq0z`7uoI@!KOPYg)(XvHrH;7@-;Yo%Nb~R>f`6tZQXg zRhLiYIKpmY1U}sFZcAwwuboz+POerhDiHHfzRv{4$y9Owu)w$()T!O}f)cW}aF*~} zSmXXtF~SVUj%B@EACXDs2aG=p*G$>HOsXcd!?6m031a)5O1uO_0ORE#QD~C9=tpb1 zXwjMLUM1x#;y8*Y3^BD7H++KcI3tf{;9q8?DStXHhw#<91Y+ec7H9QC{Cqz_O_VDlhV}?X=B=X@K+gTzAi-JNsm_k-t2m4$nhR1GY>vf|YGXjFQ8eG!~(d zR-L-|htVb5F^QlQOW|B$S(#G*GRUK@yaLdB&>5d*IIe}!T!(Q7-0lKiEAvG&AsIGJ zc&Fy{)fVfwMCT$)?SUxiqU!gDkJa>6`?dClsg-}yQ$Jgh_e|ntretn??VR9#KDlm|n`oTd{r2!tL z4PRDXwgXX(^K}B(A9wuKM7ppl%d0e$t|eW;OA{r@8!th`M0@#5$~8`z2}4&2dd~hB^MOc(G)8H; z2v;oDlP)qZ^tvdbSr=w?go9nZOabha<7|A7cKRDCvRY+M=|2-AsOm?h{P(6GH)`H` zd?IM6GCl_hN`=v@x-!F+r`c}Zvcp62b`s; zcOV*mllp4E0$l5ihVN4ej7n=8?^u4wWNtg!ZBf<1&&44d`EF(C@$}X;vm5NEB|7Z} zNud?mOxdM^QWZ@a>Xj4*c#&0*KKCrD$@lBi4NlFdptY2>@>WpjZbemh2aR~wQ?U?O zj+l8WqG6$kweKuY5l&2Y%Q6 z)q%h5ck(%YU%|p-AJtzCQn4?rvwJV9-$G|>B)^QrhYps?K+|w5Zp|yNm&7x_|y?)(@q4( z{AN8FzclydGo(}Qc(y0u>`#nzv@yf%MezG}K{Bsi16G9gs{o=hJ3BT7(KTxLC^Q#8 zDvG*^pLbnj=VUL@?XPwBg3FPwa?69>_W5Jx99GC!GqHUt=XMw7v+~1soUnAND_Nv7 znF7ho9UiDsEgU}|L+?rORZTW9$@)I-2b!C8yxe10p2h{%EOYBy3ls3SW{@`M%%EAv zXE>+wEMmv{bpQh72f)GjJ8=zpX-sTrE^DNj?Hkli@C?Jx(}%U+rWg zWBgFAXw3tnr%g$i;U{TIs|{^U2$rHG-cUv%f3Z4aO|IC?S@ahH>%+y`0z@IW=#ZA6 z^B25?&{%8EPWgK3;=PC<{svJjI|ZwB!sYlhkwA(5H9%$fKZ>6cY1{6FSSh|5p7%9y z7H1~MXp+Ae4$SsfaGpF*KisLLT~_I0X1O-PALE%!(v&*FPBEw#>u};x>Xb1uS>T)((#}~ZS5*1r9tS`e?R444uzTWFNAg@3vsh0dWHI)x7#b}c4*`t74R}=$lknF zT7*nO$fAW-I1?l$%OveIwBJjpbJLuK&%P@wEdaPoD7@WU;CgrJ5=s?gchJ;|96{Uo zP=!`3EKq0tm89D-N}&iX6WK_%h#5&zQ+F9(VTBatrllbz;RX0adE9FteqqQ*?E6fq z=`%}aU)|8?Q%e2%oY#O^8!BZj*$fY2U2XR zsvuqjUfC4UmDuYR*mQvdzw_kC>bj?5l)xlQ#6Pu-#v#tF7U~qOzx4B$882zfzEmgs z^hAFnRU`QHuOB_NE;T?fQ`E-Q8#_!cGnzdog}M#Kr-k|8l=mN}YsB6$6~O54v&7tk zP1pZvQ4#u|78QP=-55MC8sC2x;64;OKB51pceMZUsG!0Ka{fQba33}m9ca$~cu^Pt z+&qH+hY;t!#g7?#{f^tqjv1qn4wDGef^*s%6Cp0S3ClPKqqa*??YG)8sc0ceqjl+< zN32Fl7C`#*?ad*!wGb3$zJ8v{+Y9OX*7&za*p#SV#Qe|0_;Qnk4?x4<6*qOZ=x^Au zyvOi<;3ipESRi1xFzor^_Tn*kG4#!!8JtSr!@gPCMvorXD!!-pxgR^(_xTdzWgh)G zz?byL;pWL)^dg52PUCf>`EK6N*s%D+2MY*9+;n|>P(8+Wbz7~$KhDMfo4*9H&Fp?k5iyS$AxS_$WXE!$J8Xrm3MiFA?{EwW#1MpX$mL% zD(T_-V*y|W)7m`eZy7v!RV}0y`Qm}krxADU0{#ht#+wr~&U0kd*t8$SBGrli0>(yH ztLz}87Hz`!=!d4$!=}725t1n5*W+<34{lX6lv((~>>q&~850xrbtQy%!hu zwiuG^=&A4_#9FvZc{tN4(}Z~a683~Fahm>`n;rZBoekaETvdk6z&vejg?8)t<^eNE zBqF;bf#66?8T_?lMET>mRflJ}HuVaA-obAGqPt;!=7WeTShW3tBe>=H-pREC#YZfK_iiL^W7IQso+;MP~f|&WA-{kaAm7jOP)I{$TkxbGZJ=~He-B7zjJ{YnYhwV(1nR6=H z>8X_Bd4Bf9RYAgB!fHJCcSrMCJoq|R*ARs^%Ij;@iYg0#C~(s6P!(&a6KQ?&H-_<8 z%p3cPYUWak^oj??PtN8ou?<+PL4;7{?=E90QO@CLrJtSoh~IcIFO90<{%tz7gT(=r zf?wEOxn!BUr1z;c$d${?JM?XPqLB|Wmd>!!$y`iXk)ORQjy%rc9mxrtz#WM3jUIQ* zS;E*sw~o&~pYfHuI9 zC=HC-(7SKtjB1-+q_v5+GFw@REP-8D&mxV0Z*PxD4}4HGZOOSQIQ&jO7dolhZYCgx5KPaBQV6QL}rYCj_=GkE|O|P#b>7& zm3rbN*IdPTw291iR0a45SW^A%)uN7~4X`1mPDgYkd4Ey2D)#&5`F+J)2@r)?+D(st4 z)dKQVEuGJDM&e5}ImD92`xNO>6UT@mkJ*v!}{a_NgX^sGzF2`PU}q z2w6cX#+s;|o9#Ud1wbVijrPWYh!wdiJPV4myKTvx765mwxW1AJ6OV!T0

    RS`_9b z4k}YJO+RvT>e6oDqsMFiKr1g)43Tv7deNZ{275bGp?L2L>wbTGg|7otVY?{l%S0?mm| z{CXx>-T(pL>Po;of>BG8S`%KF+0cbM=LJ8wDHS&1 zK!2bO*bja4v~;eXVmF`W^5feJxp^LT*XI`EoVR4mQ}Fgz;O3hoWT1t1m6B5`j>0cIEW`QDYVi1nMO%7wyTsFP zQ}QG41lCD|VWX)^LwYzS3BNJ|G`6Y*8$+oBo5GZ(ActCLI+-G6qhLa_f?}Fg&g
    ~ z{HIBy@0t-p@KOUdmqRmkIm97&LqqccH{uZ}V0id}rTfqXK?GOhmtI%i72lv zFE_uvwXFcZfE_oNAfGjtm9-EbmzA9@znu*a54ZUL{Ry-G4b9qELqXHa%Nwx4(^J|I z#2@V>y30dTT+T-0lC)`H!q>_yA-rDV>D?((5cwJM;#R@C_+NM zG^>=LD}7;$WSfKMN2r%KBsnq$$v0o|A>P9|P@bbnTDMVwM&c}!l*82~U^7(lJsfcKCa;Tnzh$GoXG5Dz{T<`QaUy&5A8{L~5kufI^Q2pAV4gEgFALSuXA2vnI gfRL%*DcOr>prAxr`8_iEV2(2_VT^%&NeFoV4a#P$&j0`b delta 170044 zcmZ^~1yodT)Hh0ZH$x2_(%sz+Qqn0%cf-&i4MTS~5>nFLf}oTjjf8YJ7tsHE@B4l0 zx>)<{diL4R-oIzhnKR3u+hpHTNinHaC8e3zn7NRsyRHfzk$Bk?Fo`%g`8c^aIe{#) zKs_KYHye$1(zjpxgaRFI@>OdBC2M1RmFXvz3?FVlQARF6r7*%Hr_rEbXf&a%p7CA|v zo}dMrIV+zTugQBJc2jc>9(Hz4PBT6p3my{=J}!0+4sPN9%fsydaxnl33nRI>I$N07 zA$ew*nVK7~S{j=g8}lMkq-Xco(qfEQK~PjT1Y2o7P^1LhFzk5_Qv9xdj z@^OPTp~)b*QtKq(fS|X}#bgDtC|cNCx>^CB_wv6JGd6z7D%QgIz459}FR&j1)|i_E z8aaOC6k<3u0xFsNy4?cd9k4BcBZ&T~yB#seM+Y@vy^?5Cs}^K7?Ow*0cN+A-41Nd{ zheITs^&J!rmxasIzz45G*1+uY5hH`}JW1&oR3l7$Mm=Nl#nLtq7gc^kqd8v{y3}+` z{BjrYm^-M~`?UL6mqNRxq&Y-07a|e!6Gj8PWT<9KFDwQEa|W7e5Q1(C76C*jiY-q| z04FWRS&(>$T6SQU>O}wHG-{Je21;+K2P-RreCmM-GaqyJTz5AFglWD_7Lo;)z4^Z` zSlFAtl#Q1=)z}eQ415UVi_gx!}a+u&kD@_{jNb-}-pah|!Cl`EJ4a1Rak^Xiv1E0`~FUN{440GOQ?3zGZQ%Yd5s zA191L3Z7*|1NR6>fQ3;Q|3?b|n{ea&llI7&UhRA20Ps2m&MTkA0|0;L#)jm0jhDs4 z{ExFEWdffdNPz7~0pLk~oL3%*K@Y{p`sxV8cu~WGQ_0c(Q?+9;fCHabv||Cl#*8?x ze3}3m@@uKtc%IMyGkBe#X~3e$q~J7c%D;x^dj2ni64@JYEs_LSi3|Yd=EQpCz2VTk%lW#T z6u<=em%~E^fc5DyUfuCf8DFo4$Zx=Lbdq4h=axK&L*?LoS^l@*?BG~BDKH7c-{eRb z0ANj;zsa?-0I*+f#>({q8a}ocxUsYGzTWTI2F{~GOZ{#INe|9rk^ajBFmZwpo+0w$ zV*+M^|C==W^VS-e{>B7Q(Z5+~oXo?-V=NIePw7CR63^AP@j_sI9xlmcV|JMl|` z-@kdiCKA2wIgto}#l_AGg;8&5i5%6g@i&6TTFZP4M|l5E6nHpU>G}=>YWw z2ruXC02PoZg!4~8<7Ik=*2^(N;{||Em~s9|82C((Y_IMZ_<-jO;lZ((sQ)w(v@fAv z*6gq`|K$=ffyg{BDRXl3K7S^?fGQCafb&v5PM%l8zy1HUfhV8ObQUV+YcVIO8NtW6 zcK@2lfd>G$Bfez)Qd&6Xzwm=&eoX?Ilb!FS7eG!?1k_V4L%~`_J{|Wc@p=j(I7NU(~Oz|8z540C23}f5U2qi}~N! z0zFsiWl)KOYtb41jjV5I0Bnxuk0K6^*RULXJkPf3a$a1^_?dz=FpJ z(OTFcv3MX;HaVacvB&@A#n-$`2IePNV5UiSlR#a&x46IRSXa6?aQ*~ z2NOCF7dO}cdK5V@&~w;o!t}qY;hlsnIQ55&glh80-o`^dhi_1dETE4+e}dlfE2E4l zTTAf3U-;Tv=SQW!InHyHKkmSIe-{}3^p3?I^t81*S9<+%jl%DEQ6%^AGJFx#R~j|5 zyL>COH0p4&Vgzd6BJ;ny*#*Uk)GtmxDRA)G+h={iF1;@IqY(OR`k)2^^XyVO5G?hr zW1ph0A+qG=JYEmlt25C&ZrkVjd#~3by5Hf<4tQQGh2=gu-C>*QhSg{fCZVkuTt8}c z_D=p}A6$3S{M7MybGf^sva~0Kv~BN(X3;x0hZ_aa#|Fg zYel`i-u;1AdHPOEq85DQAvA44%!trwR< zaNEKvr<|FBOUlr&g%}~NMvCEcvoAV2zUMvZr<3isDyfPWDk5#aA#TV*;@!R`Y_Jeg zC*L8`S5+;z?l=)zIO%~-K6?s1W(`-LS~}%4Y;Ut0n$K!bmDpI=`WhDWcyEafZ&G{* zwJqX#JI#78I0T>Y5A;TN46HQ|NG0e#pe2UJyE@n(L}Bcy^ZZ6#m^V=M>4pLrdM!x zWn?H6`Rn~UMs9_k2Xy&S_wxm(knUcdRKKauuxSp-j)`?JRI>xZnEf0MC@Vj-bi zIn}~~Rw3YiHxt7QnmauBmIhNBkBHU1N{A&pv#=657x{hkmo>e{Rs&yaZs$W2g8j~- zL$GBN8F693Ac`XwA%;Q!uT&^CQYgkW}CjTVT(@8*vMn(CErD$puxzct34fKdlaGIJHs--J>;^!O-T4OttaU0s9h&P5aaAHn- z^|Z~NOwpX~2%sU;GPbmwVn!oO%dmRseO2zaWnhbr;&rwQWVe}hXsIHy$m-=5b2Hwi zVu!*KHsY_8j;?Kv=AzM57MMXSmWbLo#?e(0RCI%)UepZI454maDh#0(BA!9L85gl) zg^A-Olxit%7}ZHjS3#2jh@`xbGz5a5HP^h84SFDf%H~#4Yb>tp z5%5`2KyshRvev**&U$G#x4X)Nusa2RYCgi5pSTu9HwDFOhA~|H6fOhJTF9T5h-Q^S zK6try`zX}x()0I?aeIcPHhGc54!*ha&nW#`hVVNLvXFvfir1*Odi+D4%g~ePv~gOs z#|qS)+aw4^IV!W@G_2=*Jk-Q5tZtyp@3J5ak&E^WfRP>wdFHzI|x6FUGvJ-|w3*QRpq`q6X>%vii9ClIk9t<$e*uJ%yGVXo#rnYv!J zH7;ZRZXs%>BP}X!wAfRMInOX{2o8bY0YLp}Qwfym8pb0wbXa8Reob!kwOc&Ni|V0Y zP>(`I4@I6-idN;>E|_y9>X9lq^YK7|+97YBo90wP0z=!kj%Eq=H(E2PMjth~$?(>C z(hRw-Pj}T6miouam@qo+T|T)q*PzOjv8L<-8%=I0F2M4JBhqO_-#d~_Wdi4$M&1J3 zIuJ#R&}EL};%3r^xfX+V1jj}*dm@N9!=wxGz{$ehAb1$DcajRal6XBu9E^$HD#wT8 z8(KR%dZ`jFe06R&0bd%tC-v?1_Y%)-yyhkvV=r*@uQ#n?!f z`I9-uB`1zgA*1-t48?o*)dOgO`MvLa`Ii!d)87|acVXTUUkQkJoCdbFI#|0n!3)BJyD#U;r zy?r0JhwZm$O~8-o^0^`xr|BW}_-M|US!wUX<5syl&lBxKfA5uNwg05{quaM@{hwKr zRdOG&{WrX&lo)R%u`#E@y?T11ex9EHv|kl>vYIOURYW18T_z=W*pGO%MR=1{0eYH( z5Ox`6nYFgt`q&9!K(|TEaj(c;GH-+#MWMyUrvIJJFSvS_O4@E;2~JQS+LuTQkEVFU zN7~9Iw|+Y){Za1T{dg(;^LBz+ds|REv4i-{sJv48;_A`f8}_;MMew8j@1{eJxfY^` zC=;T_gI%xOs@?Yio)R>@>Xd2hZ6L)Fa%`tS*uWuXUO3S&PhU9m6k-G^le>Jh;zJrf z_9u%+4lo1*suNGX#Td!q=y*^~`muzMu=#v&rYrttSw$8c8=%yjBUX=x1&KoXDR%!t z`J0!m|Ai@Zb_;QHYe8i)z~G<^*HnUDk#E|At?G+C>4{>XF5J@tc{qGjI3egB98Q)P zighp_z+W|2TY>?rS9CcM-2q?k4<>ba%Qg^Fe?u6Y)=#2YkzvR;GMhD3ShT|~+FDEBC7T5PByGk96)2>X7qJ zKRD8@XBgsWZ^7Il{(X6%XhTsZ!NlA_c;hH>aHVGjQR-R(;jfm8G9G`^0^AnizRqI6 zXz$%t_f$FxY@b{OL?6C@p4-YpH^ChkLUj&&9-* zP|LocnOV1fz1@ejKrM(S=+Dv}FGR!)CGEOtGL2}w<4$qkk}pWYPNzTrd)4vH%8m>< zHX{->cC{Z>qMVuK%H;KAt0wahZ50n`Capa2Z}a>K4)&=K+A5<2uKa40b7ssRn*CXp zRi&^|!pD9fNliRZM>zBbY3GSr$*QX(Yu=9!rMj2ho$5bmjLOrv5)a=9Xj0m_$XE$o zvTnE<=rN?w7jy=itjF z9Z&u5%O){Op~;y|mAuPieSyRr-hO51Z~I+*(+)3avc48@L;H40U{aZL3On}Cx+8b8Na=ZrB+GumP5vP^5avITP79F@3X9-n7{HzlfT^e<<3<*1vsBq+xT- z(!oxVB_ci-1XY-=uOa{lRZ5iUwrDU~-e`7j3WS24Y7dw?egOD&^<<>Z=I^b(iLVu? zCxkd&-gN*#fG_{p_^S0Zt%Y3Tky6^mMG>kJ&N<;a5K{5Dd=*E|AA{~Z4)wfy zZx~JPW3FEWVa5+lligEcSz4R%#Aw{w`n}&j>FWL=4{s74oZq+8ggwD(_AQ_6Q*B(9 ziMxIl$du|Q^vTwb$yEFNf@Y+tMe&`Q1IRE#1h%W;bW4xZagK|JB+q;(F_h(N-y+T~ zVDHHG=NciK0FmE)I@@4YpQkxwmY#h|YEO93%rOaCv@c0K|GSU(-oVBUX~C39BYb(< zvm2_sKPIOk{=E}I>c2cLZ~KzT0+ZWVpcsvpL2Dc*-6#_Ps%r)Z{3ZHEV!Q_t2_vfG zH45|oyj~%7>Z|H*hGT81ycz5UC**2Lv)wnGMk4oZ(WOS7AtFJ`d$Ph$;>-(RWTFGk zzV~&qH5-zR(f*=)I@PLsH~|_O?mOE`LbFDW^6o!PG}kaA5knDi{dIR0BB62&r7d7W z8Av*CU}2=*DT?^4d&J@lH6K5crLD?%KEI~@KVI1KzInK zcgb#8F|~C#1Ud<*v|202Ayj=;91RUs{TAnr2&=^OD~(B*z&{<6XZJZPcawJ@lip?( zH_dEaNHE-8<&d}4!-CCu5c06U))API|-6Gu0o^s#usl2tF9;d^LgPlTb zuEfSO)es*aDobLjy+{2$h(+6g0b5$DW~E0@4dN>)`af{bF-wk z8*#t!6jZ*_RaHu1G(s6}eaiR$_6rJhj|ni|CH&fTjrrXR%@7nQPJl`QQmqx`#(|dg zt22Tu!?DPRRkIEBUb8DR{oWI{Lrp9G0N?&2@$f=m5y zQryjU;^i0TiSKlsSZDANH`Rpy9D~2?&(OB5q-*|>I8Ty7#H4~C?qduz*BRY}4U4$B zSzZTRubyL;)Vi`x)YX>=aoq2LwHK^Xyx}&r*oX16-Pmd94MOXJFgq%%iBR!zr*HZ$ z9VDX%xQ)~`nm zZfx{De*QA<^b15OAu(zC3wvG#5&m*lEzl*d>dm<1WBELu+TF)0i4clfU#!t{uYQFH zXkV0S)eANcZMT}Sr#u0^phQV8Zd&=53Fggs;TR zjF|6!0$*8Et)MkWGx?Ka2zCOqU2tZB>`<$|aAC`Yv(E>+%s+T@f3zz0&YAR&M$mn8 z^h=rZ(IaD61LDLE@ZBnto!k1{w;dV!%gwwcd7&zw7x~!~>oe=mwFo(9ModpD{QgN} zO=%Y|A~)mq12mxZlOZbV978b34lP-$Fy|5BVcznaiYNT-N0<2JxHFq>!7OxvAYn%2 zTN?m5^jy8j>8G}!Ph0VE@pAKX@=drFPB5fzx4c7WK2u8KG>3KJ2NL5nPkUM48to(l zV-nbv`IwpRa(_R8ARly=kTzH!f<38-2XB@p?Zh7wHbKDlYMe70%$W#9CA@c)UqXM3 zNpw@JEr+G`;0CTy-F{7Yiw{W`e$*0{aRt!Q9y2SiLa9a$cHhGVcR|*~aJ9ma! zM1Y=mvUi3BGO4>u$*n)+^)4>tN8Q5i42me!X@CAA?KkYVRPznJ23$DRTX(haI6hS! zqVE)9z5!9(0)$=EM9_P^i>?~?wsE~Pyh8m)wfDA?la82{x+;B;f6~XAN&UJ10@@Ug zy^}rMzFwZweUkS^e3IA^5LSCQZewM%o+FGPmgH`#W7(6rM7mgWu_`PrM(^|4DmXS= zt3EdTVBlHkt8lIK!O~M`LSSP(=O@95#Zr#$l{$!-wv(mlu+WqtI_mbb%#YUjuGTm- z%?Aismv4_WJ#@BLB%L+R0ywjUzw!m^I@%WAw)yKGNF@f!`{q>GUeekT`yr?_)O~&pPpn>TY3$u+wtuF`2KwGkyd`AAv{AujBeeYwx{9Ur zR--5AgAJJy{@(WpOzc81OV^>=rB3!<}@|$^cEduO&TZQUSSN+T$A-IIs z?vk*C#}B0JVZy77pLD|G#A2Rmjn;5tuOM}TI*WA9Cv;!LOLR0s`x;?#P+yfd_TMqf%b0*b0Z#smqRpAXHm?#Qhpyvxy%GN}E7)*tqy1%p7t6BDO`_tnf`0C9!#PotE2fK8~JmdnE3+x-oEG zys>50!8@@-@MP_~C+O8STsq4)NO{4UL)06HfQp*;#`sM^n17g)C*?S$4Xe&O^p0Wr z{#&}7;AMtifdmj8^Mds-YLUjaq=K;xOw(i-G8lg_?=V1?Bqrodeh?o>MDQKIf$*n1 z$Old>G43#p8d409mgkJNjF2vw^xav0_xhs!gfr{qKCZbS3m0@3xLqSoq7_erEhbJx zEExu*iFXb99)dr$44qB%*&g`W7G;r5Lpp6>4LkmCZ4x)e`#o%Ri z5QHB^nroWL|&g{-*V4kom*{X}8VPPZTltvSg6W@APA zN+-_2dh7A88$)!O8wZruf^r3uIGUqomZV*$^XWr1vU8LMbfmo}is3}pe7SMRnnn>6 zVq6H{(E0@wcSi$02%LZ{Ywy|UTnGJZh2O~?(yGJ*`ILJbvO2}krzc@45Q4OhkQejVX_C(lj0n7EN>Fp{$wy;-%nJVFT`x-DN>zk&sd zLWc!VV-PvQU_sFbatF4Hnyk)>x*3ZZ%dIYVLkH4AEkZR03I+NFYC}7~qrnQJ`ey2; zRTQ}^R4bBX^D~1kQogT$7}~X&nErf_X$5XBfBV+t?Oe%v38~UU=4j?`ZYBrsGWsRK zisG`ZR8^N2KH}dhW%<&{`lt)a%haH}O+%Rx65Q2-O}xC#L+l*Wko0*7cMiRQ*;<)- z@V=MUWNiI+Q`Mz6q3RS5AJgQ@jdPL)5CVtw=7Tx+mrzBUPd#@Z^(`gd<&UdM(~*Ed!2-s3OGwzOa63Qmz0OX4 z_kDHX$+ddSyTPbgX#eD8ch>Zq_INw+_sv)2j3fJ;`6bBJOr(ICIGLQiT%8Edoys*@ zysYbo%CEHVH+~^UXhvAj{`TiO8bl78PUd&bN@M-L zeu?ey-!C>}A?-7a?Qq{uH(QLm5S%^GIjKuB8yWH)O4N_}B%*Kh&ahwhNXo15KCRu* zU&CM0kQP*vj6OO!qB2b6_;hQy$M6Y5jNq$Xs%z`L5bOhY(AeSRdOH0r=3qDI8sQ;i z5A@cV4C)GRHV)N1SyskCH*#CF`z$jObY)UZY-@b}X$1rr!p$mYd@$wT5}Ez+u$V~1 z+=jbKuLFS`nrVXSiyXBotb-QU^ZA%F3}H;Q>I&2i?TGgnXn1R)1I5zkbWKPa&UCDD z4Li{Tu0>rAnOox{fGsq^jSg%!W^9LqUlZ~qS`PGB6Ci*;>Lcexne6kt7N`n~TZO*H zaJ%ri#!Ts@N<(PwwkzuZ=fjnBYm^0jU?q9qi}GW4!4Y6DbC3h=(X0RC41X0d4gD++ za0m(_Tcx!E+6?!FUov38a;gw=bt~bJcO6*1Irxm{sY%D@!?#8T-W~3DuVXn_?7v1}q zkR}VgATi!AUeymryZQ!8!gR#2KCT~A;0q{qpOz&tRhE)Z)R5++A99ggHmhICkh}(q zM-KRr>SMdKVfe}#`Zb`FoOGR9I8kvK=#Ut^$#lx?1@HIUr(Z=~HlQd`Vw2S?*H=`S zimZn;QF>YqZX^Wk7)cx$x2AB7BOGjY4C@P(3(g&RcZ$AL=}-PdwLR>0O7un4pB4m) zXPlPIkV8gH;BJY7q)t)~WM@$SII1Dhs3G%HU5HDSl1q)FQT0vZ6ahft=M=9s?E+Q! z;9Gb%b$qw)Fd4GovT*O+jvq2$IiEy@hazaDe8>#>?^gU@^U^t^nDZ5+qO6KVkUbEu z5RgL$deu!rYt=nPJ!N%h1;YfkIeI~#d$rd1OxkKC=BYUm?n0q^ZFs#xLMeMo zd$)VFd+FDF)}oI;AEV!*-y%QI3dw+qw|5=Rp&qgy#WJlv=V6}*L3-c^fxRV>`e3)xG#wh85ZBg9~d{ba2%Pp&D&o>9de-Bq91<0oA2EAjpF2-@>2b*+F!tEvZ}McmJzuj)ipy+!Ep&KGTiN}eO`Vafe+y->`VTgU9nIT9`0bk8O zFNkwTF`2r|n>K|oS&Yp;|NhdJEi|lEdp9q?l%QSdb6RLCG{_leX8t(^RBh(60H@WL z)17@wpI`V*?z*&lMP31-nk5oZdQ-H}WeDrvmCDS8f>g2mQ*4Z9rgCo=r*vIGwA z7ni)wDvw(4a$u41nGEY)7fyY&mztet_U_0$kMp_EYYeW23;&S$_)2`mRuR59=OE&- z^LHQ9GFfz)bU;5Wt6uzKbA^0?>T`Lx__VGN18?ZRH8W=j+V~pm0P1*{Xgea|M>zr= zugS;=KW^@n=8_0J-ryS<#*owu#%h}lRn~3H%%52AdvdwA0|cJcPd;^p1$0sdHB9@? zN@Cmhv0fz3i`(YSHj6ZGI4FgfxZ>AUF1>{0J|fzue#dl(i;Agx$MhaNl{fc+tDcHI z5Xm`^}8?@|X>Sj>{4*SF)_q zmZ_5I37)vgBKLBRzr*n_Qhx^_Lhd}2?{B=X$2xjAtXpd`42w%*(k^e}dltX5<%jdg zGIR(9cf429nf+W3&)qCh^XKqLSZl5cb^qHgTltU%>#|W}FsR>y+B#_Ps{K7YYz!tm zuIr7@IST)S&^1Dkc;5CfThBD4g^*8+U*~C)T~N`T)l(Vpx()X0J8RsXPwv=Bt?(9& zL`RasL^_ARrb?U^Ixg@CG}A2zHpn$9#*zV`b2z-%1x?p~ka5jDH9==pvq z*VCE(&NemXkP2eb+ehU_qibvUF;ug)H4k?>Em|{b(NX)yM=gRnxP6|;K*tb|3b{^! zB^NPQ)7;rFW&(ZnQ`vO@|4~F|*rC-(MHK5cZRXGVeP?_iRTSfhmVIs4gXBjJ z5rZ5K_6$l`#x5uoXQ3};);h}>XzwjxIXJ#V4*zmea*8&Xxr?=19Iq(NzSqQK!NMU+ zDzKGFF#>~P)~{}^p;&6Pjd7M?D&do)4m(&!4UpyCwY=iBP7?=b6I;mJi&`5uDSV2_ zxV%ceccPH3)ma`n^!C|=X!WtFE}v8dxz!EXhmF{cb<&%+>qpCM72u5A@#&9z>libT z23=XOmpC&D?8TU*iraThE&SiUN2rH*1ZxzNV&i~R>1R;Z4{#eaE@Sn_+=N%Uw#rkv zQdwuhC!Lv-??>=RERHj(#*W(b-9ZaGC}S|hEDFWc!Qo7LC2dtz`22YmW8OC%9Vwd3 zMDNHxk#1e--j4xxXj(tK)0`Zgg{?+EdUuF++1gA@%ND5r9q$r3E+8G_ID{y)(Jf_O zzt|9@qiq>Gq8Z85E1?>hhkfFG**V)yNjB19J>_$GX1j+1y1U+5iH%n-e1aB1KL_CkXxd{{FW2G}9 zTyfyONxNmqXD=k`#XR7eTu_jsvDdZ`P#)-miiBYBTV|{|Y?KoG-_Mp<{>J+gau_60 zZHgBiAFe?;-1vp`$WW{&fuT2%zd9$*L9Uvb*+T>loxR_*+PVt&i0ug9H9lsQgHXSe z>-Q%H?$r{V;5;20cJ4Z{4u;-MU0Z~^KlD@qBxClNSmbCQSjfw{C%(66dx}=Oi#WjE zf&S=L?sm&%PbDqtRN=Ooe!wVvl!iI7(=@Q&)~8d(ohFADQ!6`Tzt;e^J zVV%<~Le*XlHT>f1lSja z|Ea|<&hhWw{kRU}jYLEwCK8UCR^ZCw2kRWa#-TeYBPLResv2@mw;U(-GoS%_8YI-% z$s=^p(20f^`!J@ctG|RRonb)fmkHVvPA;<6B zs})yY=iLO{Y2mOp5`Z3p;oVdyEhYt>PSw{UFFM}GP)4_Ey3 zGgN^#kkY1)^`*{h(Bwwq3(RWbBZ774UYyN5`nAK<^zBYmaxK4Sddu@GJd4zU7+r*> z>j$PWbiC%(tm}3j+K1OPUx*Z1&8UeO8nUxad|$x}2_nYZtSuwPbMt#o z!8?Sw$s0&a8@~}U>IB8741AIEowGz^v4@?4CYH&Gnf+1Up;3;RnDbTD6H9|q`i7ke z-l0`8h9_*X))U7n`-L%}L|Sva7HG9SW_U5;g_NCgSL|_N_jm;lV@k#XonbUzNCIU9 zu~_m8*+i%y<{DNDej$aRrqHGW z>(n7tC1~WGk|7^tsMFK89#7%C+U^q>?Ne2Te=uI8a?36jr&2k!xr!GooAPi~_~RHL zS83Foo!oLj@nE*&m6uawgg^Yw&pn6`@#0je1Ld4NX33#hB&M>DTq@SHgK=zj-9pN9 zCXjDDXHVnV2jYLuxZot@X3XLWefMhvMPB_VaXry=(;>?}=Y1Nl@uQ?sg1w#lz(A!g z0R<9$qbj)26=NdvdthTuzK)$}H7&H9mYps`P4-6;*jmouq#n7VKss&tB3e*&DRSbb zt_oyLbs%Twv1Cxw-mxT1sW=JR&NiI-ASj~XD(ggW^#*YPB-vBo?YmcPDT@ZXH=-)F zy)bv_RHeUP&NO>++aj_bF%2wj6C{FG5Q;O^qpDr}Jn?p7S39BT18^m78nMJYS;r zQ^8wQd}^^X^PG4wa%SIlH~}$5CV&b^C0oDiki-Eaz<@lSGSy&>qLLn6*XfmlXG@;s z^G{m{g9y|O=BhmEShmEd)P?OmXQ1Hw3(0Vk=A9$ype8Ij!X>78zRDs)G<1~TmdP+% z(`yz22w!T5U4mWZgaUgkE~v&o|CYUsv4y%$Fl`Kbt^YJ})!_boQS|GN`Oh-YTu$nSv)!PIvM<}B zIg=IMNoI{;Ypx&fv9*FZm1{Ffh&;Wx&S`&na_JY!c4(Lnc?&Do=1d@zTX$$=t5pvn z)HH9DHCx7!7}n_0LO5zvyKq9J{t$~1TP77ye>46;_1Su4f%cUZ#;H@c!Kpb~$$DvMwz*$sh9v77?>Hi-guoj_roxJ& zk`F=r*Sw*P_MR0cE6L-6rUAPsFU+5WEbJ$x(o+;e?aabgr1gBd<~_ERT|^C$c%H?H z#zTzj7W$e&qr+W>pwGMag?Iva+x?{1=tq`i-MI=jz2{x`76J7So_9mST`%i_taPOX(I zlyIrXDBh@e;3|CYG_BdtbS2!QaNr*FDL?u~#o34Wi3Y;j4DLajpw* z^)=t(#K@0qWTMf6)oL_IHo`9Zpa*6#IXsL>+g%uLp8mNX12sOJvCM#=I6)_4vQg^^ zQu#qcRY5X$EUBgCHS1b1`o}0#NjKDAt@e9iwX$|*?o=x<;eHpRoS1$*V_}q&W3&Ko zLgO7P{b3*sZYD6W7_<(F)Jv;}nL!{tGR9jhl9#C*4ZJN6wL3+xqlseW}~g z@Eu`{R=LyAA8H>l2#{BhOY;Qp5v+{ac22sv5r_IN(`&@X3 zgO^D81d)C4yoXE(Na}lAi#n7f1$gIh z+{09hF^g4t%wIwpR7x(1(jdOW+!-Qt5tz?P_`Z*Q9?Aieh#ogC(z4GZtV;qnD$teq zyX19_E0y0a2WTAQ5b%f+CIQ|4@oY;Z#+G-H3Jo1Mlnl8mTILUaMC?8#e82ulXG&YI zN=Pm|bZn`Rd=c3t2hw36v?InNWY@QwwVQ85a3+&A36ks7<#Z=;<=~0Jvk>%rl8GiL z83Al=Q4DQ!^!?BWx=b@iDCGp5b(%S_nmN}^C}4-c8zk$gF;DN?kKlv1br23QY6T|< z-8R$g8XggGupO_?{!x(}9XvFQ2q+SnT1gB0)t8|Yl?LF)v_`r@eu{**#$ST)==M!I zc)RBld9{jg5A_ss)-TQvM%-(rR*ugtOQHGx*bw=tr|`r@T*Rc&F~H6I*F4j{!DV`j ztUhyG5=i1Jkpy~34sr*XKl#1zUhMOKBn&mAn`%>ilM|S_Dq;KZ_L{i!_igZj2YKJ{ z*ZDEm`Vc|c9Lk!6s}Xcw1yxYu2mGJVKH1`>`B{f0=-=S$t|ac+;2xs=l|e;aNCokX zu2>~VDhOivhP;fvV~mW+jb;b$K-|%xP8QAsfBHdU>+hW^uj@Uv7?K8MHK#w^*n0*3 z&Q2LmVG+m3z(5MyQ}y5~lk>=W`p>B*-DX4jEG){L~nSnNAHIX3Z@(jB(@}r{qFTw14R9c z$J=rz)OBjUMz(mF)C^yWVCeNSsO(ZYQ>edy^%+=_MG~K$pD_@ruw@QA&ZXGg3Q%dL zm^f3u(ps`oV#eXT&+@|i)CX*c1c@hL^t!QuPMnGLh~4T5Cg|xIhsk8)JH92f!<|tx z82=bj7G>g7R;ktAX><(Hz@lBGQp8&+5T1`*w!-}-bCqac3&xwyckO`K#Ig4(Rb6oi zhaX`w=eMP{9Og1-9-%#3qqN3{OMq1+@K0nfp!OSn*Nxe2V2iSJpSw~HhT=tA2`9A# zNni4ut6bE=X}c2n%H@QLL=Ze8c4P)DTTywZ`>3tpLtS~}T3Mb=k!J6R*(am*C_nz9 z=QG+HJq-AKEa1y>C>FC9mUG_rP4bfWjwXxDJ_;{P3odi&kfz(simg;t;c`Q$s|}IK zAiR?bzq%DCtcM^i%Fw}$m%xy$lU9%xBnZ1Ky(}V2bP8WC7F8w_EAEL6(&{ZW=li+l z_T-iGbchXrjyZ;Qiia4H^5LbNz|#Jx*Pp!}wce)glXMB?iNkek^W#0qgfVA3x=6Q! zWU$Rf2zPw=#zC|hOR(ODFSTT?*!UXxUrP$fj_|TaTy3}Pla{?3wjZpBET>eKKrk%5 zYT|N&6IPs;H9hX~suPs8m(uz@KC&dgqs3~n5k=P9m5MlWnid0sn5xBUW+Ke^(N+o? z`u19W<{9mXg_-Jg^~A8k`Ru?H-#5qiwoSdg2qx_npgY1b4Ya397mV>uw#uiG4S_l# z63*C4{(o1J!*;Dtc;(StJOBAzFlI81xllmj}}P90WDI4-=nE zBt|44+5`urCCL*a#c>gk`nE>=bSI$gg!}*dhY7p2@)Pd_9wt72QCVI*QC}r0i2&oB zEJXIWI7}8m4n@s`Ob(U_5euHTo^cyl59#jR1n#9BeF%l3UdG9^@Q~%jJ7`Z3d3WBz z8&2*w_xPXMs}exrX79@a1tqSDf(i_DV+^N9E~w<36#mFrb|~}26phlqKMufmj$iyh zATpK^YM^m0wBQUEd7HyGCtd|>%tU9Ei@gyQl}yD~{kGKisiQxg&qe1ke%Te#iL~8J zD%nH2w~YM$Dlt5)%Z#QDQ*nM11T8;u&`RB^WFFNn)i!b-bg5MRzN~S{@DQ*^=#Xuk zy9zj(!ubYO4sHV1p&w9Q{J3PdpYBvbm#?ul;_{b|lOy{e!mi7NRujyBefKNiYtHt3 z8JqX`!h372+gWj;^GkYVHTkqZ<^Rc0eqqNjLnNS2*`Q3OM8M{@+JiMw-jC4x zeH`Gm>yG(cin_0{p6>4RE_Zq3JRk4Mu4bH%)8jt;j16X$#sxkDskH3a`Un1&OUtuE)K(=z|$Xrm}m^Ja5Z(JHjaRLlwg!* zf=+H(%V==tfehk$J*IUAc$qd{Gq&6=jgn&T^REtN`E>;P zZ>sy{ciL0Fo;!#fER*mP{ZyWwKvv;ex!2oyn<43s3ffgG4J%Z3!{I4#(@R2$8L=5| zzG%2``otk@?>&E+E@$(3aNbv|%Pt=^8;Nbtv6H*9F=v*}9n3as&i>Q2?p^>E2~&QA z!BsD{dWD%xep|Kl1|Iu;?e{A~>( z6g1&-z&3rLZ!?-4=1!ngo4L~b+&nx~^ny)mX1RC89!~E^0hCoMHQS#tiEQ9LKD}Iz z&x_hFy95OX^v>Vz{?fW81^Bu zR180TrZ@WoFx#`2Zu5XJj2;Fg;|JfY8{hE)A?l{KM1{X%rrIYniFbKfe=h|a>QZpu zKW@z!hV^aLs@EsGU-$7!X<%7}x|Dw+PAE;(?bfA67Dh6+WeY8vlr~*Pcpz-natx~9 z83vt>MUs|77||G!6>+U~GJHCXCDrWy!-i)LIj{Br)>mv#59b{1*upWhmc)IuIU|zy z)|U0&3LeW_G9Fpg+* zdAYLq>lxUzwa>h@HCCCC>{BW*?>S0DTz)&$v{(D9I|q1ex(B<=1|6k_JZ>;bDjn}- zHTj4DcA31@ThFCE5QQ;9k^xdysaIsL(OqPV(}mOH)BDq}SpWW!TV1w4bp|fPb~TW6 zl3n(g%ZfYV{X!&Csegg;P~y=w7NE589O9Gg`LRi$BIRSD9+U(>Y@A})%CI(#b2~uN zN0uxy1h>}@n|jka=l|jfyAhWN!&8wsqAA=C5D$S5$0agXQ4NIU=Fd=9_E+*OoNI@A zw0^^Y4837Ar=^fABr$?y3wn0Px~wL}=m;*>!ziTyFDYtvajz#6*QzL3?e1eza#&cUM7q&GGKk964&ImwTQBrRP zo)^>{z@+?N|I6?5!TRixFne<}5#}yngB92&c*z!9oSdy9tvdy>{tEVEk;3ds=U|m- zxlX}$$hF1zk2mR3`uuj;%{(-jUvmWa>A{V^r;2xm7elexE>>dW1<5dNWWLbzP9-m5 z6(!8BJ%hWZQC0%@6QOH_;(NP>A0uFZR>UA49`UaY3l*gXk%GAU`it*|+h8H8S;3X( zx&ujbau#Z1^*oJf%!X) z*vS8IZSLnpE)@iU-QIw4$`0@yaV+URGr9>(eW;#lDk~>=fM+TOg5LV za~qFra6az1FNT7%3(Za2qQtl7G<-Avb!qx6Ypd0LIUXfkRfUiF>~*>%CN{t8UHcG$ zGf{i%@Pocz6|`Uz!*WFLAipbnCKj=kn9ykVnf##~i94!`#7}8y*IqeraB5jl`^jdsZY8uZb5SLawHHXX$3e`-uxqg)>Ff0nx(xOCaY z?KrM+EQqLq8pn)ewc&MpLW$f5DH)df^q-9h9a%KwAZj|&&G))Yza{awD}uey6`@v& z+_<(y+S$Ah5h>R zk`g}L_ZwbqmnAqlaVG|hoNjC@L7j~zW0wvbXiG7{4ntahSr>ZQ3M5EbB;kj3Wup$s zCz5azD>Mpna1mhW{+bceo9~m92x@Np^80#$OH#|qEAlLSK=nobmC?<8!jJ)K_4jrQ z$G6givso{Ufg=GtlOMSW?A`84+|{|}W&@)vG#D>ikUbBD$1DXJ6^lFG6uml*e|oye z(MaObOwEq7(9P2^(M9NOFG}6Stzp_Z6=}^8oK)VE$=ZF`bExym2!?KqT-uM@UvOMB zwi|eF+=d?ThD%Dsv}@~NM3;33RP4ov@aI(IH#kH#B-{hhKbf_4jG9|bSJzUZehHr8 z`>j|s=FIOsz;PYyryHl9%aqNa)J^7%&A{?hHg~U8Cc$=1!F~-P&b%eI_X=7njIy5~d$@P>p6Z z_kzn}mT46^S92xR{ zJ#zi|#gb@{_d7`AZ820nT%eMQX5VjY-r|_p!J`6rigR|DBI>ZmKbtPp?Qu9B!5=7y z4VfsM3kAo(<`JuqE1L<`j8qN2nf)P^NH;KAOLmQ*6pWWIS2Td2NNElgNocj_8v+5* zp-XC|&QG9B`?yG~Xk9yIHQu9)zMxkc7xb9-^+%FYk5Ih7OvF{Foy#F*8Z?CU4ZKM> z7`F*1gGG=xrwdF~gYrEPTj`K-D3r2TRk5!469D}pM!^`vQ8#zq9^&QtETZ$-%}0-A z4Mzb!+t7;BOJa~wE%z2;8(uBWMRkk_6C7xoVP8?1_N!>;QL?sBHNH$M5?w&YYz|BE zVP_6o{VZHPY98S$sg0jfzf(V-dtotp|g3bd8fnnY!&hqZ4#Yh=Pu?=DAKIzkT9x^ zhkXf`ZICNn*jvDoxXP(*`S`OE)<-LMwA<@pfIsLX13Am?^bYT-`W-NA{=2IGopT&e z1&>=sUfV{lL>qCxF^XL+2g@6QwEgkKYdXFBHBhw5AIcq?5ULWo5Nen^;C-Tw%HURp z)nPdg_Hm-&pxtaE(q!7T6*{!CnDO${F(Uc<?6U*Qf1_6 zE-%y*s?*l_YMG|QRBkx^;q}_!CAi4Ar6F=jiZ<+C%fiN9e>tE6O1Na)#Idxrg$?X; z(D9x+bd=qzITV<$=eq8JI=BRPBD#ybCHo+Q08};hwrqGx7bI~dv4EKNU?wwWV47SXhXW1e3nLv#KA%Tr6CL)6&^%33c|%AzZw6iQ&Kn0Nc4Ezf<9Cb zrrJyBQr2FPuiknA@S5&j^0n(&6*5>-`u6Iid{ATFv+JsXk(8daVDo+Hn+m_$f-}76 zo{_gO@9C3P1#rq6l%?#;r}S~_H`)R^6^;h@Y_2Ev;Gzjq{w#O7jZR+m^M7o$zNN^c z@-VLAzNVtv&_6YlW4#u{yR`W>3+?khJh(r;Lp5|Ez|t%M9O`FiZbe<2K?Y1X!9B+5 zq*moz96mwLZ4P3uMM2RYL5>^9b20mlUyyxVYwlb9_cu1ClnheZd#uav>i~tvEtkq5 zkB$dK9P~318PRoJ$%yiY8~N737tIT8SA4-3TOnD|^N$FRPgI@I8gWOrFS0%LFZ?}% z5$VXWIL=dm1Ba7xXuHucK90Og`G{>5bYR>yIV|z65WIVTDC-bI9fg2+y8L^{AFrbU ztPh;ip(zq0n{(%~EqW|%h$u5YPO3I+K8DzW4ENTpuo;dnqPj6fb7*SE9kr^z|7aj- z*rKG;)tohvSj>%l-^|JwEW<`H#4|5W$b|RTiFPHB$#T6P&Sr%hZBt~LQ8vtjlQUN< zmkXv+{8rTZlPr&KJyhpoy+-_)vw<0Ego=>N-K~0Y@CuRERLgJ1igvn$>8^b)Y~-)U zAb3UqY2kLQo;8gf0wbeZ z;hpDNY!Z23aJJekevwAUxGWgTOP-N*FBSlX1nx*IW;N{<87$NP53`(%_EO2MKno~# zRBJ0)%Gj%P;A~Av(Td1sN_EKik1F$~fa{a?Wf49npsnk!dTp@ELwDE`F_6K#vCw-z z@AqMbc*$KCDh=Y`i{!Nv0gOlhC7?C`pIWsvp{LU77MGm}6n#>3uB@0YdQ`nO5Iln0 z8dZV8Y0d_ITwp!n&f}+IX^OT2>q-rwR3KoV;Y?bY`>Q1B7afBwS%`9$Bg}(yd~VXO zzCBLo;9WwVxUU2P6c{z>U3o6s3HffMdXm`VBpyA_6U#r zA99iR$Q?p`c9;_eh6ds#7JaD^pVJF#?9jdv_@$f?$3tRc&P`gkkNPwGnx z&p@5<8k#_Xow;&?GdSO2@{f4fT4@k5#j4Iyn-}FhEPkE0#e%EjqvK{W&m^~ii{k0W zB(yf34#Fj;wp}YioN+{*G$7}d8jqrOnJ$Yp6FJLp;xclrv{{6injE*bxjLAfYuqp< ztr$0Vvnw;67B`zNtn68G#qKC`*lvXe3w)uER`5D!VoE4`}e@kuq zLl?i2Pme#NCVb?3UM0fTOpQ!|dbv{h%y%m)sd9l5pHhn7X|{Av*Z>E1@zAf{?}iF8 zk9+}T0O3fPNMu*^kH+6Yb|QQ)ESdMwL@0vfx*=|^$?EI42YE}Wo`wF3BvhHikOJ9?Z9+|6&Ff#f-rlt5i9!B@ zHa-pDf3QKo!JB;Do(4K!QF{nrKC+vJg|CWeGdBhAXWsPMa-5|`^c|gwh?H)}JlCh| z0z~DzY@db$4y5&97Pi{1gZ_CJ6{=OOlJ}{`lR>t_LU_8u`sk0j3fwkPvhlv>MDaislO{hyu#PYoukw-Q-mb=|WFV zd=+$y7I0*+F$2QCDod$`93_X2A55nQ-qNMhvV}`izUZMLO29wkXHwMBV-M$h zJIyrVx-NoIEXf4;`!2L2(S?>4p9aE4Mn;C6dzH?XVBk1v(htsClEUO zZEwNsu&MLrNCnK#GI<9Zj-9a|5NB z=NtUEL{9fYIc-7fRQevDGG=q|2zwaX82Z=}#XT8((igNuU&Sj><9+_D`>K2AGydd& zm7hGx{9kN0>DXNzP;ttz4KFR<%82XMu!4XM3JpOBM|^rLD&;i&PXH z)+~EU$GfaDgMWJ22duv@NmcR+M6%YDU+=;fWdhOW5v^VhHlbo}#k7N=vmzTJS|VEc zVUAfIc1xsoCPO=*diQd z`d^3}*wk!V3~pKFyRQ4cKYa9BBnGvj{(#*t`Cgr!aX*W-U9#9bSgWy~zgD(kRqkfN zRs-a7cF3I;oMqLoG;6J1c>aDW+%eiv?1OsY%wz6JM=okcyW2$vu}|SYDXr&l{ghh> z$|p(K&EcrbtW;pCZ%jy~k)7YKzA?9Mn#&O9S)MPPQX`5;J`#cDT#a}cx}aWKEQ+vb%>`4QLs(HAM}Hc^U13uZCif?@>(BRY za4j$*XB$4s9-fNIGEc2@S|xy>kzfNF5=JnV@@G~~cE`XCA zfJ>g;M65l~fsJiX0NqnG2+tf_%#ishgrCv5MfmElBZB(2gJTHNMBllL-3TgxZ9?iO zsg8;9TZ!hYv3fWv{-Ke>Dg1WCa3yQoVdVRCIj6FLgrJ{r`k5^2m@v8$8je;npeN*@DG31&lMScHp3Nb6qq=uIq=KD`R!1QRgPs?t`k9Ut~1M9-!r|T8@HJ^ zq48U~{Ze2(`u=;Kz?{Ae>&o8VDlP)HH;>Zu>y^@yo{lL<1w%1o6FKK3CHCM6nxx)G zR|KKn!PZ3?@28{FUGf|k^U10s`}EKVVo`ibj=T$Z^N2-;T#}WE*DN7IHK02q6pWrV zk>WJ-I4N2&jLmsPr2=wW!?-~Alnpn+CLemSxy z>g9cQxQH^r)+%vBz}(p9J{jI-AakDe$PpgMN!qVu zc$h1VZd@UUg;!JuaqLopTd^xUvQ|lMKtIzuZ+Eo}QodE?w#2U=1soQI09Rz_{=(J0 zKXd)9><;_Z_@PdNSfc&mW*NtQhB6t^ncOWlj<22})(po7!W%By{p@%41stLjL&lx1BT_YU-fgg(mDS*e<+}c)B&GLC#^} znT91Afc9|&16?9-lK?LuQ1d5$!BD{(9VuK;oN!?h%ZlkY(BA{ooB&q>sVNRF_sB>Z z`nd6P*6x1fobQ_jy`~fH$?P|rVI4o8oF}G!N!Q<*F-0Rz`!8P8nW>pkguVf4!;{$g z730N|%P}|g^^%+B%j6dBCGyVyx^1VV%ZJ8deL;64EuEpb#_^5F?158+1uH8tICNnIo|k3lT>}VyL^=**qB4v zG07iAHEd?DoPiZNHuw7YHMhNY$3-_G?!K0ysykVyKrtab$yAHx)|>3ut^@r@*v-Iy z>?mCXyS0A-6jCQA3-cIfU z?y$!FRFYN&O$orP{qXF<%yXk-T38x0?XKZ*+!hZ8*?+Xr@ml1YKhxlZYI*K7VS32kJ|X0 zX}z$Ita_SnQ3`a9k~f*>6DiTLe;D4b^ZyeV6kz6G?`ms!x1Pnd%S-~?tfqY#_=A@p zJi}M!JrQe6lVuM7go`3DJ*Z`hyk=4Z{ekuA?@4tbr*6DyC9e5yENQ3dpq z<$p4x=nb)_otMV^<&zp~?^CSlEgE6ek=e;`Q7$hcBBJzzanR~v=7(SQTcB2(V z=VhZFuhUtVm+bS0?acZMgD(}J%cfWGsOg1qRVws?0js}h$gMG{E6sCP!hw55+kOUkD&Z^tkDcgHKPWx8psC@>XtOt>~8 z>)=noMU*nsHTTc%#qCl+*o>`(oP+`HR_p{{?0)}rb5H!T^CK}0X=op)98!CVdiU0! znmhXf<3SYWsu6{UH7E0%?3fzG-9e z((>y3689mxKC(XAIl>ueP1hCAE276eer#%La%<*UL-Q&8`eR=4vj1p!6)@4Y@m6ps z?v-T+bduU@dUDQJt@z%Yy4kxfP+VTrbFYO?B{5oG>`&2G+^08#{ayH5 zU*^;LA+sI(n6w5=Us_u|K^wOugudY64W_IIN__nzD{Q@A@1zIh-YPhI&3ni?_h^Wc znLOSHKRtJygu*ES6O?E}l@R<4et*w>Uq6ka8bTv|!Zz8mf zIY7yZDQP^)_6Pfw*4Lcg+r$!Z`-9M*7tLaV6-j7k0tbzFbFM z$QF!?wC=ftCHU4b1=t=ht~Cbn+FEYbwtsbhbbWQ)!GFa+%G>DKd*j?bZBaJT!Y4v+ zUOeo%{HH&Pns3ug)tD!=HI3C*mI#Bi`AKd0)ZEShpcCj!ksOg6kv{I(dr=!kYsc>& z>H9_f;8~0)Ix+Y-fATQg#12RpX6D(YqV&vttdy{?@gQ;LxR)9B<#Xn__sUTdRue|V zw1nBo5#yep^*q(~*cP<+MSs1Ya2}?1ejs0`^97=>FgV*c{4KW4oZ*NRw)#m!`W|*g zissj6uu0Oy(hboXYmAKDjkWSFHj}(Jv|69UlLS1jH<`1J=CTqs4=Tsbeq^oG90V?P)90Ojp5nlo zXb132^pZW&e*df*T0uXxv^7m0Kka494K64{ZYE;M^;%EJS*O==kiJC9{Cl^vof`X2 zwWV}?+G}&9-~zoW!29Xq^KcTNG`84>=7#QBkXRQko#p<@yw>t?Y;tkfvYR$5%~Sxz z@55yF!gYLN^p$AtdS5@d%h1ksvpX36u?s9LF?458%t@WOzf0Hd*T1dXR&7Dke%G4b zJhgaetn=OC^zl75S3~9Jq;X($dKNApXo`Gz-L+nS`gZr6toEPGlrT-!5&RsdkDy4z zSz3M_YZ(_Cp6oxc3Dv^pTF(9G7-mSnmvU{;`}Q9n<=O$3O#qV+Pe$=mG?Qe{T^*nl z{$&!9gbANaFq4u+5E#2_{v)F>&&<~oO`wN4RM%IE(skQU@AHrVX+YH8tFA;gPFGzo zrnQTm&|#7NJ!8HR@w>;@5FmhYdDXNb!U_ngpKxhP@?<<~N1ticUPPS5-3Q&5o=J7@ zxHgO`nngRsU$}1lB#0HD#?aYhumFOslGrX&6Cc|qpEq4P&u*tW;9>u5|N9&O!2(v$&K#E}*qT(0761 zXL2!;+u(%`hy1YV9ap+QR&nPp2w6rXdv$35|K}jSTrk9-eG@c3O!(uu)1(2?I;ubu z2NoAzGk!Jnxw_MXd`+h}l)m#otJi+=QPOJR(>&(~&N{Nm`g>)rlvQg{;%UwjKb#Bh452Dey=t+vmv>H*!!UI!*NA-()9YN9*o1^Q11)xH(?x@_3vlSV+ zf;N-*>|^d;!n;#51Cp)XQC7e;3Z-w`-R&?wHi`Xmy0J$GWvFDAJKAZ4*Z6Ent?dNBld~<{pu}etIwzlRi)i=Tizj*yO+bJ&V6lSob8ZX zl2Zc3&~y9`q7Rnv8u-NL3n!(KHMUdB=*a76OXILS%O^Oyk|H=mlC@21f9w41Hrcq& zQF|YXdCcz8_~kw2dU8BVe-UX1IZpa+CrkjkGI>`k!O<$B?PcPOx5cQAY#|UdJkYD^ z9J-17Yl7+ME#HlZ>GJ-kTMpAj4C>sFkrx{3+*GG>4*aot3izIhUaj^?yBkp*O}}t~ zUY$k1#80yQ_s-*J4ZPB*OZQ1IAXQLXdR+0#32ZGHKOMC?;{nPIR^4=S``=%J zaiVobeadcWaMzjweYtMi#d&nh>R{PGFR1f|l7}j|<)NV7puZp1T;6isU~fYKRWQv_ z2>-gGyB_J+gajK~C4P0YSVc-e@@B8&onTgv_r~JExC*zhI)?wZ`v`cHbKx$LLrD0} z5E<0-AV+|VT0cdU)D7(%<@12)31pK^2Vfa6uAFj0Ml`a(JPLU*-4_2faaG>`>HlF2 z`T;JM#wTP?@Hs8I-v*wzk~qADy#C9X0S5cT{+*)sWePHa314N zOi!+AuwN$Z7C0~L68cC?08gX|Z5;aFDsc7E?fx5=>KJhPYJR2h8i8GZb{YpMIL&8H z9gi_OMG=HqVxL5+Qw1Xw*HrhM1^S*IG6c~4V(u%xVh``AaSVLxG`V~|pqNW0X@bgG zF7%GR(ef_3TZkO2S>l{)C*%{ADJ{ZF-)sfGM68+a*24F@p57pqjL%_AJKPLRHnKdo zFJn$FERIA2*GDB1HQ-%|INY?DUn*=S7NcSmKW_drf4lUDY)zC_on@d&w}@qXy``Ft z`Vw;L@jt!%qEa>4uw{5j!0jWM>IuIt_s611sBVH7*mF6Yg^Ix!*+4zXZl`q}`i*Xm z(q<$=*UhaO#s?Ko5Or>OYP7peB42K;R|$U-?g>Rn zBd$fdS6F#Mk#4Q(Ozt?|T2iqtximT?()sW8Fw6!9CIQ)6cTEL6{kp$R-$;kq zyeWl9{~cwcugUj45GTkBjqqvL5UnGU4xxLS7CZYv9e+J}0+P}?_XAc#GmhLz$zF_% z?^+i~X%~G%{1Da(*)Wo5t{Pd6kBmd}s0)=~zBRq98Y6k@uA-J&6F}k9ZBK*$kOq3l|s+lP)vEv=~*HtPQ;^@E=q^zp(*;Yg~X6q4J1D1 zUGr2lJnK0TqEejV@}N@vgWW+ZgVMXXK%tdxhH)qXsPWSceeaUmET5n_(AFOKPY8IF zLZX3xQbhY|-(s1^OIyp?BzUFbfkL!E*TozpAd_e5eNMW;=~c-$)psL{Rwq=6kflX2 zQr2SStL8xljz}gc1=$k@#1xih}v&K&tyXSa|)hgrRl|!AF z_-H-{m>+Pp7{7#PRV&(4`UYDD#6sDajT-gK>6E(_O_AasS@Fr;>bUR%V-@|*kog|^ zQb`fFgo4h_MO}aCBMM(2&-X*|jRxHWKX12%M|QtLc1iHd-o^1uAzkcce1$C!3mLuZyEvoE8syY75aH-!Y@Ud4@ zS4$O?dK+IGvlx#vkEH_CZ$?RN{BZ-rEL)~krz^9 zl|rrlLqJm}CZs$&P@Xy`D=k^L;GbHb?PqZ!sa!K_Dd*S9KA^7ZydB4APEB8uQmDv; z!Jee_CtFXZ5JM+s)+tP7+(JsSX?9v02v8yotU#G8?uJ+`BbI3yr?KFcUi!uh`>Up! zBRfVi0;DMf^-%6#sHsuh`+bC@*qnrQPW?Nx8Q6RM=&|RH0r#qWbZqBTB8UhWb9#6#+pO^dRVP?9nh^B~r*+ptjVw z8(&HlV(s9bEW7Nb{k!QnIlF%EL`7Z=`UN@_Xo1BF?%32H#415rW;WcO7=ovKEiD{Q zE=!%N8K$Mot0-a+E?M7IYyEfh7fO6B9e*PHuKy!GiOakL&sQ@%eM%ZoF%T{2m+=P<}Bo zkl>#xUxh*h57f`krq-IG*O;Ihq36>cDxm|&7|2TKE65l;{jAw#v{15r&jbolzv}AY zdW`4{jsg-FzZ*;&lfw%mtXJd!aGJCJ$LinD)DDD)@Mv*!6!ibB`u+ZSm=uN?^PL&t zIG7#ICCwy<_?@<}m~9YSMXod@w-wR>C`mD|LgVfTRd?b7$u-ru_F=A@*xL!Aeuj>&g&=~a0!FnFk8Ph{3c@w$L`e)9onCKRC8uTVN zcpX7cM-^09QzSMxTB?SdOc>D|hJw+(3vy6d;7~0Hw89Du{3C$%>T?~Tv*AZKhb^=% zu2ENn>t^~|44O4bzWqAvDtXk7+1RyG>bd%CLL)V1Z!VQda;<`%a?vvx7RHfgqK zw&>(X+x9mcg*!zBh@)-HTkLhT2)oC50c%5s=u@0e^y{2l zlxC1+zk6%RU4mu-H5=z@{Id2eX~C(WHS~qZ6q#MN{34!>4Uv;HMCW*wnlU2zyuY60 z3DYN!e=F?FBfYrl53jq&Wb&7V-O$LmwNp%AU?#x#wIRWh(ONs9rlF<1RsWfjIo}Un zMU|Yt$kV~`T5%HkBG*`v-*HvwVZ{!h9BH71<0C3YVv|L-q8Q`4kTW8kQ>**d7F|n> z08g-gl2pAp2StZCcwlm~?T;b<@Sqdohp}d(nqMhE_CGO`QAs+FM;Ne zKccyf;=djsqLk_H4Hnw^JQM5SU1j`2cD;YSFA?7hsxqbG5GBPoh1FKNPbDMXNf9NE zCjL3)YE@-!`_eLo%11$IJGh+FBI_`xc{oq)Ne3dl&(+M->w+o&0;NI{Cbj?mj#qbI zF5w6Y5uj=^CIXWK1JTM;H?0wa*QVnVu*e~gjhV2F??=N4_X8l z%C#)A0lol}sE7pc_T9Ijv5JdC6Av3E+48FwRdKYuTKEqdEJP&sVS8P7h<^zr>EJn? zFfvG_?=MLqmpj-Yw=z?>eLs043%J9=h(teo0}Gr(UwMQWxbkNbk?*fMc@x4#p+C7; zZW^ak0v#UVi~nUyf}hJBz8OntaMsx?TeJ4Toy#%IuMKs;91tFC_j0|_)g@jxWrO19 zD;Vl}w0fT{BPeq!pz*X)c9xI~o$!IhOZ~Z@gi_4>v2W$7>+`EF+N0%BP5%z_e#+Ma zp|?)&bJge5R8a8UpDT4^Be%3X50sdNxX{)%TBVQu%ygCipL)a2shYcuUKx1UVNLA_ zbrq_I{g4Gr^p^F{TLs;p=O~8zoI%+uZ^+uRWsiqu)hbhElVJ@|gx-^1HIhP1!a>bB z&WVIg@2?+eZLVsfXHRKd;;P42CfEs!>*1i5B=bkB`24m~>zVL1rYv#BijQ1%QL8jw z_*Y)ptUI@>E${2_8D*G?vFHZN0J^!{(J{n{jA-CDI@8*yde%wGS=|;f9=2~nHBL_m z&4GnjjgAmSvl-hV+{0CVd?s`JH$#L+c*So_gUP`)v;71Xdnln`royb#-6^j3QI30c z4$ereImI!^v!wnkh%RuKE#TvciFvrjom{t-S$h(SZ~_|9L$RddOvTVH5(q(JEi=vC zm5;zoA)%q;IeZ;HW2Jf5=|DnL5Uacs`N6{TV9S$)5?SD0L&mOW*}4Ck!l1ZZ>yUm` z2LXsBqP*~?iW%bxMxdS-@Ay8v?sKEx>Tvrd+0RSM5z@OcI+Voc#V{OwT8Pah!pXXZ zm>K%VxH{IQ{DOxS_qSx2AJH`5wfVg+umk~di`wEClHR#(2yO?_KwGMx-y9IN1-;sC zK^Z2*S}aw%2hi0Hq~uTk{&GztV~5yzpC>L zzgF|_3?3|&+-_XC-8lns*TcZnGi@-Ex5II_ynyv~U8aAPYp~a^c7Bp(=ukm-k?yao zyq;--*2uN21+47fnG21?qkXG~<11@u<)M^Z7YuRRB|RO#ZC%pNG7QSWn_BI@DHcWI zBL|<396pV{-O3$0=gfiNF62Mz#rZC_W`f;1%p&+c3=e0q&mL-Z8P9i&Bo z(dOU6zIq7Lt#WU+JN@77xunD+9mPu%E?NNdO896eWvOn}sSVAIbH|V9OArr9TVw9Z zX5|#b+Sl3Em)~gsQQ7Mz97`jkMy;KwDx*#Fxnd91L3c}ejq}IB&g%skCB_2}wAYLn zH$o8CI=-WaX%h#_Ns&(M@sn zegT6va?}s0lWD9VqE(vO%Tp%}Z;G=fp%?{a{Jz=NYjZeYo<_I9W&L?g#qEdCln?uQ z=-4rn)_f15_)S7XTxyg<3i_Nk&Rqoi3>$;RH5K+$0EOPah`kb@Aw|$x7~L6r<*@S$ zEGW;Wi*J}jcG*|W_9E~$CI1^P0ojoX_EIoSVNL38JT9};cPIS))&kiLNRG@OiU-2v zA$P>RZPg=yBu8y;wVWdiHP>q!xI)3wkguInPCR!Dl1Zz2RhhZCQuxW8H{8+!(~rcJ zsG9nX(-PH@>OA(`(i=Rq#?sii*`$6^mwfMxghn-!4S^j)C^jOUkX`4FnKJbuay&_Q zh42K@R-J?P-4|w+4Zo}Q_n(zBe(q(>D@*Z&?o127r~&W!Fo#P}4L3zeS8`?2@n_03 zECuXVk{Fpw^LU}6!`{55(mzp*%5Xj{85F8~D_=#-JEIms3VQ0oL-Hd;ZOpb8?Nrk) zTeU{;We>RXjUCBqUBa5K-t)g7u$7^%Ka*>@7;?FknA0#5`ez;3D-I0gJa8+LtgJr$ z%N`^F+ZAKq7z|!acK1<%Uat2xzWthXwOoyP0(tH2)-i3$WM+)*YQ7-m2GNPh-;QB| zR!7Nq9{zJ5hU>!G80)rUG$@gq>Ji1^_QTtIqtLcv0UnbY0-^#Jms&hM4J3Dk!$}66 ziF1yI>k$rBO<@(Xa-eMUBA;N%y?lN>>sd!2LCw0Zo=lVhpFom?k>f^ST&8!?Xo={Z zY*pjI|H6DzkOH z)!RXRES}mh^-du>RKgtzlMZy-Fb`J1jgP2Q;(&`n!!6#Z3i&>%BQPx)9 z+-^+g=f|AE=k>u;6Or$3@YWZW9!YZzG~@aE&(7n!`$K0@s7t`Ov;H+5SxgQq;GltC zo_~VKP`>ED`3&#G^mTJxeQ!scibs7&S3oBe9)NQ5^`wXNwVnPS$#wI~{q4T9qlOI( zcZ~H&tlti+OZGi6{p@~aD9g38a_Y{7l!`#o1e1RQUirACp)VL`-rb1Y(I{`%Ej@sP zsp^OKn}@G<4}eeay~rwCI7R5&bjLf}5UPqQ@b;4VIQK1ZVVtWkLyFWQxDvtQ*`A_Sp|eVU&SmN!itr*9Zm2fa+0qP{h~s{e7^TYZCVtuT)6fAezF@*M&EcSg~wxGebr3MZW0ZRGT z&A6O>(GdR;G4a{MD00v`@5I4IT264IO% z_JiI98o@ZI#%!XJnfpKf8j5ya7l=lTYKW40M%r>KTOiG?!)eCa(_cpXP1JZ+-xf?| zf>6IDZLoVU{q{8HB>s((RgiPT?VBO^rGxua!pk9_@@7yM{iPzvLX#NYw`ie+@PdBg z+5ymK*lU3|fx2K8zH2S6iH#heYiu=}S%drA#JVr)Z)X-PN!@w9g<8ayAAoiEh63WO zrTo=2D1h7Ygh>?SA9|ik zSQW8t+OaxdvEDz#5^c9>OV-Lki_FMaD^DB4LDjE%IOv<8`6hz>plg0M6R21jG z*$HEG&v7u(=ilMEUk8GXf4tX~zS|afP|dU4@{qX-A=N7e;LeBW2rm1**~5t6Hvn`} z61Vr_@h}N&5ZV!V=Et6jI9cPp<`5P&Go>w(`ja?ixOH&R$}`Gn$GDe+KjxzlM(F{@L$bOX;Hc_rHNxy_(lm_M?JhCCb zcy0==NPllfkJ+MEUgjW+Y2e{m0X|~p;0=aFs=lY0Wg=`y<&ZM*Z91^B2Vv!z9r4c< z)aB8*$)gR!Up4MSC>g8&Mb|e3W)j7D#>Yet?z3buIq+WD+}Y>7^0_tCu~~aTZNnujnixS?VFS8)WnaXCpz= zn*6BN{z3Q17E#hU#w=@q*sBoiQ2oi@%DoF%{VVim@smkKt(6(=oGCXpduRzzDUEq9 z@{G)+Mk$cxL#j<^qNfC&r*y1u1!tB=auJah#Ytbm~t5xt!$UMZPrVxtxJD z5+iyr+e;tdh=9Zu=fjd%XXPQ6>fvgIdMTo&{$0(OgBz{*e(J~U?1GS{yqNBMj73nz3S3n{kHFLS~)MTC&yRk^ru&!j- zqg3=1*EqvDbcP%%=LEY^eG2_aAWSB{0|fbda3YV`V76{A7A_;3*_;MR)O}uu4EE_ z6b}TBRls}|=Y+vawcmiVOLtBr=-ZaTa}lWR;;I~HT2Shma>8w>lR&k5g6*$sjmvO) zaQ28c&0e(|pFTu!KYh4iWyY%m8~ZzgTx?1=-PUyZUy&9fA7O{btHlQA^T4n~%@{&; z_nm4`$MBbhB;WF%_oao76d`VNMp3!$N%|MyK7g_P(9@wW1-1O(C8cf&$bEwg-=u%l zFeX}xo;<_Y?7#lBdLe<1_@5_buK9onsB|Pvvp@15{|kfLsG&Pl5GHiD{?{JTer8v> z(?O*GFnj%78~6;%_5!CquOK-(2;u_~Fo7W`5U98o14SPChyDqO$XZtXR0tBtyl4s4 zZxBGgfgCp7EXl!`V!*03QCEXxiW_C(D{hW3~x{tT}H z&k?+MTzDhMn9=}-)TNJSD~Wszwwwa{WgU=t!jiX@@-{LbMCh-ug*xvh8BNAIF^Sav zm7P|*jt_5%G_Q)Hzn2r_=qZ-drRY?h8F^hcCmiId5$FUP%34@M@K;n@h2Z@7RCGbC zFca0UNrsN{!yxbYB0Wx~5E?(;WUp>BEXE#|R5Ga(+e0;WM^_rV=$Vci{Bz(Tz#DKv z=T0KgrQ}@_2CwMmu{of2y-Qz{y_pQ#CIb!`V8#7{cej+<8Ry2=A?(GTxF=$N&?Q(zVs5J>+t5 zT5O2m5W*xJ$N4N`h&A6G(jP%69aen^TY-=4 z70QCX`m|CH&Wfy|-C6ke@I!9jg63=`r+>fbnRg?KTO&Z0Y|2ea*theB9yo34 zO@d|_EQL11ABH?SHxbKB&j{7GAhirSrd_C-s2p<2lG*T=az}uicr%i)dcVkYyFoM|#fzQYH zJ*0$=m#uZP6rZDrX&_aWk#LU824J}E2lSC%N*J}AIIflM~HeP#a&@D)Pgh1v&l|0aZD9L_2>u39|L za7)CWRESEX(x}jKI~U>TW%_vt{rI`0V*tFp9i^qs8n=hT_kLd;&GdGDPP8d#jM^;h zFzWH5Gn}N|K9mtMoDJ3qcKg17c78rO>_qMMppH(3vf7C#3Xar@Mr8vs&^xRic!<-Z zVw#Me3@~z&1zst;yL){-OfVTJv48Zp0ls@FMDAWM2dd}y;!ypJH-PTXTxR;OI&(Sw zFT-m9y~*ViA@0xGTkl@>5AC4az|Xt8`vw=IieLev``6&n7a^nJjz^4?ci}oRvvddU zX@ZL=;){tAh9wJ=1~B09j%|AtqIrIVw)rx*9jgv-Va>9axAn&-cF6kCynmqx-Mh*3 z?U-1T~LK%;?@rW(Yfs9nvl?laO4t?4IXffai$3-UlFqN|u*NOn%Z?5LTTV zxVctws3Fo*rC$1cEn_{Wam*xsbTHtEta(o&qw~Ow^WKvgW(k*t;&N^kbul`pon&#? zLvJ`COPb3ZzHNpG5+6*`-jjSj4gq>7q)%GTcMQKkEXx`5Bq=X(@=PKe<;=LT>0o_v zC81gFkG$fzt~}uAngzv-i31xaLM!g7>m?ld4VdxuElF9nnDh{sXCqhSc8NgdO>p7y~hcc0x#P; zTZNXyF^%Qtxe2@xYlp0T%QQzoYpC{iK{EcG&9;0|ogJTq zOfWtZ*B7TL$G*FeR7p02-VH|rO)4=*ZjOCczJTXBlP<%_dJ9-pb;pI+I(sG!>t8C+;G}97Uy5y`;Dtq?`t0!NZmtazJF$74e*)3#qx_L* z?q(c35zb&H;8Udy4&4bFQp-=NW~X>JofUOMI;#ZtGsFu1ttz#{y3KUkaubcHL<-uU z9#LtPoB?VZkY!Nm_JwB|ivtfo_(-$5ddwe9EDrF&Tq(>G-$}Aas84SIhimK+w|-1z zJNIhTu%WH0MS!+EULhX;^+Eag~b>3Ik zm)QsA2nW$HYKba_YLcAv^wZ$=dvk%9NS|>3239rM0hC!W!O<2WKQ+#F@B3u{IJ6G8 ze*xey^B|}Ti)4UTYFW_(aSrzDD<9FnXGO?wz(RpeHDovT_reFWh5WBgUs96VuwO*e z)|sp(yt*z!N)gK$)Cdzf;h6MTqx2WKuBPe1Qn|96xS!@f<~YL<syg1Y;MHeL$H>LMB$1MT1icm~z*7qXCeD^hqz{rUPAt3-M(4$(k zYbj=rOYVE)&j8l5>IrxO1n0^?)`2V`LH$gqgN%lB-tEPQBo9IyTYd~+{9|NwWGRY{ z6nhT=Xi;3@H#|?$pBZrcJ_;z2e9@SP`6EK4Itk@dFL9V)trei0Jcz^aQ>{9=Q7nLW zxWWe^6MkmKfUXiLj9idWl}fTDhrQ!eOGLr3H(q-i*=i&8+*%i!Y9p0wzxYYMI}VMQ zx22lqZ$MF}B8NU97GY@_+-xD1^COY?#oi{1+*86_%nWVu8`Zz?BRj(Ev_dcT^)-bE z{JDVrge>&PuB>=ccst02to6oG&1--|a%RpKEfV74@fnHe6tOBZOf1(eGchYIHjA1e z>K+k64*syfDe^k8RzE5-X^oV+`tM|x^4FMA6AmLWr14y(sqC*iHz%3rQD|tiR7E;c z-yL&gNX`w;-3roXT56@{pegu5$t1(Ycj$eICDNZ^|gmPS9WYDT^MzjhY-7a+a3W-5ewFicwb;L!kgGzH8$KEcU88z5z-#cZ>ucE;ZL z|AM0L_EKS9J}BxCg48R7@AcUEx-mKj#oa`^x!W`7m*EM#jQc|E2P zWK5@Z8=^4mF}cO9F>chX5KWJ&m*DdVI)uA5?_F+dB|6eMO-)bGDdy?9#aDFAdCdSr zDvJSTpjP9J2VJh|{azbdAh#x{l(^wZGaj>$)qk?0v-S1mB@o6#9LqgLAAfDG3Yk#q zOH(+|$%t(KE+YkOV||MZNS{g1%;UazBmYrTHju?&BQs21ddL;~1j;B{bEK{s(Gs){ z!Bd_Hl+c2Jr5`QIU!I)Jx#mT+>5iB1t1tcSbn^H(&X zZCjys?M~#)C$@{(uL$|Q5X*zEIZ+L)zLd@#Nx3ExY%U0ZoEK`eCbwTAJ1|f9Fkg6B z7_pcEbm=^Ydy`;xDT(epx=qMa`P7wRwIwvhiP2w@+LzX_=OSFb!1MLiEu~^QFv~hM z71HNTv}A)*cF~Iv+fA+?0L`33wqgsf2*#$8ZB0K2E7po)K`P`<;d%3*`1BD4$20H# zxrg4UxZwjh*kaAGfG!_ozwzAf)}j|yivV{b$!I<~E^F9wK@7meypVBv(EC#GZbF`1 zl%33YKvvn6`NmmZ?>|#-c^VsP)6oCbGVLHpE#Wf6oz$q0a9#dn9`PvAX=DOkSH>qk zL(V?NYSr1>&b(|4bbr>t3B&pWa8_p;gjJNw`_<+T? z!wZpEI3>tUrqz>Vm)Xs#X1QOqdeRxSxzesSO0#5Snrqlc%l9;ysR9oE_*_#<%WuE! z+hyI@F17MUuODI~=~j=u3}fsp6@p`na;h-Xw*1W&*X@cm%&vgbWeZIhDTTj&l%K#| z+4>FWFD<1%ezaRq8Zz@UnFs%p z_aMF{+;x8A(W3|4BSUMcElX{exxl+qt0efwDI+yqL_i>8`Dz^y=z}U zBbz>EGv$oeXeyfHOv4kN1S0YSQD_LmVC{mC9CUdZ19>3T)t_1^v8kgd88Rf~L3M5v zi@l@kOO|EGY1|#Z#AB6oT&6U0^%iP8tb$Kr%gVgzEP12eQjJGR+@nY9V&F;nE$^&n z>Iz~dMIM0DXb!%$Is#*Nqk84(_cRQEDGVt{$Bv}oF9_=fX%iurX6Z$vqpAf>z@Jp! z5-yj9=jxhG#t&8o45c_sam4Kb;@X>oeBR=YfMD?}Tjzt6r7f<2pwyxa&?>WI)+*g~ z&gFunoD#a6ZwL?P8G^ZIgn{ERCd)4c`NZ9cf6qhqYW;kRo!HT z**fh-?=(;zMcs!fz40~uVE1nmm9|EAPYpJ_AsR_euAY6J)_x8rCKsNg<_oRobGl(( zl(cvVJb^eZ5Q@JBBzWeMb5uD1gomYx1K&3BOo)d%y+A6u6T^s2-C%Au9K1TdZvz0&~$fxS*7A-&8MLb_&_~whPjtr4^6m6J1PRX@2HCKCXOqB*`o%1udI+Hy;ojL!xvm5gz@qP zgK+Yxe5Z#7%%TSW0r;n-*ySM^*r#crm$bj?z*9WF=z6w$m^u~!Cf{Hoppy|?P*Mna zu$-UlS0}7%D8S0JD8F{s8H2+TV>@@H8i*^PZ-6SWVgGF^kum0I_VFecBy5sO{wp`Uyg&B%0sthP z+Eo01g=lF)mcT*CEKIBnEbRX@PRtCP|1QiNNy0Gyq-lhZY-vnZz+8x2T>o*KorRU* ze?OGACjrcmR&Mn_`8fFh!pEg0NCK;-Iavc!0a&@Yxc`fO>I#3&{&3_@-;j9*IQ9Ai zCkUBUM@Uxndr4Hfsg=IkqEz}>S>Hn)^DMNzS8?%6QP=%# z1CZY+{9qCwa ze)~8T4___D*5-5?Fi9dm65cuF)n%_C*mPG+QIOX=p%nf1?caisE8@^b*ToyNw7b)P zqMyanV08=F0-Y|M+L8n?W;X*}WbVu9FCe%s%YOy`Ys@kATOe>;w)h6o^kWJ0xu$C>hg8}I9LTr(CO>M zTDd6AV7NJUouHVF?eup4GC>GUtSQn?9AfqIcgx{L5lV#2EsqEAeSDo%@lWcYn8x_y z|Nd#l2ba`J7(<_JZZd9(dJ!=4}fBixboD7h>nEc6~~5eO_52ptGud8bxhJMpy7 zDm^?5X^bjc%KK9nul;f`DGr%f#rk-N!PJ+eF#v-I^rpuw;~RUJ3Xt`SzC?oza54>( z>xERc4AXWPQYT|Mm#wA_ZPawRgWc?14){`~26stX|Yl5TBsvjn^&tyLC!va31 z@h_`IJpb_Mt?2#EyzXFE=${njE%}Q!MFxdo+S7rv@#&+$a-d@-)YsI~CG`?&v(kR9 zi!^p{B=8K#eR(Kq#XEm$f}YH2BQAF)&aNiVgz7Q03z>ScW6pKH2cpUZ6V^DG9}>@aewtl9ba2 z^{*uAVTMGTU%!XZ+mJkqxMq==gi2<_lA=oFl-7c)iFKMR&9VG^GtC&0N{y^A^u%D( z@Lf>=?d1Dj5cMlW)w`iWq(YD2bapmb(PD8dtx5c>K@%AL zrOc8O+mKQ6t$I5nG8a%xE*a_CkeN=&Zn@1F?1C=JYr@Z2bqfrAqq8aO9;aZ7Il7@@pc{yUG}Kq0!gpJs8V_LMN*j11&6mwR);Q2_5YK z=6q%6W$4sk6>#DB)Xl;;;YD1--}iE*#9131tzvkH{!+LSK~2@OAWwDOx#Rd6 z^s7BE1if6D{OYp&Z=c+#tOXWx@5$aiz|17o)v31cZ(Rg#(jkyf%+=#edSJQHmK5tk z*Jvq<_$2s_9TSt(UCA-KSH#lr(KBAy3aKBNG&!byM9t|a8%|m~7~!3OJGdk8EN#=% zM{K|-_EkP7u(vcJ$m6ElKrK*nI#s}ShvoRl6_iZ?s8?JsfN4l@pI?Mw-nn!Y5ZL|1 zqkO#N%Pb z_!*;zs14(OB?we2AAi<-7Z~U+HWwL+l&lISm(webEcw1IEUdl;__oC|8~6{kt%gt~ zOL1=uJR6eHtU?UrL2*A>+KZ($Kt&J&M)X`#MazG5cYz6O|77*~M3pIh6#=>p%XWVO zX5<&`38999pV>mBa^TL--LN>JebEkP94Bn*1F+cY}(?M|^w88oyKR!IR(dbEzCd z^}RccMPL3QXi-fhvwus1oa7ZotPt-ZD(pt_%(dW7owOd0tqv@;o-|9s*^4$3^q{rq$0owG@*`uUT`t`+3 zDa(WN>+}9$!Q=z=8*}%4Uy(l(ZWVTU5}>Tyw)KcLRmu>Li}lm^1x^lB@one#r7xuC zEZKff8;i-KZ!t;d&N?SN>*4Y}_?ENq3v3|-`AX?i1Q8kTPA18aLRJe-io+PjF)hy=&9f0GMNB+smzeDMR+5Q9 zV9^+u4z;VkatPq*o}6ibVDo@7?J&af2V<`dFB*ux*kAb~q@ua6%p}8L-e$W&9&MhXa??xR{v{iETsQ?aPk78pN(Un1h0KeCJ zMrYaSvpS+63Z%b0V?i>2VtB`+1wzBK_$Y82l|)>ppTSWwEJM%4p6GoYkUKAq8KY=U zD_msn z)kQRb)koEix@h6-)c4{Hj8%_=ar%fOVp=tD&b)qr6(7(0KS4pxKE@7=P)FB>|mVzUi-nR}S{Qkh)G0tt|q0V-yc(}02@C90v~n>&{bW8wx{ z>Jqsi!U+oIM6~y$r=U0Kxpt->2@Rc=?hR6z?J0CRRzXCc!n4Ph{pfP!KhzC(`D~EOw9W-> zK;={BT9{x{C2< zAlwwM!;@5BuO@f1$9#Z-G{23?q^}*#V6{+b`kgfywb5T<+CuWBE33M=NqNwcw^{xu zhCV27_>t@Sg`h0UMSPr>dJn{$Krfwp!0;xsPP0=~>|Y=rEGTMUX$2+^e_b74%LScv zrw43hqAGh?>(pkQrU#1O#2cO5g{e#NwxCtM08VV4+~|W&SQk&}PVR)lOnQ4p2H2C& zMy#Lt`0JOpy5AUGf)WO@$N9#{^US^SI6HHpR85w`BExsxp^MV(6ORLvBsuH$fQe2X zsnc>l`tgF2VdWzjU;6L0QeT?P(4f}zYK-$(-23OVdR5U3&TPn6bx}Gb7AM83b#{Ft zpw!hdQnz}dtlRx3?##~g+$;>z>eAh0|$!PzAuVz;%PPC9_P%ye;wOiK|DX=hBUSX z<(YqaN~Ajnh)b4IiOZkyy}k#j;B=ZO75YR5k>71nJ#CHa`Mkd2UoOuNrqLJq%e5g| z>F&|xCKV@{gkI71;dfbZhg3Ct<_xOrdgHV9rrrs*4fc56d4Ko(wDIdH03m5LW0_#7 zlb5wRh(%2%Swo+tATl8U6{jU3 zhQ%qHMXQ_Ob)mp+@c6EjP%Ot0nj!|Oz>PkzYCL_r;3Oek`=`XR%q@=k_WkO9*u#l+l_+2qQ$Bjz;_B&E8BdV*5X zv-4H2uB{o$*l;(*1^^!NUBTX`=Rlj61uzA^wqv>YWP%LUmpx*edrp+2R<~N=*42cdyiJONly5RVM2{k1yE`1jUTLaIqZs1mGnGu9# z{QWHm0pUKSq9V__xH*U)u{|nRxXS4V z3Ej?!O26^zIAW7$Bbrohk{mt*k7_7fmirE;<4~GV83p|p*Y~*?7ZvgkC|_Ox3)5Wk zY1h8MMZjE1%zXbxkUQk}KLLRMuOOG1`9JCR41Zv101L~11p|)sw_=Z4;d}DRxK_aT zPYqd=(9*e^k}fb{AA#2?#OLVaAHM=+Fe(JIcv3ZaJJ-yaxh0!zqmmyJ3dIQgO}=*! zH-Bbo_n+Go6?+B1BlnC+KcC~udcXIc2^ICLx6emr2+24Z)K1!NZx{u)_5o=-{$B5Q zljIa)ohM!pm0s>#JBlddq z6rUCjgaH5j3}W|>*E1{jHp1lO_vgEtHbItBHk0+Aiq4;=@0+zB?veDzyb(jx@3_%k zp&iSfT#kn6XMG_*@aEgEVE|xTv|DgX;QJy1x08vuIjI2sZtCSKQZIyKlPZZ3%h$JS ziC%-Nf8ohdzQa?Var`CH`OSFOLLMDVx7Z*jK^@$)QCEXL`q5bi6JKvP(}nm#bL82% z)v_!^*Cm);ut%1kaAEJs+9>s7TkXll0BSm!WWBVB>u`XqtueU~A7BT10UZ~*eJ#b| z$_)r*FbpwScJ$dVNo@z3UyVvVrMicgQJoLQ%{B?MaWeKqK`HU}X|K>hK`ev_s5lNm zio)z{b_36r^My`YJZl_0KyQFL4(%gs1q@(vf!Tk9+R0K5@i@|#11LJPoX z%FU=G?;n0$-Zz)rgjP`cjK8zCV@-%SssYN_NNbJ-dPU-^o=}D;Us01QkIyo<${%OGUUNm0n>1MF>Z z(4}Nt$h%Sq0*Nn>7?0tpk>=}vw5nPR$Mce**Vc*%;AHONIpYW1NTn>v>hf=4Vl!PI zWI5_V3GBJ3Ny6-R%s4X9yw&M880{W+#S#6aIa{1OUdk-SY1YEI5rwEL1V~W1Z zo6Jzz0cTiP9GFso{#~A5cnGG<`CT|jBh}9Zo4@^(4n1f2tD=12D~Lb7GrtcD93?X0 z(j`)h5--{3r(~?+ojhhn9T0Py}zl;5hRF3pEahf(qGY;CoyXtafi-L!SlMbF07n?=K| zj~#oH_oyS;W;`|iFSwbAIAj112LCrjy`h6z@bh>$=0{cu6Q^0nAL-umy*n%uKrwYk z*_-z##a?p}dNnz;4XHG17jxq0ppJ^$LH~iDA#g;AhFB(GHP(GIT25#0ZF$d+mT65X zoMVxmU4am$tR&Psrq6nQd0vPoUO}|dfzR`Ec{RqBEIUkstq4Oa|8iJWwVZ>Ee(6|= zi#M}w1*V#0IMsVT(Dgqz0GODxaAPRQ^4d#~GAXV_l@%b_S?bVS7C5@I8P=g|iAT~u z6@#8N7oU#=kB*K&%qKYh8&g?v0=>o!_~1h=MM=Kaemk)oQAuvKtHwk1=al-`ur8Kv$Y6QgmDfXp&qQ;F-bmR}q$ zQzdPLfrPI;%#kUT1AMjkb(!ri1*S>TJ=yy_cx^Y%HH$%Vu*WD1xBU0m7s)$i4Roz8 zzrZJG+jGI{{c2svFFa}qIme3UjjZ7GM2t-As*-x;O_)6&rk|~CJ~VAWQpB6^RXn$S zjzzS4fWA6Br*UN^0bXq{J^3fs$(~;(fA*(-AqfbW3kM;a&a1P8r)2HRK?8M} zLi=KL#p{8(0?k0H#n)&_aI}r98&Qk~aFo6K!mMxhqOHfz0~B73QbBB6RR(ZO(ol3V zNfvV;*;3EegpvrQf#GlC`cS-rP?)0C|1J5=8T~ir%6ReuXvFmuay9&tv^2d$24*DPgcT1NbXA-U*uMaZ&YpeZ1~nsQ%(=F#jA-J**L2TDa~Ara+0HsB zRZDJle_3k?ux^K4r5KV{PYmZTbQ`~4p@vpy4C!+N)|GyqfYz0dgrpomOGUDv)k&|2 zE;5u(7c#BPA`I3N@nQ9eF7XHsRt|D6Jmy3Nr1_Up!#mX`aLlTv! zLmyDIp*2Enm63-#4N3A|krotN#hdW9e)EbK$#|_d$B$o`GYvlbxFVX?v2^jI${xEn zRpJgGDfGv&oj_ry&ZNxhoYHU=!V$)UXg#LRpEWACyUE)SQBoP%JL-cnm0l!*o$%=o z)_VUwfRIlkQv4&(=w93NzHiJ?ZKmtNX~$4)C5>;DPyYH50soHdUTMy8aj}h1kJ}f_ z<+XZb=)m0c71s?R=I~lMEr(yi$Ofz%q?e+fQN$d%ETynbJxnu#83tYoBl}9nPgk6;BQBugmq<>K{SJZPT-DL%vI`?cKT_>7#75wn)J~=iv zat~UOHtud={y;n7{a~0ZA8!oEot@$3V+xHp&uO2RdbonmdC;lx0D0eaXt+Y@l4b&` z#ro>Rn-~9(g4WDQc;S^?-rD*KZ{02vkenHgsRLQmmNkW?4b+JYtLba@d>4)fFxcD0K?euJ;sZ=M zDBM!4tVo@>7v8mPTh#F*s0C`s<~$9Sku&W;MkCZ)2rsslr(Vdr8CKVdxc&qNI65%4 zQnkthX1lk4+s7n27L(d^JWsb5y2P)0b242S^$KS6R4Ahu_eJ}1VHr}lZooRy^iwZ8 zDW4iuwz)S6bz#`RV9Z6H1-bz`Ir{`H?FMb>yK6=V z_0B+jVxKRx1_n)LG;SHs2@I=UY8d9npk_eq(i%J)_qk5Hi!S|=8gDTH;J`_8A@E`c zN*bGxUArMHk+JSWaQ90BR1QQka$ zA>gZ3aU)LQ(c05x;f_^VkrNK<^(CQd`|KBB3bC`dgK{1_0qezk;PY(dOZcxKWXrj7 z-typ_3COoXJ2JV$Y*8iy<-`)S%)kcy3C1mh6|}#)H43$o8;fZQFa*da8BtYup*vQN zvd5C_{X9FiA0V2aVa>*{b4Fm|PTV+1! zGOla{q9j4W$Q2U-=#@+_3cK6|4^+EKlc_r9M;rMSLi3P<3G0xYnMK~+bCrZNReI-T zhibE|p6mYA%6W&DkSt4`4o^HRu9aw0_^=ugkcY5$;XG(kOj@+xu}>hwV}gvUqz;`} zx{t_3aDf_y{T-Gum$CihetbXqeX@p@41c2u=JBhYwso5gkakYd(YKW&)#R?2M9iL} z!u_Es3NzZmnJCREkqFR|t+eO!?BZMvJeH^}3L>I5EyHfs-31CYF z!}%{hR9Q&_J$nwrdDqr33}I5!k<>fj!h(l*DL0 zfF5F9?Mw0#`QU zcU3*WcUiX8SM@yL`SU8lz#hUBy9aOzQhAmrArdaqg`qjNMc-X2D8v?+p^(YDS#aIblFTlOp0iPMP6^j$btrwN^V=( zGjjysA#t)U98jV<^^X8043nadaT%*t(}W4HrGgqVHbot;cqs7K&85KzIN`(k1rdTh zFhkCeNDQj*`wFV9kCmiBELCLAIfZpvJ+z_=r0|e9fKpyRuqXtw0G|O-`L|Ti49sLH zA37Fk0a6W;3;smy`?X`}%cdft{si{iZwoRu>)W)(3RkTN+Tn9o-P3;|*W>L&g_1~B zN01n*;XMuMn~c5?&`mB{S8_|6-o@XDiI3&?Y3T{TnMp>_r2pwgHcbSk{%>{z^#7Oo zfguT)2EfA2`d`EkNBY_hWNpa)D|P87K=uy;0Ym|8I&a+lAaB6jcwp{8yg!6cb^Gje z3QbF-c9;5>mD*DjRgs69!&PF8LtkI9e}0A19K^sK!C|RseioPl#zhT<4`` zW4HkS(Har~-tO04z}p@Qq5l`)?(Bnb>}d4oj|v&

    g>iC6W}zv%CUJ#l2KZh+-pw zzb!CghKk>*ubKP7Rnka42`Uk=9-H&&wDWYmB^|zx1FA-u3Asa|5o9TX(PWxhiq-;n zX#cbiWJ$fzY?`a^c9Rms+UV3g08Fad^4Or;S*P(eC2mf(>xJwU7#k@-f~q8rWf>(q zAwp!_r1!iOH~)XU0dB@MUgOOJGax!qk?&rfoqPPy!7L+|-ILD+wlc^a&xkXb^l5gvJ`A*EIqN4clb}GK;Z6h71t%!44PTKNseZ)$7eeefmVt1_vFZMQ?QJEfBb0W@qzuz^$Dgi$`8Gm;qqmRW3SdlpVi>QLdXVD4?BAU zj2p8Iyv^dkmD)LELD`g16^)#a8FkcbY?f>qm6OPg98g=KlvzA|mncR_#6c`at}gT& z^l7$Mw8GDG*$Q9yw!8#vRT(-SsvEeGJz~KX-Kmoa`hGkoz2;JF1Zo((f%M>PO$+Ga z-Zk?Vv^tB$l_t8sQ(12J+4cPaeTq6L_6M5 z%blHN&}X(!_srxQKLweZuQA?67`|t9CE0RFe<3jik<~RNkLwn*Pjn*vQ6olYi1PU? zpSzFkRB>jBGsdB7*9SwL&PplK_S<$MGyqwIrt6P{{h(rBg)(8I_+SX89ayxFbaR`` z1Hdp69a^Ud6t8$`Oui`sL;LxOa|)+nrFqzsA6%h`_%XP+WxEu7+J@2ZH^xIY*x-0& zorRuU4frxqnptH}#4hs|=cuv<8%@y zpZvhxr(hw0ekw%n%C`t424lwhS zGjw$XnFmM^YN!e!BG+Wq=Hn2jHu7#_@;!ATmfdyHX0o+RjV~nW8$4Ge1pqtei#mBO zGS4!aw|a|HwPepB#b!FnF+P20C9IjPx^p$>#ANMSwP|Fh(>fG25^<6$bG%uDA*HA8 zY0PD$)o?9FDDCS}@!VfkM&hhsb8}l|w6s;+(m75HE84CZBc6UEP@6S3QgIo5W4%SB z@7_Qb4M7S*b9Ke0&1yp-vIF{Xcn zvvA9eT@SwF`U=L4l|t=rfDRu8y2p{kng?e{)SmBEANTYvvRFCvkE3;^GVM<;*jA_;M(xU8_8YHATWhsjEyn?ak4JHJ50`KQs zdwu{hKEfkS(IU{PI^Z8ha9NUR#C(2KR0=ex(R`<&i{92W@nE9%r(U3#`HN9eli<2) zH%LsZ#MWfUQkdq_Z}_pcF`O13Bu_e!i4!WI51I#RLSRXzR}kOgS%IzD3T_Pff;0+^ z%;C5%A?#f$Ms8HyR40AXtN(mcAB`RruEgs~%%}&S16T9|9S{ab6L*%t`icN#R^@ke zHvzMh(30@ac04vTuzz7oIYUZt!!ctwckgQDCqY)`hrB|`A+e0vD&W!lMUb{srOHH$ zqs?J+Asg>BV#axOtlNcC;IV?eLYI8WrQN9Xo*OzYYf%5GPAH}DoAyDu{vFEJ4GlSU zd7n9uPx78%3cx%0_NUX`A`}u$@+8tE)nU0CHRfB&0B1G)V_MOMG3#!{JL|Dd@Y*`t z3BPl4{%ReoKVZ3iq?dc>s2Q|KBRpDXmk1mU_f*RP%TS2OQVxjOl4}@@{7Is zG^GG(*5ndF&vJKrZ&cfus~Kj_e6L&?5Q~!?oU+=s=0q$uc+abE_0@7|SZ2L@IU!S5 zt6ENb7%P2!n=5@(;#-%D+eCrDQEbjr6ewvNaOGsFZ_>@F@~iFqI4UF4X%J!Mx^t9(e=*3 zokU&NXl&cI?M$4BZQGuBlKf)Zwr$(C&53Q_JYT)ft$J^L_s_20)u+4q)H(aCz1Lbs zQGxCA9==|)R<$2>NBw! z*4fw(rb+hBOVz(B;dyln1=~?FXr_Uf=It;-LAuQzBBcL0KIqL-#z>W5jH1o$C+MZj5UKDgL?S zou_l%hZd*Eu3w7zzTypVsO^PH?gg!|{Pyh_q}!qj)NZ<|&RmixCfkynHeXBM_!!H) zk;Sgswg)iHx}2?T?|In4bMQHGnU>Pl^9aV3e-1r4-z~41k~TJ~=JX?;|0;+q(q0;K zWm<8bR%hW=h*yuw<(x>Yf2-D+m_B#@bxVH*oqwD!fS|lBz|O@K#&_;@^!DK4!fNd( z9--AL|KLI3nCV?Z?zB+4o{Co|T7TkdxX%)y9RS!2V{|*25dAHk|2&CBfeZ3t8kJ_K zwUeUREOR3Iu^V`~=VRRz@~7kB!8Cu;IOOt&&rVpE?mk$MHr~Fym0uC!Az!i;y?=5x zQ7@~J?NvCo3v{7&y!ftmjYAsg$7hC4#d4s@t5?lspZf^KfY{6=oM=3isw4nLr$>q`={1y1UrSyDYmBVKUm~v)#u9hp zOaclMzGj-4(-^#|F||ff>-Sx!_)lI-U-j;+;AhSmFAig6Nk!T;Phy&z7aZs`cW1?x zpBs&Frz?Xm-9`?s2WnZE8@=qqQ%Y2eD*+${cVUZ+les&CO7siXLKzmLC>q65(hZ#D zrU(WE`(g=W6XNwBQ_1grdLT2&KyQOT_xA~PsL5@2&qAuC7LR5?VGZYbqO3qG9|nmc zu^yG@$fKq!E;+3JW;;aktE8*jK}?)15r#F#%paXpARHl+0u3WF8&%GhLrn?6@&~Bm zuHo$Q+fwCWhL%gTh^(WxKYOLbLk| z_raT97mZ`;Dl4)VboIhW1beHtZWz#|fc{*-Me(l4Hs9f!Z)ZD$ckdu1LO^L>k<38l<#v)AmdTUKCczayP-B7nXY| zy@gcMd~Df-Ul6BVa&(hydQpQ-IB03fUCNcgl8st&-p0-bgQAd}e(q&sFbxn-p)y)Y z5cN7qTzxowQk71Gvp!HY<#^@_hInQiE}S?K1T|~dyra_5U$r3p)de}F_+ZqeW@PD^ zp@YsXsyhaA*nS+@k`CIPTypcpmZ~cEPB~zsN(Ry(q|>`dgh=L}O0E9sl|BosX`M%i zmp*+~CJcfA;R2)sAxVs^f&{orELl)NCTiHfgffv6ji4H(>4eJ^>4yOt`N^p*Eb%z= zvrt{^DBm1J+5fgqBNGu2ZrJ5q%bE-c|I>h&*{}=QxMdx(qxyw+8@2S3iH%oB=HkY7BR1~S4Wq9_tj~cMURNBrYu{u;+(AJ zbDOg@%dQOUc~N0JMmqqRE)XuxuF$OkAKC!=Us?zij(>E%0u-)9W`-G}kw12O2jpAu zdRb&zmtd_M6bKRmC_;d4wD~j|eP+R#7jrzn5tvac_IQ{1w;r)(H3E?mR~Dx4Gu@=% zIu;u)bn*FAzx)(6p9r>@+v|)VWr!yFcK!@fy&PF>dFtO!gq{KPXTYQlZZ=F!9%c1x z*XPQ^?G-zm)(u%DeW&p`!wfeS$MQVD$2K3L(;?ah@4^a599mF}w{3!=U7EqB~bgFOg8~* zeub45o)K<$w~t-bfB;(EhVfsw;)jq}X`ry1OI|f$EPhW%rrjpmR~}UxD8tY(?qj(cS!^hv@Xj z=mUJ-0DHgdKR)y~B1~i$(#L~Ph;`)!UaRqgu=9!HT+bz^dr_mvis&8PU<59*vh{O( z+=*e2DxAL;@7@+r>EYsz9w!pwCLqV!x}KhoVgi}Opa9K;vNnA_J5b1rJ{R_emcn8@ zEj>Y>Us$JPjkhkg_{1HaPdJ|sB}b3?@;Um50C+e${l`(L3`_jg_>EziS}_=5Op2xq z#1Nfa=K3OJPIEetO5X>v*}CNXGDD&@82&QL)&>40wsF4-`f@RJ& zPRBTd;0GiVEfm|S2`#9(H-^bFQ1|2A(~Sbe)Tj&20%M~X$p7sg>Ih*n+N!I8zM{0K zOc)WStlvbfGsc?W%ypWd_K@2O7U=oqR)W^W;(RH#$<3&$FDc~uocn-O>>r7#jDhA= zRT$1_n%6(1H4$5lb*@LL2sYc8Ok`BBujTJg58$R!G+7|0P$c=5^uK9}r;OVJs5H^) zjrCwsnAYkHzjikbBPG;bEJslH?73>p`v)>JNIHY*_-pK0V=zMpYE;qcg-XUUqEn3d z@(oj-CofjZNXm#~qpZOdji%M8e|N_Y5y@#`G?YqA{92o-w*l=zcP=a|w1^0GeEhIi z8kE|WstiTZhtyQszVhiC*&o6K&>Kz0Y|RN^)?p5NShOGh9Gi}4Tvm73uYDGihW#U4Tno;0o3IlqWldPHuEp6rEO^Bh@7t0ITkz~7pfHfxw ze7k}e=$(IhZN128>w^w+ow7ztHQ=EpKn`Io^#(lelDKr~#cs=${w=BlfEu)9jj2~6 z=?zdkDQKH`*Hjz?g9o=T*i`xSP5AO#VQkS9mbOz6#dY9A&z2#@G=VgMUHlW!B0y6Je<-em*_;lmDd=wDy$IX>i+o`E`})*0GDx?2!We}Au{Im z(@cD$-Ar`s>{ko6DshvY^ANUJ0%*w)NX56C;70tZ@W(`9|&RAz9nnpNo zQCW*mkb-|HsP$heky}l{pQbxq1tVK%g!N7R@e}^=X82*q23OdEc|4tq70Z%c(MhZL zTb`+d2DJnr%f|sffFqQsr-6}$Pke2)8TztY+DEO-aBvX?a*SM%W)g}pvkT!JX5g*J z?6MN3{#b(ypwp_o2|09wi_T+Y3q?_?J4`y~~PhqoNUM-c6B_(aB%A~&q ztoea?!duN~s)j61eJVREY^w*4SA#Gey5Pv~Gb(&7VR-c?L!80icS4$a<85$%oF=Xo z6O#gkMLqhMn?pmzO|STkIbFdzmJFsNio*U1Hb19h&tGNR{s)xCl*lq3kqCdxWjU_a z&?G)AX?(0SjK2xZ1S|**5zz|?t*|_X%$PZgz<2r9fkEXeyzI_p1TtLDhe)%16EDX? z?bhZzz##+#kXEHKtuylG{i=ke0viyL8`c7@%$7Mx{zlAI*~SwHil%bW0UBi%Z_Lb` z^RueZ_5t;+vl~iHX133il(z0OOY?MJ#9Wlp$wkE!h$z|!6M)1(GlR|G)0!Oiw)0>^ z=`#)cp~?}i_b0hCFHJkt?5_QBSY4&}`Tb#F9(Uvg$TG`|+tSJA;T$z)>~|r+pIDUl zCfKW)IGG;I%;O6-ao!yNJolJ{2st||Zb&lzb7r*u{>Kx{bo4hwCypYIV6~jnlUeU~ zw+qz>hou_dXIte(LCCNQ$H3neWi0aM5P=cg3a?PtG;*o81Q?oA7;#5>gw~LQSOzQ0 zESQ8GK*NlKGFnrUVuPkxwwY0BD(LuB<)h3IUCb)I!oRsbJygX^OSZYbfJ%7;SVtb;6acniV`{|DUo47` z9Xf=DZ6IFUsH@*bTRgrZ2GJNh)!#wHqR_r63K3a}oEym#L;ojfJndAWi&ih(FBl^L zAR>O-SL=&y1T4;}fwg3WJQ4P)@pCf_`~}NBNDLoc0aekDhx^$?MX(Qv_ju3zFn=ef zPT~kGsb&+cS~TiiXP;$Jc6d&RvqAvxsXP=j5Ose$;S-Nfkm@SeoF)YD07Tj z1M#^1*__pN#5)TcIdEPg)lhXVp3nlo~ah3(A{!q_A+pv43l~yc?D|tPCA6bhQBy z$-tUe9WiC}8`w^@z)%xUIzFTpl|jUh;Arx13xxi9YLH(EnDMZYmlKp4k(MKfJJaPLAim%8s4+jc0{aZ@>A4d$4nQ z8gTHZny?Fh=f0lE=oo525aOfsJzU%5hH43qDEx&>p9NiR&~I9bpRWLce>kbk=gb5Y zA6M`T^6AV4;76schhhU*x~HfT3B^`qs0cy-{AuQHo|Y`onm!?)J_~{nYbhM)k21}6 zR`+C>UK{dBI<>25k-qUSv#p{rBhK-_Eul zcawd$Yf02&Tc<$rhS(pYp}y!5GBW)O@Ggb8hC7fc)3Zl5b$jIY!%r77J85rwzvU;j zv!h~OPKOYW|GBz^BTJwI^ES_3d`hyuj3h~zXLU4-^Iu5=)TOd~n@oQ=sb&b5yK64z zfXsRv#Y+S9C^cNxj**#3V6T(&f?rkS;NHh&_oS{q-=nRsvL60M69^?1j#)t-iUpuD zqM2kO#O?LMuq3ZRq^Zamy!!5bWZ``y^ZZw*;GQC*H!pf}>EHLO+s=&=9W1y9S7U;UtD*Zg{X+A+MA2*R0lWKA4g=Nxu(1@+pFN}VX-dh`7tbNqaj`WAU4*knNoyhKI-`l{jtLd28 zjDBr7Is&Xf(%ncgCkwA(zm!P11yxBH1t4xPyl5|ma}NjFIoO3f56qz}(v_`Olfb~2 zT*7_YdYK0M*<^tIb;Uf9YVGw8t4J`IJ%syOmA{&ppr%lef@J^$liR-3l(1_{8_K}% zN&0r-GtEA>(-qYV{^bgTh{ObqCa_8HSSApknTe@9t!u&EgnghSq># zK@$$_nSwLu??UfN5IM~%oqN|GL;#?KXpgkQv?WFdM}z&{*2(7}4wmSs3%Pii^%z~= zxW}^JOn^SXVBo;`dgBLexn@A<)T5vWIt~0%TDt?Z$Q8jb=c%N&@gukp7gS)NCnc$= zI{?@Ib<@|e`-A;gTLCi9S71nwzhgMG+Kfa`QS%}DqsR2S5l=Lw28#*9|QEG$FpRKl0|nas+0A0$h2;wCmDH(6`9cM&2TP!GYoyJRxB=X}PdR>1?vMYN98oi4WPXkaX2a;*G;U~> zzFs4*Sg49JXCZU5beab*hR%3}gIcSlx*XV3@SV~3K;ZlEO!Dp;IR2h7gdaDchJ=lP zobW(>Xp><)diI&(5z*kpNWAo=sujo0M@U54lEPPm@r{HeckSW9+*s$Xr6k${Ed`v| zTe6#A^!8o-mW;c??B&OqpV^AMU_*VA9kNziB+v6OKzyu6%^XtJ^5*~NyucHp4nKO# zeBWtnAsl(u9IFvii6NI@+wUnlAK`p|0Dl`dl1uDQc==W^%ZcR*Qlmvn{iu2d=CWPq zM`ckgNCLBYk>3XO7IplTpWbn;bp^2M+1R-&GJF%#Lfnjw)m(oMq|h`Vd7fTLBQtFD zwyEBc@#PR|SwY+e^7L;5CC4T?XtcL0dBN*)qDkDPOeQe77SX%G-(WzB+EFyA)h9@h z&LAx5x|R}yKj9og;by5J^_(ZUmvW!ApZgP68hWk$iOGMRm7;tymV5m$js-A#$>xTY zF0!2GM3llCo#;T2xj81J+pYKNf!@YztJB?jXtK<$KQX-PR#$6_$iF?a z27mAcs-0!^{;AkNA$bl6xF`V3TdAnvGU>YOu#j^D^0_5e;kASa8#u?q%cw6XCVqYE zUrcg5TVG5Qilhl0bSCOE%pkp@DV4*!rf=-)(IqVBeM80yeSFv8I|`oPeO>$&N=yum z{h?CCl0~9T$gsx#4F`)Oe#Ry&+tTUwhAWM?!SVgXW=H!o{K^#mn18mBiife|gVAA& z=93XNNc16Nc_?5xH3#)>` zmIy|hM4dtx3glqvBJ9d}h+z!@X+G?IFtIsh!1xL!5J{X@AiMbU zCc4p>3P*l1%7F!25fp5wb%`{;X2|f43dwX5Z;sUT*3fk#gN2hqlUmQWF=m)(X*OV<^vZ73?UWIXd;1eZ}h>U(1VxLAL)Y$ z))bavf%d`Es;sWrl(lGTWBV|}Vq*02j|m{sXd(pAm4N^hMZWx#4P?`mHVc^{y(DGZ zBo-9pi_~8Gmu}$I@6Jj~Pib{+??POsxh7?Q=a@iioB9oK*7=%7F@8M%u;9jgHr? z>OT;jJ0#cUze{nj&U8I!R!-IDTYceQ>iC4<>U;V%t7<&kHmn45@5HJ}{8MKjMlRkA zClXK~P)&ezF`bvp?4HHJwY{62K6$s zsjTlh9LJvOM|k%AHw;7#O2iiq*TY0aHNkufgCrevb^%;kPujWeqYAev8yvJ9za40) zQM|&0b;~aGnI|quXv%eIt&8~YEmN;87ic0y$O=HLzJM_cb>EzB5o8Y|1O}S(a!*eM z{YSJFcAh_FY-JT3J>HSe`0{VX*!6dYgI?IQS<-dJqs;2N*dRMx#Yk!;oGs{*-R?mn zpqh_(XszGA9<2;>Ps_`ute}!?u&-vx|3GZ?8&;`B4WfOM?&)pOGo}7amD1n><6)>> zemDZGVNjHMK2_bf=1<>#0E%|ceQlI2a$I_0JtDoYu%hqXzZ6ImOnbcNFvs*_H<$ib z>fl#3u4z7gqo0XNpS{}rQ588E>U*4#3Nb9m4AN!x)LARqr=8+u?o3_FbCc}tSiV{=baVc3R8vx}oCe4shyUvYb@G(VU=STF3)1y_SZo4qqRG#9Py(d{- z!ib8UBpua?VO4@8aT37ENAlbg$?Rt#m_b$;_OgXHHitN*nbv)3kVB=5v8xv&jx_)R z>e^9qL0;QfyhU?xR5sn2I&&()@#9K@@#PCh(t_}2OF)1dO09tt`;?B8fV$EDSmT9k z_MD~wqPvR8mm=%fI$(%!oloA z-_5Yj8Dr%bafcUKL)ygj!6oB!D&vh}amK?LJ2W2c^{-CH!waEQ6ex~1wY}EHN;zPqc>?wVW<~KMXEx=Nu_J+TK#S+I+% zwdYd9jAJF=NL#LtQkG@2yUgtLHFHc?D|&6@>;!o3cFb8ku84V$_(6Qk@zQOsn{fdV13k6~{D>8R6z&JLFONf_==Uvd-BYtX=e$pG6>}c& zCH%8A58>CodJmX19N2*p0R;)?+}L?0K-HUA8aN6fE|eO4wDDl$pILF3s^YjFNyKWf zUG~ST2Gvlh^eHt|Wa37?Iwzd=*ppIN^dhpEKz4b!Kai=x#>*!(u}Xlm!Q0#Wc{h6U zuj=V!LY|{4?{?|*onNM3^fO{FqmSMFZ^Q(rpVD=o_O02(Ieaca=%p7Oaxh5o==naP z@}ugP2r^-tH{K-SvDGzTVR1tjwb%DorV1?XO_T~cx@Tm(EG{*v zK<{^?Lm%Psd*M5L&QgFWe1guWFTMlB;|qe-n{1fOzBb{YnH*m1@pJ-{oM^Ok^mHrH zsjYq7coU{V&$0`srTx-ty7H_Pbi!mR>qMo^+tyoWvUBn}5a}i*^5%j5_o-UWmtRHh zwcEueVf=c76wKA(+9#HvkW#nA`cF|O_h2XD8Z1I+xcuq(UJ8aao!ETkSLq4RDRGa4 z#G>e;5HALNBz?3zNc)ZNupv(GJx)c6pWC5tQ@m|2OH0Um3trQf8Q7>$)+f1db_s>o zybNsg&U2w8${w)`;9NQ9y(TlcspCeAEXr?y#xTymDXc@lN-0Pp5ELNXTq(fn!07*P z2?cBThg8eV{r_dvYHfrcav*tM*WCOu=%U#ICuUmcXqbTpef8Dh2(%%}_zpQyYS%h) zb?byCW}RGBO+G9ym{*i!p_}~f2L7Jm>i)Pny&EC7V7n=O`B*r5uSwqNa%HDUmR;f0 zg2E3UK=J8$uPw}&A!M`{sQn=oLWcRmQW>WSKQF zz}ic3e#y?%q_i;F?A301O`MlREKJ~5RBG!1bh^!CsD}$5)uYr0un>7P zU4&o$M&Gd~g{gl{-MyWIvuS&K>>(SqsoqqLz9gO}X_9JwE4)#NmID~pXas>4k7>@P zV7lR%#0d4UWdjX_=|~T0ybj9MqFqZu4AhLH6zZ*sc|huV-&aIJB@OURWZ;^Fs(C)J zQ0%7~ph+?eL`1g9qBun2%|DSJf$xtCBUsibhxljhqPQ@>=bYMDKz~Kz7%1tlp`!s| z%BoL2&QCrb!ZN8eGXkKl^zK>nq8yvMhqleppWgAW;?UzIjgF)OlHZyM10~%+N$?f@ z?82P))7-& zxtn78y|+b?%wUdZoM&^A*(|G}Sb32j8rmikd%9cb>Jpv>$9F4Fg)=e*iL8aBkQ~=@ zip)APkW!8BvH_^7Ii07k)b7JSW9K=k5n{1??@xX?J&Sf-3xMB?B%BJwqMh)l+FvNq z@$b?SCIIfnQf7p5s4m8Ga}T0D9lq)IT;DKLgq@m_EfqeVK-bYhsyldpl-TKMMDmna z-})|fj!$ebG5uWnJx!Vy*fIR4T$y@lQ%f%YA{xk~BStmUqhWjF zYw_7)-$e_WZjhfZc1kazM#ha&PYdLIVYkhMGR=Kn13j0o5ZK()0wr~I4leA~&QmZ) zFz8JtORD1Q4feEn|5T1Omes2#WYcuN91fdqiLGM&W`_Q;HBnmmKBviHD}x@iJ%hNu z!WMAC5(LCVc1xmMv(^r2&A18Q*T!JG;w8v+R86M@i0uxWSlB5zjwDEJ=rEUg85fjS za9I+_*lm--R84a>&rSU#5{QC}SV`w%QTA4|NE{EzI0ABJyOHe*2pH73y`HL#Y^4+@ zaOK_mg|8MiDpS4K&Vksf=)F+s^n6{x^@g>J3xGkm%&6%UT;Ow+F{PUHT-NgT@PvN} zbwcc*=8IEPSU~qbu>rxghP8IbnGs{gmhlMs_xn>}o{KzOmos_)N%8urO@ zjGoP#Z*P*30YBMzp9vH<#s2uNKypBv<5fTjU)rD7NE<&u5Z#2tk}T*K4RcC|TGnP^ z$vs8UWqKu8cINSJ_<3(t&RO_xO;I=Fv8OMY5m|dv8Q*|{>sigsY2?&iF(MW!jtg=E zh`4!<%bACwBVKv zIJ=8t!>6wZ4l-S!++GeD28dFu=+9VfH(_`tho^Wd>6uOnPXY~cPt+4qD*r66m?OuvByamK4{%WF4TnncMxQygH;6E{#kYvmBuBBxuYj^KP4< z@dcejy~)7CQQ1`V_5d}$++1SiQBWboWJ|=EoMz>+Hd~+cZ|Lv$b7ryc4Z2t-MBo~6 zgUUXj%LqegA-zS@C=o_dd+uM*&kve0wt)R-6I?AThmE5<6BtQgI#~CvwcxU_ z(MEiNN4r%b*Z@CkY*ID!i%z0BROX+VGgkx_RND(EMVGu7i4Dh7``e=Fo;IfUL^KzC45pg@4Q(rc!#!I?A%9}7XY)f z3)JzUBZXGf>BnD+ZjV04coEi-7lzK8O_Of#qeP!(4lJ7HDT>wZg?B$DJEEgIL;pem z%WsVnqmw5!hEWZARM|mBSq{}PVRAf#u+Z||-ctejbgM2!m}{{P-2K+k{1d(XLqC#i zLD@QgYR)10CzG#ubreO^y6q+KFZtTJa~JJ$wjM2CeZQxS@vU3_qJ+@$CeyZ1)_cfZ z$r-R-^adxWHLoS4hG4=gBDVc7s3@+>X0`KAl#tTBJB zX82X&?_V-P@LzYOj7|UFw{h;4q#58^N&pKd=l`~YzSQ|)i%=r@JlC8YOKePdODK~4 z?MyfpO^$!g46hH1{{T?W3W^Ylxfz;u;+oRenCIr@QJq!5o(OKv@Sc4wB*P1MdA*$X zrBIC*`}Y7mU#=qd5Y>6CxcPCvx)&0$zq#-~W?J+S_Xc))_&NdK>2N(C2cC8Dp?wPM zKTMJ9)8jI0{eJp6I`qq5=IGEd?TBskxAriEn;F@91l#&!y^E#AfPsk_L^kTV)+VQ*%&@SJVP{{>(R13nr(mV zGyR5tiC*HLK!<1E{(XwfdRffK=61qdf*S=X_Eu*VL#Syn4y%$R^+B5s(2-}4j-DBd z0?*qLYrO{D(J{K!5fxqtY=d5sZAwfYFm@60Bv(B?0uBI62QL*XtT?*nzI8vfxkelj z+Dq)PG7DxG|Hgn(8JsXpMJ4RRP7>J37e1HSk6zHVRT#e4O9M7zyai=8` zybhYnq88)?nvAS76o|NwU9^FX4Kj46mKR@-G>QDem0qIMfRuC?X&liKwg)mj6l^>v zt^$Y5S{9J32(#p0V1{YYN0%IOSR`%{&_~h)Qh-6$P*(SwDuyrqw*sbLGIZ4P35AVd z&FR_$9Q>t@`fHnRAl&_m95Yj74$>g!4%VjNZZEmY0Go#Kf%Z>lH}4yvd~NqPiR?fj z7j6-Y)YunDDaeL9AIJ^17dLcbvfMb6sS7iJ(*uB$;ujOBJT-MoMopx&|Fx6G2ZrY4 zGq!y$gbXBmtXdBYOkwpeHESCvx(r10&=3F07a1hx0BO|UE0_ZA2BH?24upsxKupBO zQEd>nE_NQCL~lW9P+nZ(<9x^w<)~~rB8}g1Mi<=eQRm3hepCjqHZP%=o})-HXGPuW zXb9Ns2B{IO2oz$dSJW0UC7vxRPm^;gL$DEAJ&A2=!RH2xgSX!jjK>}Jr9ro=^+s~4 zkYmf`oedV8O-uxAaz23s&<4u?QCE48(%j4a5;eTd$>iF$vXh+Bczn^i<0 z+(IzDy}w>CCq8^w6HxY%oB2rZ*Y;1n(fhYb)bg=s9B$tAoeehw7*@|0HmM6}2+WV} zSf@hQzF$l)+D!_VmiNy~@G?TBO9dc}K?^bTmZD&Dh}w`A+(0X!k@>3?sHtV&1iD6K z7=TOs7I~}cvWcyM;83bl1ZVT|PdCNqs4awCE5Ccoh8U`PG)MBz-9_bzgy;rN2jRJZ zz|mcLu@S*S#JLRt-6|Oq_tRTO>pi6eC!YBB@7J72zL^92#nOb~`-^3Rsu%z@$tUKp zX33hAqKP}EMs0C!i(ZUQn-8TL7GMT&wm@1ft4$!1F0C>z$>G>^1E@lI{W&Nhpz&4W z!>O&)-s}h)qzBfEvIqts}ggPfo6UYnDJ*35VTdY-cMca;yg@)?zO9cPq; zMJTh&4R|Qmd+>)0p>W8^5dbJ%HU`Ad_0>T0G|>mEQIIg)p~Ty&t(vo}Sx{f+`A)Ar zQij)$L~=+)DoN+hNU2dlMXZ2b7i=GZ+VV+$G*K_xFSs@7U!k&&q~AIGj$PiMrv}BK zxvzD_zyt~L8T$)ajJTeiB9Gn-^oY^eCJn5Mp=Y?ev^y?fL=1lhr3HAQFb1k&=;aFx zVy(1~OZ7Ms8khHX$^()H0(Mh?a6O%}IAzjZv>}%M&-xwic6rA@+!qaoKi8w~Y3y$ z2e--rGAl(;54$8VjHS>Ffq96{FYv(WP$Y|=jMNg#iVMgy@mUl`*zmo+)-JPjkzxer z{UJ+CEG4wXwb8fYTPyw@eu8MOY5;85JMI>i!eaYWSN*gW z_z>A@?A9Qj9hx!E#`_Nk#cPOvdJ6>C$!XXP*YVO1f3fw8FvU?YTFUGlgLnH$DsDgA zQ+7-AGU<8h948pfVXzc9v97r3bnGaedSU*O=nbxBv`lY;I?0mo5!uc@1V>snvPwX}bh$^Fw*Y@ELWN*KF(hPmqt zwyW%-^9+!R7POvS-R$*g2_ugAp{%1Bz1({zI&jclYv`+?_?fEZ;8oSDEwDT4w2}HZ zrde&+fubLsbW3R+qU-w-P^{s-_?;=@PPM=}$7ATMk~3?~23B~Cl8}hh2Pmb|>Z+z* zWLg*c5#1ZMdfk(*@uQ`@hmx%nIQ}%+qu!G>o&)M6mE!4G7MrPwz9FZ6q2k^M7OvkN*kU9~$l50KsKo z@{evMAj2?{N!Q*vAWnIi50ooL6IFp2%)5O;z*e-n+gwXhukP$3%}$r5;y4n(7->xa zVFnZ|JOyTEuE8Dz`Qde-ts--&hF4iG3LB0*)>ux};|b9i1y#``xVc=129Np+EB`i> z({miKMxXI6A7TxL$P6V%W`XX~xM6p?Az;B_IEoIE8@7SnN^su2eX_gs)Jb8cHA+h? zv!(lkZ#Rx%`@AjGBxCwz8zH>1*NlWE%K&Jg!ANVfq;lG-ipb5IG~GLc8ZSe=52)Yk zhnf1YMc&)EzRhrbVb(Q3CeZbko%ssyaP_~W=Zu=5H?e$~hSrVCQD%5}vvbOoZ()h} z#R>}!!&FjX3ZgLmkNS1SvU#uUsHIxjZQhP~vT#@aIlaU3-aX!mM2I8=+AS}K3>=W~ z=8G0S9cW-v*Liy`1N3b2+D1vuWk{<;XWLg`=|pqB;Cwi-pwf8w^1?1VC7|hZ#Uop$ zHrb8fR>ft25O?Vygz|)X@`IYTQkp{dL)$Hg(`=_8&{fJP%y@t0OBD~e==~`!LV!5L zPM7VzBlvH>a7qm*h}8cb=86OZp$4#WasTi1_(*pxn!E-62j*&>0rslW zB`1QK-D15w1_M0=t>=Qe_>Y}iD29@Dn2Yq%88&3LkbH{9q7zkIB2`lGPU`nN{`0p6 zr5)h?^)#hKkXc8xzvkQh?VQl=`*yKoDUS2=Yr4n8FKefNr{}{#8WGU*_44qEc=2=q z@TShR9I(UXyro8aoY8R2l^CfMoKKBoJwWw4``F0L2pXRcsF5j$$0|z7`|5=lltm29 zPS_z!GzZ_93se?dz_|yR!fY*I_xSDNz{r>zw2qU{=pav~rED>sYvZ&mdN=e)R!*Jv zWd8k}Ldo!|dy;{k=LP`yNcAlA2ndajC4ww7gmr#3_r;jhCd>{d+q4KiYIb-*I0fEX8`nQ=biY0``D*@7L#rV@AYrm16n?$;lKlBCrlj zUg&_@QIxHy> z+y{Np0Tqx~=y)ygRDVN|7su_8dGcL|VnUK+Kb61J0Tpb)7^}59|6iWJ1sf=d%#Ebo zDW-+xGlHl^fUL|PIf4R$$Z2Z%rAOcPjGK{Y8rM2Px`S239|Jf>)-lv8BI#S|J(>aJ zL$ZWPrWkSTySwh>6wj#ER%W;3!Ub&$@%eAEvdd}qV_^(WoR_m{y5}p!BTOq?bA=hO ztX;$@aL1ohX;7S=%Bv|BCQXy(PEtxOjVwe2U6&&hVAH)L50N8fia40x!$&S zj7FO(eF|HCfKGAemQeb2kh&CvsHDpCEDKSEk0!Y(3>&+Vm!{N++cu-rCCB}?Aq5mw zv;|9;n0NkLK)F#f=-3w&sI~odbY%=j)+@D{eZM<2OUv^H%ZDOlTM~Y1cU&9l4c;ai z)V+x;z~4nx*WXfcy5BEm&On(nl_;GpAiNRS*PdDp@ov)6TwDzc&pYa5k3zlD^Cd0e<|<1rdZ zaBQXA?mGx!Z5GT;983^S?nd>BwA^eJ6pIv_02`{))N**_OOAmtsg2ocEx~*7nvU0F zUAOzo=9QFk5PMyLVWc?JnQT@sQ?)j!eC>Zz?{n_k)+c*Wv_sD0RSti(pgsND;qpiz zo&{D+lyDZl2=i+|+-YRn<4U%WE)6#J!>^j+Ef3g$x710Jn1TSm3RSUgzmX-ftq)rY z1nl#mtR;4j`CtnqE@fLR>iNRMr{hWCL0SK{zKcHdRfAktP~#<;OV{(wW{Xvm&rhG{ z)I6)Jd=f2t2C=c2Jyh5i)Zo=ha8rS7BD#qc;g9&KPUYqi{}d@4WP09fZ`!9_b>XQZ>Z^)Yt`L1_q274;9wb0gQ0 zXeVfd;Mx4KE1KUmx4COU5e`rUSu$~@kr^eB5I!Y=?!(`WkcZ}AVhb~6L7H}9NsU4b zH})c)hur-jL+lMI38n0&m!B|@Eb9=mUC^SaQEjg_<1)o^=9Hs1(z&S$7vc|92Q1Zz z7D@9n2U8hDnJzFTe09}Y(g$1DuKwG@aSvUSH;m~Z(T?-10Eu7QrV6QhAKfI6^C;R| zTl5@Am?(rpgvm?A9ZZ`K#eIE$P!jURACDrSZ@%}!^j~~C`f*azyVoFE>lB0&z$Oqq zr#b0eD^U*znNma^V*exB4;}!j0Z70X<|;Obu#q()mui#)H$|Ph;%zTFm=?92y6X>4 z2~y6TnA!FmeVFuk3p1S(KhihLDwsj_Y53EDu0-&Rqd|zz0pG9}US`um*Q4%QE(?4t zTyWH?(>@~2=y4)Q8m0q%al3J3>TZ9fzq z^L?eE?=tJQD4atho;0XMGINK}i7WBZgF>QHhrN03oS`{%4Dr7BRgtj4+b?C<^59u} zImtjj?TU^Sj20V^o6)IVl<9?M-cxJ&$Q$~3FVD))&}7r`G4EUVzDWY6=&mtfsRqIp zX7TEK!u=}ygs&+iD3s4Wnp&*t!NE@=Aw2I0bGf@^RtDJtTM z4#g|pOc|VOjM$R*KLP*Q9R7R%4JH*g3a}9e2V#!cQdFb`VhdJP()8Z|36-A*l=`XS zj1xI{Zddtj%;sV=aY~aSH~u%`{|xamHiER4eZuY5^`8KFT%nD*^#6IuN3wikU2r`G zr^rf5@o694{GuT(lAkdOT>j??){-V70M`si;n%jVLv1~b5OWC^rBYt0JY2avhDFTqY_>ftCwiSInHe{qcd;P2x=w2I4R#jT}B>$WM6$Ads)L z%f;*_X`)wVt%P@ye%K@ zMa*1)C-76HJ5)61D(RmDjWAsH`rRw`_-l5SXr$j3s}kD3d37Kf5lFbO9{X~$&l~7Bx-4}Pc=64HTt?-1 zQ)cVo{C$!0zPp*Y4NHT)lAm>?oQQV#6uP9c;*unYSdia>7DA;@=i!|c@EC%}jRe=X z*(s!VG?npC?etaSE13dx`!dT_ciE^oaH!IwxoLq&tV}&G%E`5xnGx~ut?k-!*tRa&}^liPa?V%AYc@&Ci5y9XgqM0XazK;B2w1ww$?)CAKm)ZBR z{@E9(?6kcJ$_?p;Z0XAkXhqsQORUw59l5qZ(YBXyHg5F6;Mxo1YuXG>*tYYEXz54g zz^~VHg}f>F6^>#Q!^hRu#Pm-;f*}Y0`UkaKg{Q%IMx8?xM#0aMss{4b&k_9>)E)aL zk|)IWUqyuE(0cvw7o#y`OvLH;0TGJ(yn)Eb0gPFdEIOFP zmOlS1|1phFTltx>MV`kssSi(fj|5)GOQmjL87^xo;aNl!)o&j7Ivagmr88uMh55xw z|GFoaL?Jd{`5ui7q-Y@tWT71Qs%rx+rPt zXO6E=+kTb)o7ro-5owOx{Y^(mJdv#t|2P~=LD>H@K}T(4KGLNK^{N$a%*5=B`-Xy@`F>}*`4Qtzu2Zv19W3N@gQm{_F1Td4s=+vf4h7FB6VOPTMgcbC`e~x2b&(+ zu0ovJ&Vy&hW=&gxO2*`=;6fSCLn@4U^fW7|i&^^Xl6M!)0>yFLSd^8 zve)4QVRN4!2RR7oO0mih**RpTj41L`XdR=8g`BU~VAXe__{b8wwolZ*EhE6kYt9u_ zVy1il=d%DE>(LKes;Ge!u1rPm6d`vrReN1cHuq63za~%``6eJ2gctSd!L8J7(0hFtEqkqe%8=ww+K&$n$vS}eqMAg7}N9O$3qQy)>qU`P7JVm zt>*2W(x8#!LF3J;h1}#=?$z^p=6}`o> zrimVto^Dk|;_ZA(O#h6SvqXWcmU{VjEwpkV&Sc*pjRa9^R#m5g`w7(cyX$PzZfhDI zvdU5XnRLC|7)A=oqu@&ad)g07#%~O-cb8$bXiZ!2eHCxBudCPelJG7w2UC->}`y=*?!N z?yY}_-1D#Xkrhy{@x7cj`vnMcWtC7J{0pxT68V`)LU)fPv@X|VaRzSEkSM3Uaeej` z3ioB7`L`s$dOTEHdVD-yA1Ey{RTOX5WB!qLyU^F;o?=Uu{qk*@WI|7Axjv%j-vG?T zZ29`WenL9Dy=;BbDRG_HMSM{QyX>g(4|zdG=?zsXEYee$S`b;NlS|nmVN3IS8_(qA zbOUZor}p~+cNcf^^7YRob~!yfRnstzYM;AX_5f6&t>D`6FWn%FAcpBLR=wn(UR|0y zSMk;Bt6w;$d6z?9-NGK75KoMc@_?3^FYkCcS*0mC@J^+PLsGrjg!;e6d*i{RdKzSw zMJilp!O@<~VVa((GTjE|hXEd!TPNNyM7gN+RE(A#baMQ5_*ORQb!_ZSG8NyT{_gQ+ z&Eh#;^?1kI(eNQPSw{RJyVepdqxuNN39Z=X_`ah7N$*HbZNn}<&B&?X699PkRVsHq zS*=@q`pxaZc@|yUOepN~%S@YjVOC@bLxT!o7G0@inCVS-5_M!o34z87<0-!n-=GYi z3MH$54`c;s9aeGkMh$IL*y3j94lw>bW;q%M(}=+?S55fWxUwweCX36|Tv0QN21Z&- z-6X^rPr@6L7zIGqqj>2vA8@Njkqh1?x7I3Jx?%5W20{yqP9|EKS)$6>k{mJaz*2xF zuB}z?qJeY%Vzw}W71X4Rx+9I(_YT}Vyv!Tx-h~Tp#V>_;rhG8$$Fe+ zHf~Sfa{THGiK#^+o>gME>-za0S7vAm>x?^DyOLM3CDR~Ct?&@c0A~4$2r89f_)l^i zj}$_Ds^{62MR^a_Z>iGN>ZgrH8aOKk#+>(F25!zAW(6&mNdX6b=5TIvN)Np>Fq)cl zAsUY#d6$$|VZ@dRf?%B7$_>t9jgPe`flJ%#qIIA{#_T=4O1ghUYFmkdM|8N=6pvDIZ#|OS2>8 zsy{kYz0laWn!a*@zD$xajVhS+pl!Va zJ8)h@Eg>LSc|O1luohF-94cntVy!SZTCfaAsxBY1tfRXft!S~w>P;9ZaAC2k2G`9t z?%wODfy{cMm~XEayB}S6qdXpxsq3iEZE!?MAa3Ffcmb%s=p?)BIwHs&yJ(@8r}!(S z2I>hg0VRCJ;@Tt!mebgvC!`lukqzqHmn;NeWsFo2UPO1N{Po=vIEZpJLwkq}sCa0) z%V{{nVFW?1{%{IwQcMpqf;PFBoMJyiT5yH;lIveWRG`Z*xFPa16CEV+)i3R zVem4K?f4ovcvb6`pq23LbZR)H#99u6{-%!EMyf!_jPL&!ei(H<iF#) zME2j&;VY_``mY)eu?6x$6R>L8xU^d4AvC7`D{OI$TE(u6B|rw<$-MU>A6u#!NJ*E8 z^Vrj%slC{)B+A5P!KKbBDU%h>PjFGNLb0y6kql>b#HxbDFt7?8?4O`r)sRbK;%BaF zKox=25sPAD8p_Vl*fpoQi{%{3S_ws`#!afP@i_mtNy}At`C|o8&7{kBxFbw z`QW1V#!LU}qiFuERnGXd2}=ji2Wc7dihfzAa-gmwDRIW3_yls1p+YB;4IhE+FF!+~0TC8h@}rX`%R1lBsRVj(%O5((B%=dRm-@}M_^1yjGv2GMk?r6*&v4onKzTC^Wl|yCm}HO zVhuLPmBs;{DblT3lJ48vq*4FLJ14u1-yC!1vOPDWlG6s!3=`sFxKH*0-CQ+#k5Mxu zOH^M;@Wcj)6T$c5<3@gTHFguk%> zMd+C!I!X*=Fx*6~WgEa5YJ4kZ<7oRlG^(7~H0KdoQ#Dz85So)|0-<)BY$TBG4^pjer)O zERHt7g9IWBh8ouF)t4=%3H$n&A6(zD!Q(SjMz1{(?DfyqAIO73H0odYP*4g+j7-^Q z)yU}u3#nvfoeg0ZENMM?Es`uCVYTnrr&J8W4o&GXUFmo?oaK+8wRKIq%*|8MXI(&D z?e4!5Vq_@_ZoA_{Wjg8|JfUW+?o=8GjF`m%yu;;lf8LlXPYVk555F(F8Bc<}^ z&S`#Q!u~Vo`2qXsv_7P5_4uHc@r!M{OrzhbQs0s$4_F#`&pHj~)<@B;M&uLW8&H75 z;&Y!!R*a#CF+y)CsaLgv!OH}-803#x>xsXlkiB~}gJf|O^wqzeUE7M>`FSH8tpk@i zGgY%Q#JRVB%QmkoMfM9$1y(eOS$hKP5}Bk~pX8PB3pTXmAGMLj;c;^pa3((%3)=XJ zfIyMm!RKhkbO6LLgFmAb!)07fkm>=(dojoe@9=w29B_MZt-$dUXUX?Z0_KLtih+j@ zoeh>Onx`H;aiqHv%XxIDe*>5$jUPih$$Ri{_c^F zwq~fNt^oz!Tz+0QA}z_yW0A+%L#Lf6BDnKaN+dHIqZ;1Zwbc_O<}0<;t6^}kQ&=G^ z@#Z}ODvK0y!FfQ1j9nnxeQSW<0W;32d!4zvZljMtH^y#a#BevOl8B5@Mv6p{BA^f- zMki+wK7WldCndWzbs#iVYuHK|7LEo{htzmU*n!D76Pa=Q7fxLW<|i>sRAB}u=|ZZF zY)x2wRi)2vDzpx=aXTpL%acApW>sJ`RWN@5)k*_z3(ENf>z>~N#YzCMOjxP8q4Ueo zYfBlB;Y=`i%~&IzIFKN8r>N)xBkhL!MKDj9Yo(hXaLh5#zn?*Em_lOang(u~pfPC)|c)j8YsiCO^KzTXj{`KtrtHsFtl zFJn$?SJxhwEnl!aZzp6+VTR_{Jz?_m0GJ#Qt`D?ZpOh7N$F`-kD_Onrhiv`v{T_FY zQ{lWL;pbCxoEYC^1udzil+x}(umL^BLcSk4Z?T3IVj+QVr8uEmU;MJFbdg^yi)jLU zFIa2yyu8V7(*VG!+YyXAH^Gr|~5@G;+dR0uxHq$A}x=dWB?e0xd zS{=($_1ynzF5!Fj^OSq~v2rb?K1RM^t7T=D#W;{bV;pY49LI zH{vWl6mXIy(N#eeY0YDbC;^FMP%*duk*x-R7d3on)Y}B~l7Jgb0?HNy2{LRjl6b`Y z9q=53Vpa!=)p6lG0j2Rn{MECK%iZ-YO2^1SwXr_eQD5U>x1!nPza7$*D>0)*e>f#G zi{y+bq=NFgexGZBq#MeRMt6a_oE7~Q;GUf274i3=MyR^Yl`6rF#_+aJd!>Mq2`>l=>$rYpV%0LsoFNlZbZ_+QEVe`7|TDL|+IjI0d* z0h<5kE*-DsAKI<&yY!7iIW|PFKao7XazB3(#16uPQ2J$kLG~Agdp)pK(boN}&`gnD zG`xw`m36&?yaV`de*#?5VtRZ$UoR*nU@;W0-}tjXUqeTFx}58{4rRYSYpsffTtA@z zpSO3!y6>N7fcY5yhLM`Do2FlemF^sN_?ea{<*%emcqERdYPlBKaWK|8iPa%Vb2Kc; zbl%2V7CEz&IXGc7~VuI+t3Ap>%x83;tV!xYg8%Bn|8h^t^*Km~Z8T|nE zuhhL2^9#BF3Xev?4JId#jLz!|(-W{m045Axg%B#<2@>FlQ@l>GU^Y38XBYaJWwW@z z6orH9C4-O2eyeuOvhGh8uh-@2 zBB}`H;@}>Z5mO$;tCw_aJYkB!pHGNr?&1u5{gh@#`C}$!hOWv+O6Zg_IO)bzrjHAn zpk*-D8;y^1g52=8Key91!r%`qd_5UcUZG*H4HL6z6??AvSazLtZ9UID3 zpk1OFmEoe;@9ECLq~^kD}B!`jrIsS zfpVyV?t$pN%-&$YxgxTpV{E+Y?B3?S5{kC77QExPmLKk3l6qTPl7p`gpKyhlDs7FP zk*R;tqLZPFD(w$XSJlObPb!#aVfu=k_GSB_qR~q;;Gm>G1`!nH2XO`w3l+?e>C#Uo zl3raD{I=BU1tF|L9B0aO<~Fz>0xZnFMoAr^hMwHufk#cs!dN%A~Kf0 z&JB10WM_quq`Z-inB~QILllV5SdJ}`E$6^p~Q~1$V_lYBQxnN0&;nz zTJ%iO`JuH3F1nLZ%T^n%Q}?mje+Bg1JxEeMbbs0?yVW~Ela859%auA$9O2EPx?z@` zzMC{oA)BM~;B0u>z?YST)3b)MoLN_-t~@z|!oXqzT#Rn)$ZW+YYL3hs=Fh+#5tZ+5 zJ)Smt{on+rFT7wkr@>MVkqXWfx34vY-C_updKvWwoP^FBIkpyNZ8FXE#+l(l1Sg(` z9BiQ)wH!#iosx0rXzZQsw%GSDR$W~nNBWMAfaj&V(1R|}&tcX1zssV7x)UNEe3XNyL&8x=*5vK+tEl8a z>d=~?u3T)k-2f=(Z}K&)nn|t~Mp;Ro$MJ!Gg5aRx*f7M(@4H@;=OCmf+)Uw8N2nn; zRJG_I&&DmGX%+979WE5)V%Bc& zYV3o%uTaED9;}9KS?7N9^K1GKS9?B7brv<<6brnxwFc*57tUb$FE<4722UGxqz8ai z-g$?grk8GzzM1cA(b~&1)_S!3)g)yOx9hcRJ^#d14%8nV&qVh!HrdeRQf^xzUpwHM zjWzgQ>VcF7_9S$T*STALHIHA^c<_!;)`tpYB3O~Ssrqvr?34ZLc^%9@f8z&BW6Ghw zDy2iF1XLlMIRBN+3YwD*;xlit>_`AWn+q0Cn4OZ`p~2S|pI5@!p^d-WV%Y!V5yW

    {JP1IJyeDG9EuJ$Oc-G(qw9GOH%c{hpEyRHl6^%=0j^` z{Z=Vb*SzCYD`2>My#lf^$*oVB>cuvZUDd?Nb%~X&!~TxU>!-&eSb?DkD0dcz;Nhiz z-5H~|pM+g*rB>#`e>5oOd2pF@+A@>DlH*Z$olI=KxF~`P3X=VVjJvkZ#v^G2!W7}qL63@1A3MCZ zZfl=%Mj{?+Iw5b_Ysi8Jz;{sg(dcrrlI2S>%6}U<$`)LEm~N$G~im#e?NZ|QFPK~74- zvvr4gB12?15-P@RKuyv4==J70O*Jl#`&oocYMUfHUb>iikZ`}O#vTl;jf&bmu0jG7 z<-^av-2osIV999i<5Q3(p&XU=Qpfk|`(VL9AUUXtFl+-TM^kWW4FrzrRNI4A6MNwx z;gedZ+-x^1_q!HJIb2FY?isHP5B{%Z9_2nyAS%Y< z?*~xW{7I~Gk`eovQf3>-uz&v7W_C=8T9A#o`d@2XL^$8VOozNc1uGrV&TgFobwHbf z3#)P0lz9(AQ`vP%jEUs8+3*9CP*OK^om{6|xX>u4$S)jCE7H;L?)v8Q$|zJE9r33u ze}OWl!Hy-Ct{3i=&g+Iwnm3*X-^nyUy2zxRn6>plTm_oxqWjtytHX);~hnwXvYdoDOi*8U$EK-+R$as!imK1kDEFgV) z^$J&W+%~GRrRT=4#0Ri{ z9E_dZ0kZhcGaqpc%|1pHL|Pnx`=8kfN|LTAdqwZo;7F`c zvqkT9V_+MGRFkr+HQx#gdR$Q*KX1qVtTEdBsxTRe2!cgS7ArE!;Fi;kB9wddqo18N z-eTTg=1f$H4J^LclTjf9&^m8~`6Q~$iSxARGSlX{%i^`?Gr@SLO&t4nL%GNuaHp@y z`C$r^vyWoT1deOWtIFZdgXS8Ek-2)gI)jt1dcWEZYM!^yI!2ab&V^mhJ8!juxy<54 zid*5xp>`>{LoOz(>q`9jeHZgm8*yjdoxgK-;qi&TRU(X^v&K;fa5~Vq8RLE3KcW4o zH=R1c+hWNa)O(vp%X)f_!1H+gGoy}Mur4Rk^9)>$Gd-L@md)QI(vx#(d5}_fIoEREW$OQi-|XsdCC;*yr%v=@isfVTE0@S^`P5&({mp# zDp9$rsQF}U^Yq>hz`-+6b*tMoQGy}ArxfZx#wgxhaCUEP3FSt$ZVz;0dLVRjibq@A zH2#kqHBLm&PKt9@X0JTHZ+$f$L5f&P=D8@;Rp*1nYG|Uz3;-G1P%JN6U)zFUqnQbd z?dz*`^b2Df#iM)2f0zNqU|bM_qGTyP54Sqi#e49ZoI47$oQ#MZO5$2 zuv-4W3BRe)VcgCP^VrH>O(X|APsa8Ded7zhI`FmV@Q+f_Twa^sLC_G zEBasj-@YnQT6#Wi@6VKTG3orS*Z*}6u@2yIsly&0?&1GMmI;0ELi_%HP@)Zxd4Ih7 zK8L7VpZR*2`eixfsomD*P%LY4mh;E`-!=WMKT|3c1YAOr)@Yp3QM#G+$3$c?nz%{iytcuaMEFIfTmV-*yp?hakRAE{y@56TM8K*h}^^3g@LgLA2Nk8R-VQ7 z!9^L7&3~Q)e0_GuX@s^a0Z^dt6Uy&6Utj5ta>F`QYo>MQJ@`|pEc|-iJRj~)o#E>k zGwNxf=Z`}(RK?zM)l!???;nri!;RNHb6;A+3)bUann|}kPyFBgZzp#tkhWCw&0{1> z5r|Nh4evUuG>Q@hwRtjG*;Gvi^$Bazm3r@6KkLHcsZr*M_OHSK&0;JdTtxd9gd&6G z_&@8@izcDz?RhDc*b0D6*Edw03y)iaJ%E%5;?-Vv){@ky)l774dCQd1i(p94?sYiv z*2l|qw%MnG7@n3>Lsw&+f$t4vSu*C>78~kt3pFbV%;cBI)6A5uFwC@5Rl93lRoCWM zvkpm*jkiIwCzy-@i$@|T!Sd4xQ5kh-pRHL=8k>lvLqP!7g@y=-fmYd(vgYjw*e_Jw zb%)9*sUKw07_CDkP||7B*@ws~Tzy9qk`XN1{Ta7IwW>9FEf%yY*vkql0)z+2Nz7;N zbcwRTmRj5t3HP4`NLHX@zyeufX8VCyB7({0@p1>h&@;LLHbLX9qE%AprO4}6hRJV> z!Bp22?zMC}PIUYJKXSJH?+^Qa?di(k!!g=Pb}6Afw+b=YuUCK97~c5pmdP-?)2$FS zY0Faff-e#cZRn|U1xz0Fle9QiWmkh)fMo>5C9=a=`9wC3c_UDrY;3l3&_>=n zz2D}}8H*DF1Y~3|n=t~8VmPc57Wo;oOtF!>-4`Fx<$2F_E}}jykH_>%31`7R#Ykv@;n~!?^SvBGFp94i{;5H}hS@i#M9e zB|TtN@APv?6)yt1TtVemFG6qECWo^?J*6Md=V!_QycwPOS{yBt$26Wg;fTiEGhhTeaRQ{c@GIyLKUY-rh4 zmqrT#Pk`v1K)^fG7&BlHe4g*ts~V%^W{G{)Mj6!Av+SBIVZ=IVU6(d(a)6R?Cj1Vr z7#|#fNjo?J&rs+^_C`(>`}y^9&XKLdcZEP(7JC^P$~@gfcNrh(T;!y(?AQxDJ;Of9 zUvy#Mn4d?(F_QAgAOh#QvCWb*??1%*NyPG3(aKb%3dP2}L4=DT0YhT%0^Bx0?n<4! zo%C{87fPB_+OvZe_~xHe84f#B#M z?{N6IRIwmavd`buOCm2S5#!=&r-Z+~SKS`%34Yat-Qn9uO)-p9^Cv6CvG2CdP35;E z&l;`+dr4j*`RJRF-Q;d1^ZRSslotnx-1W6><^7czuupIFRb|o)*I7fn(&4Tb9f1UZ z)O}2tCp8nnuaM?hnw!r^Gwq27l5O^=CGx6A`^8;u|5iaygHPi0d>6PkbmqeOOo)#2 zr)F;0k@E}hsddW%CI?0CnS1`4jdtk;G<5~u1V-~3I~@{z=X9&d);4&3ezN6}{L{{=~&FnrEmMmy{2L@LJV8t)&%MNf*f` z|2Ag>G2e-iL~G9~4wO5Pmoo9$B70d%!(SW*Q!XU&N!g|s z!y2|>Yqr2P7Gb9HIQ~s}tS;gJAChWN+uw^J62Im_k0n9BaUerdGxfE`mCYiCEkJCI zgY_j*y=#Bc+Y9)Rm;KoWt%ONhPk`?Wfwg$UjEaoYIC+Pygked&fV8ztIRA(lJTx|6 zmd1>-{t3}|5DCwK?-jt#U5t}ZW1`*UN4zAf98*US!luWEx)SIfMkWOZ%#iD`DP*1v zyQq*4*95yVG-g*c**c+U&ESQf~sB>5W@U)DXa8p6aIJH*0{JGNivc&sPv3ti*Q3zi{Vbtpt{S3bj z>jdS|b?dVqSav;S)_^=`p;ov(ma0PO&bL@e!M#$6DL9D6B{4S2p%fQ0w8&=}$MK&NP`A%zC@rgxG{-eN)*&tnS znu|f7{C#uqBf5qdx|yGAHn-Hs(VHs+w`lfHA}UXgm1E@uw=dh#n#m%WsiVNYjj4*M zW1_9BOim7z02AjUV77>w)B6QrMJfym5+aH=4|-d~0?VC9QRZ=5a6);j&&*qBGh10Y zelN1)%-WSFBPp9G=d$rq1s3GdyU4Lwt+h5VbVJi?;laR8R4tTmRf~&XZyC{P%@*C6 zgOTny$z$2VA29n|ImGkg%qBmar%3fZZ}U9R(hPtBGE)t4Hh1zt=>jc4_(mOxeL3h8e5W-hLY`82*la zIJ*cq9iKYjRBa>FwcYSaA(Qb`FG06uZHUnyzt9s~i{LIE2p_GM3pI*O>2}@f-MmS| z7;0zV_`&H@XN`gW>T~}Vs+^4*cPDWXHA2mbPj3Gp7YX$I8@N)Wa_k9KrQKQe%VuQ= ze5^!t#9+Tw1MF_|E)Z!~_4|-PqwdEid}kM6=MExTOp9r=y;wS0Hi;v8>FjXcT6s1n zA%Xj#YR>_Mqji~Qpc$Bw;QsOYW&5@(He&0I^q>Lh#lb_=&%=;Ge#AY&%-()SRBocd z=_DX@4!pLH$4Il#)_cCCcIE5IlVJ8N3vMopuUou;ZF$;K*U(J`fJ!sY1Kyub?b2UZ z4SeZwou17!U?4du)Jv4h(yl_2QVD)*ubu1jNSf8}>*Z@XPm+1$nPg>Cb}&>P+~FDh z8ptTorAd6k`W>87I}Fkw=}VyrC^0w6Ydxvuc(T%fZlO1KUyX3|ytL+I%rFUzckwLF zTnqQ%6C5Cc*@4oeHD)_2lI#1S&^Tt$S5{uO=)JhG0O=JNpZ8oENr8T-XhyMNQVinv znwECKzKsE@N!sxC)6bO(o;jpzPqy1&Y|*D48$v%OHHzxhL3%Yj%^5;y5QLLgMhUZCOf zj^xyu$s8gKKfZXPVs)55%^+vPxX(B+1f;`8h`e6hr%-zn0?54#Qu>%%yjV zjXy~ylWUR%$PSCy&p$xfH2o#s>6n7Wu8db3Q6IEj+(}w4b7730Eb==| zJbxIr0h*jb^Lx!4+Uie~^cDru`BKv7bhO%g>e(_5RnWFB44ca6!*B79xP6Qy!`w*0 zM7bsHtJTyItuXaArV4EDT z9{B9(j*jz;KDc9m+h61zN`|jco_yq;tT%>TjX$7z;I-k@wBON>IPZlO7 zy6>!ekf}9? zS5}2x(eSlS2i>Ao<*^qFeRXRANePX?V_MDO$ZyTtAnb{lq%O2M0EN)o`DZM3=~a$X zAZM(5Y7Eu}_l??g#8&dR^Zr@ffNS$F(&MS*ZpW*&+&m+N2MiUgVEu)MAZ)nkZ#s*% zLxAOlnuYyePXFz5(qH3udF(2n@5DVpOY?|qusLh%Z+oUkZ%6?=G=1I7fS3mIR`K?9 zmVhdU&PZ?8&Er7$Ax!fbACWwgU!%!?WcAfe-Vh(;`Eq~1Cmssa;RASm39F8e-Qe?a z*ki5U7u%Kk>ikGUl!QX+|4_RL?QAEw%x-!!yh+1(+M{BEG-m4`6o1+~l{)q9Ax-rn zH+{|is(zWcm;V>Gi{>@&o{W(Q@99DGFc*cHL7n;m9y4y*f zxYH)g&6ehyQkjChdOqCA7&$`P#U`@B|3yh?7fgu3!B>vM^rzR{Xa16T7)Wze@&~nFdfbL_*|m5 zd50ws>(5^yoIEvD$W!gakx@c{C3UaMZ0C*5CJHAw{Wc3QhqyEL3UdbwX=_k=>$joD zY}w+ar@&(-(B2s@b+zF&JkemhWRVmaHbP1j8ZjzeLv^Sg_>XJMYEmKkDjQYfH#IU%CFu6Rl z51s@whv2Q9Hs;em#OfV+#%p^z>Nrf{qAy?0HRcsUBXSPG_Z6U3L+njzTMKLZOOqlO zED3stl;c_%;S*F1L6hm3T1`9G*`!geMx=yyZXh8l^FtPd4^=CFXgV2Sk`kG^`{96= zf$7lm%K)l!;fEO681o|(`cNh58BLmV>2Fg(5E;$oi$|im9f7=S;nL`*s;F?{_wZ|2H0w*zdl8A~ z!O>%Bwl<34^#Y%d+vCEL07GhdAW;&65w`oc<^keDo)L>#8WD4Yq4o;>ArPyX9&Ek^ zf9qYKl`IfzFzd*wY!BA3$|T0vn=a2GbY409^Y4cjPvxQnhPVVyH(TRX_158Nz<%)j z9%FOg?r8~RmG#mUNnI$8nSejG=K6IZxz#H)g1;ba24kJ^*e=0PBIN3@3ffiQCR*!1 z6b-;D4V{EvV!3cZGVBlMqvOu4Y0KJ0N9TIX#b?siSZ`bw4M5r)F-0K3-&V=T?t?(* zcKx<+Ys`OJf*k&)P0=lNlXabNHP-nDNArFMLtkS1Cz#CYzk`X^2LF%#I0MvPQ-ngZ zkw97+SDClbbAW;DydDOUn1^`2bKN6r3(rdb{~YaK-~+rTzU1UC&`-`ch*ZVdg{Y=A zrP9!*1+fe%M`Vs{T5ameGVu>m%cB~_JGwRZ>H_7gakmTBhwYK5bv9K`!pJcx=n!WD z1!!!QCGhgx5JF9)@;B$iAVR9oe~Ez_b$roIfThBrqhZ{29QPseAW#vA98U zfm@{mF?T-Xke6L#e1Oz=J@tEt0XNZ7Z28)=&T{puftB!6Tv~oS!n%HgEug!Q!hu5E z?11U|#a|_24R4)6Pa*k>ni_rh7qq|FEqw4g6t=`|v5xiUckz#rgjl>wJz=7a5M?;( z>T?)(MI=|l6O`vhZ42C*Nmp$6M}+Dd*Q{YWUkej{3Q226#A@n{@$I@g0)A};Z8x|& zaDJsxG1lo)t(l1x-9=4jTIC5{m|7-@-gZbp^G5F&FY@$qk~ER%#goG)ikuLIDG`1h=99T}yO?Fo6`AL61~pKf;jETt)Md<)+s{ls zU4=G!LVsQCp$6vp`(Hq0S#jBJUx)Vk5Jc+uS4MB}%k8JmtmWaKjEafR>xspYawz#B zEvNsI&>EJ{2WB>uwAtSk7 z>D4HG42&Q$nf=h%m~wC>i=%Z()WycG3}%4ZkVp!sXu>phwmI}dix(t;-4XS$D$btwljVPm>%4TYGZBG@9kj2=GZ%rqPayedSze>%~U$&iX!Dm1vJ= z*fLJMEA2wdha*)TANdJO9d3K_2yJ_1KB@0Z<|JHQt%zjSq=9J0N}k!I)vxk!_wFHk z<}J#ifoz$ub)X1;w+9%J+}zQViGEDv;TYHr0?cFS1jJH-yt>A&4?i6TLELrK?t>EN zJktwy+(Yj3Y_wroW@ZGc?vZ7OA!1Ty<*V{iM#W|A{*?^a+Ax(|Rg|Cud251)p zkC(4yXCTOAgVlR_%A(qIXAGE`f?OQ2WM}vbjcp(sgaWy2U{A!>&voT}ZNt?)0FCYb zG$^UM89wBswD>!m<{G}viXCqT+;dvs2f!QiqQw|;Opza*`J(mBmuAcZ&qRLcd@4SD zVdS)VNaqElCAn~DigTm~i-~UdN#_Z;kd&->&tZEJaVPZt1ry;dUv$blkI+-lH)F?z(qO}p#r&MM^Ee25c8!eUoXYD( zBm5W|`u8GtB4HIKN0D1)yuJ5(Bn#6PBxa(b>NNFQEvL(bS5n-(WLM_Va+YfZ>XJ}( znkLu$b2SIdIu{8WeDG0*-L?}qEF*ZcPoGC_*QUzON@dpC1@OF<4V2GvH|@FO=`f zg3T;Sx?;qdNBWcuk{_)>MZHq8eG66k00yjssKM!aA_p$N>PV(sRG|cBEu3=f=ZT|U z>4O!eyo~f%bz+NcvQOH)3Z3#LHG8nM8GqO-+7TkU?$zw3I8X0jt;6BDuFHEOuw(xx z55`f4KuXX1XQ9)w(*~yj5Wt3Dezz9IK1X!I%N;=oAG9}zW`w(wFybmIb97e4;VwW_ z{cp??f7VXUL^EkQZ-uWJ#>Xn`P|4S7<83Lfb05hompg8~B_X}ViGkA?Uh;q*f51>a9_KSPT`k63 zzGf;Q*a6G&FA{Mf}#{Rz@#5do;XGzw)mS z+rH?`2Cp%p0duTMOAr6|{z+tE{L@R^Dx{S`Z?ljfGOYDY15JxjW zpjLA?Es(w-g{F6aOj8gIKotKYQ~&=iwaSCA41edq*Yu z*_~pF=%_uuU-wV^yq|lG8OemU?;mhQ!-zTAeD5<`-Cl!$P+>m&E=^G#1RCRNl= z1mVR%=F?nvK-qaD3{j&A4fDv&X>S z&eRpVHH`}Cuv=E|>(4#XLNIe$mH$K6JBL>mH0z_WZQHhO+xEn^c093d+jcUsF|loX zl1!4D`OZD}K0lm)*RHOv>Zf~E^g`v{fK_MEAcEZ>sE6ZBelg|HfFtdJs<0 zh%aRiFG`0f`f-~OhA@6G2R4`>Cz=?-4NN_#{)c|@HhJOKEh)!KLaTXv*^Py*g-ol& zjm z2{@zZH)gx4$#;9TC~0MMNVV`$)P-6(bFE(2PVkfSX_+pYrv+bkF$Di=C-DlEOz+sdX^w;;KB=NvcRvo|(I=_)kcZ!u-3MZ!Rsx9~)o91_)78ddlFJc>*)lor2o9t^P*l@9J8N@6G#`7goU zRxq97C1;WrwL5_`t%e60H)v-)2N%HIdM(ThCVKJ}w+l&I{RhqElkZ`)qIwm( z20LutS4ZVOjeW`RNW}8eoBojiE3)E!sWQ6DU5sO8M+XueRBHGc6i%y|V7Tw@9m>7) zq$`^N8zEQ!KDOo9?pz*PFjhAq^c@|XW5J&KV(H+rgiO8-l3&d}?7Mdoo&%s9vLjYR z3d`Tq%(a!GG}x|BSjoLthWVu4AS!G-Njf$Y-EDB2o#WMS^x)NpZX=42M|s_k|LFoUm$A6pua5bM$8Z&zowM1r>l$0=8}CXP z8<2i@P7<5z)R9d;Y?-*6WlRqy`K)GU;A3@uZE^&oHC`RHaSiy&*h}0${;_2TRz31< z-JRI>oRncgR`({IsyVy9aZn9&OAOX%vS0bQDE+e{|J`%^-bwx0nzav@*3+nZcy{bY z>S#1)VDA$mHk?ZBuo_L$EkfP^xAFhdJ-$rZSGBDd+8yC5-%sS@I`MMhq=Cn!(x31j zZChd%7ao<{-j0#c+&5S|Bq-7r-g~xP2XNVT-ECvn$f~;jQ~8nlTlPQ`DmRmdqbg!;p#RD%$LA zp5^nHYUwctKYyN5&QBj=z}{b_T2T5((WUGhzHC4}{N2u!_6@f{tix-b^et-EwgNxD zPR;DY1C?VPpjkH{cZTSo)WdrWUAXCb*8b!9(a?PqWtyI0>%f(4`Pa3DfK?47Ya8RM>&`ieJ7 zfqY1DOg&m^bAhg0&L)j{7=G6|Cx27b%x9^EFvOS0zJ%5}U7LQ7uazY4qqI3N;doeg zVfwgiWf-7_2N|V~jFE7UKF58UI!=W`!XQ9|f_5!2jSXJcZC?jZ?FTDHCr@vZOO0e# z$v&|_LV}s70d^LZNEVbdt}!)TM0e#e@b$ZZa*iO^23lF=<80>_`0670YJ2Huy|{f6 zJu(O$5vT^S6Db`y1M;4iPv&}l;Bbj`|wi>GWze8tKg5wm!a)13yBvx z#)Atiq+Au!Kd><8su4Km*o8AkW?;cvrPrep->H}!TJSR;voM>0p|K#Zr((g|d_VtQ zBA%=`cU;YQ)9lxMEb);hcy0^dLZ~YeGP{tHIUw#-iu>1bdCkbnBA{j&@;z;EBl(Hi1X+A>R{xeP7;Cz8Gkx`8R-hF5*>#boPqUVzBqbAr5I5kSs zZJ35(kV)CaErlFaDDFp~ohE3?6(kQ_dwO#Hg`zgcIu}l`)90W?PG(|1Bhik0->fb6 z_6rBw+YGTORQqxld3~&^3G<12KdTHxaKj_Nx@P*cZJTOuBDHR|BE#FU4XDQS(0B5( zV}!Hv`FLzvxn&lgR#~HM5n!_msQ22rtwGFhR=Qz>O)3)))UAvP4 zA@>mq`NH_Sfu-s3X$)rbeBxhk2@ZyuiV=VTdpocv8RwGU@{TFsp-q$f7@nHa{N;8J zGwHAMhDe5lrPWcW`tdvn0H|-1Y2%ym=OE+Z%8=!b0Y6tY|CFr z<&MlV4BYa0w7qIqF*0yD57^J9x1;bd)S!bQ5``mIsWi=ecMVmBBq`$jN1fKw>`to} zed*OzZm+hBV;6KE@#n^jL#>af2}G-vO?maosNqySfdJN~#;>R+(X!BW~wR=XsLCi@TcmjQohYH`PUKrAHLMF z92sZvusjAPF*m0a$9!?}Bb>^)LVcX(YnU=}l6noisjINpYG49jn;ocf2C)#-coXWx zv7!g3jUA*iCJV;nfLBITZBCv|EN~0cw}+R=2K#n*T<|_-M|Dk{xRNo&^`!VbG-}mHL{DW6c#QbXw>s42YymFX9aFp% z`?U^D=dYzPkwwl!9sC9D(R)sC$`TCFfA41uP3?SA8pAL^l#JoNLd05<+un7S=Ig9= z3T>^Xaj7c>t?7v6RkDCNqH$Fe1>_b|jltS6K@a&l{=Z;AZmkGgpb39_{-2ysC1!q| z_UN{~-R{}sP{9nS7j6_cuW(pvs(tdseBRc#GJ#uS8~ zdo;l2Kf!_%_i>H6Hk}_o#CF9-vfQNfQBxoL<;PAj^o}PCq+b#gq#t^NvRs7^H>IK1 zqGrTXoBq-+BSf)j_1?QaD_n9!%{^`8=bv3gYV(ioRljN8mz~?hszb_pE$zVpDXzgx zdV<{JH*(W#*d<7OyEELWGl^=nLbKZ4np(WSvsI##+;fRpmg%x2hXI+B2o(URyPNV%6g-Y-> zV$2JXi}W#%EM$h#w4XuC);iSYB+Vd9W&~E2;t3+;PY*gTq~El#l0Hp*aX~9@nEWn+ zP9fIR;CP_e=ltY1LnTb#Z7Vvz06)6_SdB6JCOE0dDq?q&(W=&pv<#^1qVVIlB4#8e>K}Wx!x?3lolSR+$rSn!RNUJxm zUXM&wKY(QuXIN-L>ZV65`e6>s*>xf}m8wR!2}Qi5B9Q9JPbmAySWlMP0tk%`mONV< z(1ac~%W0o`5gTdzoMbEb?!F+CQ}m5x!|{a}fv*ifqTwp}UffsMYTdsdf2*VR(IXZ$ zl5yuFgM5@feb}EKM4AH-!fHUTXE;aAyA2Zk_tvpt!rg9loTPzX#LMjr2_iT>4(13QmuPNu6qG=mUWH&&*AZtCs2h!x7K~#X*(~w0W$p1I$ zM_&L7>;HLQ|NqeN^_FW->yZ>FbS}IXi#2X;FStmQ&khTs<(A9{D5z% zZ^tf{ohRlpaaSDMYmG7^Q~0s=`E?Y?axL-G;`(J4anIq;hbkR5flPz7YDni-C+F!t zlF!@U+mEWFlq~_>-g_mAwpn*06l2-Uc84$jcT!>%6cYD$%~is8O}-zQbKm&+pD%-D zvmStTG@mVsJx6^dU{c#joP0T3?MkIaoDXUZT7lXWy@yO$=4JcFY6YXxj-%#x90`wQ?}Eo{1gbi7D@h+$>13XKkRKQ_yHiw} zx_dqACe>Yw8PuRNaA6v(*+DdlJgn+%YaSN)fxEpzm0J6}0sI$eY1TwME!DsT0U-V3 zh%D#=?}1qG|sNiIxwxfDUi{+{}jL^?!Dkv_rKvo>S&E@f@Aw*>10p5c@ z#{Cz^chyQ`52OicCXRR{Z&?C>aVY7_WT(7%ISvD3xoq}@NV|_bn>?@{jc#_YyKv&| z_dB0*v5gp)N3a-^gau?6TUTdY0+QkIO|)4gt)J!}uAx}EqDHaa*ez3j%aG4#OXL(q z@>;5`%P~?P=JWYurY%5mgmW=*aWLK~&>=Q%=se#h(Hrp7s!{Y+v_>T$N>3-xR+5HR ziSZc0WW%G-)!6cPc2DF)bmJ(KFPNrE6iyvO0shabwQu+pa3#g0vo;H`;Ww@|m8Lh{rK(?3!K}p=8Kvy9pm$|rE$1{vQM^cL(ZkdiJ!WbKt6cQ9o;30*yoPzT|~Ns3qRNnYjZjuB0wY? zHgt#;=@Q{L$o3W!vDL;J`v5VduFzL}{FdWGS%CVT#ghUcbq?hj?e&qzj~x-_j3deU z9-Jm!&)F`JO0`8s!3Zo18^{J0vwy0LEE?=jpx|hZkCyZN42Fk-&?}n$|wduJh!Ha^I2Kf^NsGVol)RoxXLEqQ&Yb(;(94Ji$ z4K!+*VgJd;%ypF!l(yQQP_yt(M41`p`Q6H306vVzfZs@FWSdO*29ba{yK0bsoykv> zzfbO5VE=&WAzAA-xCne?FvqGG+_+z}lgOPOPqY@$nT~&D86FnMTQTCtD3rLyXCW%c zCOeYaUt3`yPzVZ_1M`h4UVf98^Eh&alQa3NbL3QNMBjEjE5r7HsxZ1Js|h%G-Davc z=+8G<2O%aHeB5Y+1z^k6E+W!?Di(z;|GnpZqHPDTz{<-Xas|TEKNFn=5F%ie-FmeOhswbKhfqE1i|mu%Ic!d#QQ;Z)3Wg`&QOydM*_J zi!owrC)aCwI=W1Eq{_9a1BT&^OM9T-)VY9a21aP6 z07iCoruRpx{S`iW&epM%^c4_82ckX!iKlKy`;F*o$fgEm^k?4M zW`;IQc#mmCQ=HaZ7rUyl$2DZvu5HL`uwR37(sfa$Uydmk`{U@Y5V9qKoK0LI_Iw$# zmS$HBwOqIv8rDS8dw0a*l9a%J&w#}Xs>Tdl+F0`9CjFyar<~Drlq@uv@b!aT$;X`s zrm?Ayzax}k4EYyqper2NiVBB)Ki}~MsDRWTd=DGWm2OA*tBu--4Q9-)AHP zhaR^B?v^w58b*Y(nY(tP&dE4%|5qY?beY|C^R*dYuInV3kW}8w!LH|xGb};zl5B~K^ zQ}%sE=<@DMED|`e7==JY43Naci#d@SP%U#AbO8yT`fOwOSqBW9t$K{%d@#PoGU_NL zT2@PD&WKeKBDyabMd=RWaa=9)0|2wq;1?s}mPf~=cULe5EdCpdJq%5d^m z91P-crW#mGX*+6fJbbsMWK1G0D^#>X_?r57Kl_t8FB79Udq#=MAE<%Ucmjlpz8`34 zzIZ#i94A;HCu@kU><5P5srC*3N?@xq5Z=xFmjc62>fH9WA^^lRo4le#MPccDbToD8 z8+toeWOp|fI@hfus05dE@%So=>cT=Ae>cim8R|-slt9u}TP2uFURYlURo7lWp}e{` z*R~>vMdz)<;D3vzhBW-HzeGTEYjGp$%zUH}s~E_{(0cxs(J}FJt4r%|D|2gELQ(cd znWi00;CZtKNKw(!PwG9jxRE)#)qe|X|3~4_`MCjOg2R928TwOEGxtyS+iLpBWkmOH z+4W3FbdBb*#-e`{{qr@#m-pL#NRko7A`#j1(<*Y~YBHQ|Frh87vZHrf6Xb1RB6IJq zC~Fucrz2P(G}I+IAnjX@tWAIgg490gbqAo)=XbzSy9#h}2>{NwS`U5soQTh&d=B_h z6jZ<8^s_9N$xTMnHqBJuNdabS6}Ek5{~ZJia?y5D)@>NO?ls4k80f^BuFj_!fReg_ z7z)+^1@cy@Zd_3=lI~&wT;*C~RcuFw{~(1(z+1*rF{EVt;SVH?(uau*mcrQ|RE-2i7A}r7r&$9dD-I6UVFPmt8;L-He0o@6 zVCAF>RUY6~X@OpvGYUxb%AH(5kd^qr#C2lT@Cm?BEl{EYfmuUfy;TcUbE1a1diO?K zk5fFaP=;cQS1uDF7Wah6t*qCAL=JtvpI6z2+f4{@K$~s;FtG&lh5<5T!66?EXWzKj z;RnVs=hqh{Roez)E)^k-CqhFnx&DL%s)Vr-2WP{{9D33!)dKYKN696tZ8&TQ@J|qr z3gjzful9Ikxxzw^VlOAmut_t%7ki2S8i)8>syTwJf-f!XW_vFqmL61#3|PDPt5Dd5 z+>*`j>Y+#rYUz=OTI+(4pDXx!qdCxV?8=>e!hy_%NCN8alab$Vj#aMIM9-)u)W0}o zi#drYo|G7a4hks0L_fG&hdmd3?LtJa9N;k*>t{%Ig06Q028C$~Sq^;pvj%%)bEtS> z2HK3heOjUAgpu&GVV|4K*tvQq0F{OmS`%Bk7~=0(-rpD51hKm(sl@f6_@Sumeo=HO z68RWBJFfx|l0-6#EoiwL_o!h<1csQr-ZQ#wS2bv8G&Ded80G}v-UEk5Ez~Ut)Y|M< zT>%7*Q9oFU^56r3;01m?2|$MuH-F@|w3JltY~)yztV=K>*3|g-vCHHCGcoz z+BNx0D&gk)aozFqYeaMZ+0{da0ltn#?Da4~Q&N-I_0d5(!ok9vhLm_Y%;&PAj30b0 zU4Svqh#ioZbdT*V(Ho{<9_Mc_pq$jX!yt0eGj(Xnyw^OgZKoO#Nek@r!;IVLgoC*s z0v<>%*sS5wM*MD&5%k{M`&7daMZsF#pT}>kN`7g@n z=T(_3&EMzA!56`XNye{-Eype^CxFwY9@hfJ<5S(LSNvFvc3`2C=ykfYawoP%t;L>2 z#jZnXa$gl{Z-FD-rXU;W-Uy_~PNHG53=8e50!4>JM!hF9lwX{WvCGpb!zNdRfOac3l6FKIMZ!%jrgEh#jSEao4pZ|X=9M*+uC_`>lI7FD^ZC4fB49gPtO_&n z%}g8YXWZSnSTRk{1e%V|UO()s(IR)mvH};*?_YB+C^b3pzssIP1V+9woxatveyfXz z?~aF;$Vsq#65+s7;lT2iC|rV-_S0cBGwtRXM*A6{`Sr2_$uKn>iFDR0P`q=t!>F`jRvGHK1Lyp!oS%p|F_nK*HFu4LS_?${#o}#?~(0&~Ns!m8$pBd9uzWDzB@h(zy zuw9@`^3-qClX5}l!M%y8tod0vdJo%LJ!v!DR?2GV&8iL#`XUHOWo`(h^Bwv9<9FNA zz!z4)_`nU(fvOVpkGO*S7pm1i&%Z5zM6f?VGToL+l%$Dy%Qv@BV`a2$Q?B5~aGV6#%cwiqQ?Z(jv7`bEHJO{h#IuRmXl zcTEvg{drX#;5K;%fck#w>7h1UZm}A~DPGI|;xgz`x3fKGO@)4mdts`fOMP1O)Mlg@ zv4Ih!MC!xAh4>DdqI>-(1mg61K6Tq=ATMtzq81lQ6150<3x+~S)k`w8E@=-hng8osD}YHx-0a;tnEU}oQMS+Z=d1R~Nl=XT)4v^+VK zXa8&j+ReHE<|7+gZ;YE&S`7?@*hlFOCJGB{j0Q`7RmlZ`@p*3@VCV_=$U!hJJWGQ! ziUEmY=!CgVR(UR|Et?qe`YG11T5HyQlR21jh31&uWAR2Sh3mtaK}lBUHyKU#_M-8^ zIUI!kRI1C$!xL9b>0jvu8jQ7PvmAap5AZWs{M^4GxFJ6O7*34~#fD@rO`wX(JL9kq@)M zq%X`GV8KZIcdQg}izJ?kHWYBPfefq@hFkNlBg-1`Ri-|OV2+Dr2_)#@z4bA{l&5v5N^XM6^Zt^Wa1SnjN)X_|EXTRE{{1 z_{O04JV*?ZncgzYLdtuLM00v)I z_sOXuEYob;;3<7#8Fpf860|GQmwA0Y+LpEsS?Pz;svNuA5EkM{*^wk=t{M-m?al~U zBUQ!T#H^4HmvQqW-LkxRK^{=4LQ)xG{efTp7^-$su61FN3j&Ohe6 zA$4*V?+6u!8=B24ATET>MRVJh|B|?V5uUn^n|OBPu`M^89a&8=;wh8qt6BvGkY?i z;CiUrcHi?!jdy2s(am=~cJLyq=mr9S65E@!wK#RT{zB2qTGgDjs)ge+q4MyC>0+yEbaAEX3>4f5M2<` zTI$&@tEFb1tuTN}V#9d~gpK5USYQ&qTx<-Ilq`IT2pDy~vl+uUuj&;NOU?k+aDrr( ziWTXbX|?~-|$e-M3kT^$jjwP=u>{{ECl8^W)?MLF-tkb@BTFQ zVI5%gQK*SE9xrZeAq&wk#s2`_czG(JB8EnXd>u+tPUezeVqVff#xX&rg;M)xlSo*I z29Znsb}RiI+pBaDUS>{_I)HK+N!lfL{y-O+;gOjgF7@ufSZF&Detd7Tx}vhZQoE+= zctlouMv*)%N$=W4${9+SxFzfmtxd?Tqp7>bjkv0jc>yZ(sONDwl;yRbh>wnzMY5s{CVz6q zE3vN`cnwn8nX<&0Cgh{dv*{taDVr)e-J)6JgBTpJLY*m)Ct;ly&3oSHN$pnp%+=oT z62mRfBP=x%!c)*4*iu5>K_gb*dY(Px^S5J}g&V``iOR%$01YVkKw0c5ZuLaJ%-C-> z5Q?UwLy+yFT~XNM$T6Ku1C`G2c{bwpa5j3c#LlD>iJ9{T2HESLp)x zW+5qMvVNgm4=u6$5OwVWPPZ?ScLFYmg59kjoniwvkCv`>iCGltC2B#h@1MV!Glgw4o}Y1%rfe3RGQfKW|0 z8$R*l?HG2uhyl{r?0bAe znYJOgX?KH*V}?dxkp!b`lx5>cPDK1q)`PT0>q$8q4djiS*ZI7mpOSkLGJw)DP4^m; ze{U(OF^H!qQOf5?yv!$+L&4NPxcf<+D#i4S2S|N1r-%`Ma3MT7O}RCx1!d_xe*Ls0 z?e`){u5T2-!`r2yXU~lfBVf7b_uKo{AK4#b$rz&;7jS=##Af{IAzsxf%lf4EPv2=y zSAsNqc3}C=e<)-fbo%!#9Zn}U_Z(pLUHzJLLUo833nf%Ny%Xk+VGG@~}YDd22s5Q^b z-u$Jwj=q4}5P5xf$RT(Jdx-HGqyK08SHfAJ0(Ftg$|{O<#TO)!7{*N6Z0i4fwQWiJ z?ty3fZl4zrfN^nkHaE6|@ywpq+la;czUA)JrJn#1Jop0#0d?8b<)PBWBTAV-2BP)P ze1YzjM80I65h&|u$1k~+c51t2mStYTzJ`Vh3f|rdUJM@*=H>YVBE$DcfB}Cm&Tasm ze>w9ttCAc(Um$BkIOg*V_w)KboX2qie*w>r2aK2Z8(#y)?LVgU@i;MOf?T+k>&|wO z6LPf!=hhQ^X4FJ_jNKeCa3^sK8q!|M2zOS+Z>yreDkk6S6uT*g8E*3Ox}n2PCJeW~ zyk1#N&$<7)MO#g#Gwm57f8O7&n8{t-cEJD)f#dw^YkVKSCXYS@6$SeUt@SNeI03VV z^}L#zs9#N-K^}0=sdY&8QIasg8F;pE4C^{aJ1RlM$R9ACQX)NOcrRI~iV04nwFc7U z46EfTXOJF8nJ&b%pP7zc@Hv6F<`amSbslpZd*>5$h(FX*2m_K|e=f*VDdIsZY&3&z zJwB{e`yFz+l-JQfNp*luBOU(cO$Q`SZNiOrQ(wCH!{>x>Z#fpp;^`S=9BOnrcxSed z#){>bvycVJR|1Rgp70hoUXVKZOWaJn8r;SuN9EhlVHRCBl#c6B6ke)&#VbkVKZgQj zV(3bS`kCiub0Xxhwtqe=nV4+rhE3r3&p(q4l82tqf(HanVZ-JAB{3hVHUgkh44%zs zarJZ$4ggbD?|95hD507(f`J-w?ZTnVtI^db5MMa1z=aORAfZoSHO|@8S}=JkfVpFZ z;MJpRqb}ccS%MbEt|nGNlNDk^!_5WNAQy^IuNn^K?c}xJIynx-be~V2^vkvg6db8F z&bcxDdf9my(PJ7ASqo1w*axgq!$_R94s}@s-0Cn>>Bpe0jH=ZNTA&-33PEY!pCszr zC>U|0y1XXi^P1XR$G$k#Lh?RPDe_<)^*n=CaJ})4C17pjaNGh^rZx~=Uja<#&B z_+DXhli5LWB)@{U`V-S7iS2~-4j)NS{gU zwx0_X*ho!&SS~2C%f#N~rCVxvGCtplg&6bkJXOF5olwTe2cR0i<3$Uv7sz6Q3BMmo z&ZzCB65WvKN2ik;&vv--uV{Iuwi$bfj4ah_CQEXY$xDj*4WFe*#yOfE;d zrmX%`?$S-uj+7AkCfr~CH|n&#LRF6t(Qp>FB28}YtXOZ zwcrf;*sjv>4b(V;$HJak4N17T{I?tbufwC|rCPo%4?anD{wYk0{5?2u>;D}bgM~h| zDuz`<*OUbiEx1jSC4^pGj+djwMi@yAL5Li6D0+ za&C?Qs}t`a8@WO!>N1cya>_V=M{EH6g6grtcetF|0uZ>wnv7jEdcTQeg@Uu$Y>y$9*E^7NA8bgk8f;a(s?^{`V5UK5{n_p!+( z%D_1p1xSY-!?+P?9fGriS|G>luZi8vOT5%{LO*WJP3sMS$E|wY@Y1;#Ao3l_IkYZeEF# z#-s7!P*)wQwmqBwETo$E%cqhGvj#YPH%wqyaVZh>3RLm_ zp$NQ*lRX8lpklE+p(l59B$%oZ3*fWve}zBXbn^7o_$wheBp349J$<*NkmtAHFt>-0 z2%zNelP4G}&jLl~nUiQubopURj*zSw{K0iJAA(MQW`U4QznEiEn)CR*-uCD@`WH}@59I<*2Y zJKhzV#efGRdvX|YZIDj{G3ms#5{oV`-2zZMGg@ws5siJN4DwY(H4161`OLaTxDD~7 zOm>jV=))HE$n71RBySEsV^VOV!K~cSspFc}Gn5I0B&a;%fA zl47oT*{ws~BXRt06KRsKOi3RjTrsp;U1miH|7{T#;ac|HxHMXM0;z^9AB_KhaTj&J z7x(FR2s(eH#dQXtrcj@;tK-Bd=tg7j{Js$q)Y@QI0?~h9-It|6X^LuF?BUm4&D93! z5Y%P9=e7Z9-h*Izfa&fE~%lGCz0t;nepcLwrw8AQTOwNUnEe| z>W}Y{JHl9;JFGmtC}Al_?!-zzXAx20J*Qbyc>F5SfBm!o5WH#)W;(0>-HybRN2y9- zu=le_iA`fT^|}JBs@qKWbSKaU3DT+Cy<`DBM1gT#sAeNwRkyyGnm-~eKi%!V34aUS z4b`bNJ`f=;y=>8W4U*|Gpg$JpC@&$fG;kJ#Nt3u5u-(dfAIjE4Iykl_Zf_pV9>Z-( z2Y($r%T<&Dgu`L=io=@1-FQ|v84lix*|wDh zlW4RMze5i*(5X6$IPE{#qOZ~$lqg1?SRnEkE|sR_+Z%kBNPX5BtPylFq(ZhFsh)8z z`#I$b=F9-PF7|ACj@>4^y6f+^bzWzhyHYI%qI+ckHqA{QR;3Z$HAXUMotHhdJ$AEbGys!@Q#%a zf*^l#Bf?Q;RpqG5`3fiQSl(9b{d9EVSl$$*UDV$6;HD%kj75We?EoK?^S2siFxchx zS9g*FaGad4COh)u4pzm5t#Q0ENtc)&jF&I=_evn!1Sdxjp4)&)y8rG8>K_~7$`CHgNbfX9i7c)(yXanIo z3ICiPPH1&Px{PSXih;;wvejF~(N1kQR07J&gy#qmVHtJ=L2BmuGHl1U38h>BN6dQw zSk{v_dW5UDhQ4gTbLQC(sz$ze(Qip8Qut2kkc$f|vJp{I$Yx!ihS~X1hkDHmY6>p%?Aw+cW!7a1?tb_1)j2IwHA=L>y z@CA9YjXc>QgdD;HZ?msSg3fw6UqsgcDqttynFxJ@Fd>-Q7Gh@iWjcxDu6>K_?EKQI zIa?{{A4Cgrssl#d{zPbXd@Mc&h9JiUuj?8(b+GcwX%ttC%4B+*PQGyN_fC#VK~jjm zWh}i2Y@f619h4PJ7s+&Qg}t-2tzYL@CTTwF=A4pd`)CkM@e__+c(E_)5DIz#4v+sV zm?SqScIY?^x>L7qn>y9#p1tI-FHhd1>IEEN^A6O`81-Rc(8i2wh+&=KznBn4o@L ztnphb80xybm9J7iE7l0Plu54PesNyE*Delr*fy#d@{!6+X&abOJGyemW>kDKze>2P z+HI609rCIt%TRva`6CZsw{j!-Nr;mGSV{{m{hzLODrweb--K$cEdMK^+O(c-6nPu6 zf8IB|8K_V7JGh9E#qz;PNZ{W9GIyx$Z$34|`4SnLiV}hICKxkJpUz5hx22Vm&Waze zF`<2io`3S5_Mh7v82fs}V)sax{l7*h4Zj@UJ$AQi6igpx8TD9?_C5Wh0AKeD^oD;w z0h5!6-$>?+U(l0KBhj7Q_V(Y5YAbKt^aR|$S!v_h38=6*z3LGKCv7nZQyB*aw*?IS z|3I0(>W>JXKfgY}*2y$%oU~y&*c*bO%IygJt9*uyGZOxDyTC$W-tG^(a?_6}m@>XX z61x}ZKmFJB>eKc8?+PsEHA6}wg#a-3 z2SrCp?54Rm*sp69pC4oLya~n>uD%*!;709`s?A{=JSH3qYPYNUyyV%Oald?eV7AqY z+Vty27kf%?X#S8K5eN$0SZp#IU>!hP+|Uac17SvLZdkwg;gE>~DSMg|nt)eLbj^j~ zwgA0>p*WI#+ShQXbbwESv1OZv0c`F(McldcHo;vqnD17J>U5bB#xp}P8PwEub*%^w zh_@+aodi0V{o0%J!&U~QOf|2(=G}0Lba!5pPnNiJUoX9uBtIFwjB$z#eieb>^VePT zH;AN#&Cu@58ke{UYCt}PYBAC2b6(9$D$M8M%vQNqwdIj5-h0=W}P??K=)j`$R&tLybFRh*@8#t^o%3{WsupxBc}lw)Q#M9u%Mo)P+L6EtJ$IKw~sB z;&)VaHnypo(MZDHco@j)edAaHC&+)BO$jaet%uc$hEW(*8?>2cSuQzv%rI$}Xb`A8hHQ!f`|>)k9lx4O)8cD;bma zHVP&HSz(|eXzQ?M6%QOe9%n`bBt04gytfj#DIo8f^_9c*G271oFb^WDxK@n@R&f3-)gvsdlf<5cZcYt1=(t0>CFw6vY1JRsgtAPgd6 zF+TrZj$=&}JT%!|yb8OPk&X5-t7I0bkloo-8_dhfm3=~Lw0a~472FB!WSxu?spRqWosY4C_s$vs@=XVn)O(XhI~M?c4^9M!E-wfg_G8SmIUy&QUM& znxdF$ny>-L&eC?4rb&#-jCP(p=<-^d)(Qy@ooKvV3md3fSUyH-m^oMrLc|M)JI3di(BChecLFm|pi zr>H~ju6OtB9|!)TS5cMN^?OuZ<4I8h5^9r5#lCgwx3h(o&d=XS#R)KY6?RMADF)zG z9Tv%js|Pxs^)=FiCX5RV+a(c^1QZ&qjj4QE3$H~7d$?UeLyo8w>c(+O|WpAVW zfs8N#BFu$93X0U_E(eJyaKS>PBp|#Ho6Ukz)~#0*N!R42wH!$d(jYlPzzTgc?-Kp7 zW6d2QnX(|*2Xu?9TM$Xx@mH0JsoKW(L9vG^0D*8n> z_F86AlrX@fOoFelafXXM0rzjF`*Cf9fVT9hZ3WThw!uWzrgrTCfh5@_;T$nV#LXhA zfJBw76~5w!t4go7P;<#Xnff7oEl(}!9jA&d5$(uhyFcD`HZ5lx2!m@!a7swSmY>Lg zYQ~q)t&>Be0^Nf*Ek}f&o?(Th%mZ8rV`+wXSpmvo2BvW2E>s|KHfkVm91iS8zHGS4 zX7?y>AW^t$XlQZJc$*ilo?DK5UF&%~X5cSx-pDo^&QeE|&jyDyc_E?78a3{whAgbv z77c1Ar~c&D3PErmmrHf(JFz3>##t=@e-@kSw7l-jR-)d!gw2l%ntVg(nZi>^s_9$V z?B0D6I^uLx%bA;2HT|amKc;`Tzunkh-5zMYo`;R}n=>UVp*GnGOuWRz(XkZMoxhCQ?QvRaC=YxchQ2=Us6KJ!| z@K%@s;pcYnV-3l5YxB!jbfh+OXMZ&~EGYB=lwUyNjj=3^M9o6rjKKmA%8_XmFgKve zba6$;31*fS1}i9@NljUJQi`lY7?Z|1J0MXD6l@DRO{nQX*(+-1orqR&6>{hsw=}Js z&-aF$a4Rbj>V1VqJvTsp?topB0(^c5A0vV1Fhiqt=0|CpRAx=7gCcOux-pqHQIV${Yom$B9H^=7M;)L5Ot9}Mt zG4DYn$eE5U^^`>49-(&t$g^N?m$fqo`inNh5#RJ;$fk zHQP(9+eye=E8(aK%R_S~+#if4f=^LbOkg-4s7+C)^l&|1toFz18%IH^F6wXp;QI1N zy1a@6t}dop`|XQU2x$!`PF>J1$3?UwqqXsHFA7wD2cQ7T%xs5RZ@sDlMYaqI9py;0TX#n)6%<|TdC5mO8Lo4(-1 ze^tlMkFZ>)r6rQX=0nf#T=!uQ&^yw0^>P&RzOU5q1;X5!PMz|r>3@!(SeySLh-PK_ z@7b~clOVdXk6R>{a@&z@$`Kay!?#&N!3mc11CZMZS2HVLSoy#uv2=}ZjzBgA7vi`V zTg?6&z^Cw*!*>4ILNCY9&l#FO0qXNIJoirs6%+JR^R;>B4mGKQu$s54EvM(*4i=*a z@P2>4@eOF516){Q7DcYB{tIZ`d?*041=tC*MC5)1M>4_M%NL0I`~zqWx;X!Qz2Ati z?67;1Th|46<)=|Pcz)a(&0i#Vr{%XS^=y5Lhb9JwF8EMC&j;GMe$*}vd}^k;)%6g2 z9qmkf&hl^Qem&fOoXOWnU$<-Z0WyZm)Dz!IxW(5P-Dqa3P2XN{^}8owdw01v?j{Vy zerQE{hI6wBO%FA}Y>kPi*CAQHqJ*Nr&dehui0eV^^r&M{UmPE{gkc~a!Tv)N72PAy z0hHLHBM$b7b><<0FCU%a=g_V`6t9B5Q4zQ{)zYW0K0aa9jU>ye2Wyf5cvozyO)?X4 z{!}$w?Hh z!aLyGTnWLYcUx#jDOwnr$UI~eWeZ0AiGT=3p^X0*@^4;mcIu)&#}8_`mnvl$$;TkH zd}9CHeG|x{)FI(f)0pl|0G#G88EI>jX-s9=1i^(r>fu)n1`ndhk;MT;p53hFpDSkK zoS3@MIiwZHljs-TfqV8sjV_DzV@lHFkH9Yyl>E?DH@9q_cviggsOrwkOSF0vZx6z77vh|dpR4i&a{>bC z`dqQox*#jNSUv>3*Z@x%!8o&S`8NxlQIW{b#D#m&1|~R=gb5WSFB+FVq=vAB{om(_ zvEMY0f6OU`N+1u9ck_Kf^#IrG0Nqx5EOTbwgYvu%TN? zK|;eaRU&3YXMkbZs|>F(b8*=8EOm|eeXm3s%|f5y@qY4Ww*odR7`Kjh&(^c}wCEeA z?!pLYk8aQ4|CZ4vE*S&AI;rz!)ug#Ft`CF^Y&;L-$dSud&}2GDFJE&Qp;KKWkjH{V zn4wn{?UJ-rG&DH>O{5aG)N&a^k<3;P;6>g9VGE)lOIG+R*knKIct-6K;4ljpw55F$L8lINCx! zSYh2`bXa4QBR$!;NZl*9(#+CM%H%n#(%%bME|Wck2vhBlNTo^XN2tFnz|LUhdP*Ex z?A+xuGv;eE8QtaaV^e5oz??4R2-d6)k2?v)KC%=W#R6o>CI)Z?HTWErtuXZT4U&al zSC;p23>BbuCvjCeUE4;PhKY*pF?d8rd4fIY)6aX7PTt{-WSpT3MNY6l5Fs z>qA?r_Xeytx-vcz50GeGgYpJg4Uld`zSm4oRUD;%947Mg* ze4co>ycdg%{oP;95F5%53*ArX!m^|y@(O03 zUhBk5@0w8;*q2YC4+-v-ytWu@cuS;24Pgu{ygengN?0RgtORhZbq=d?N&gN)>5}j} zyaCjykJpBHmW!Fd8k@B%``8P}42ebIGo*(L!E>In@)E&oG{0V5K((+1lIAKK?E03j z{^9Nr|5yNVQpi`^j(wO$@S%Y97AYdb(kV?&$AjrxI7F?&$yjn#d+BKif8!-ZlM|A| zDBd>kI5yN;bJt)b*&H->?tzpT-$C-92bdfrD#WWp**CK2lGUf1a#F2|6_D1O7Cq;) zrVO^as6}*eXPV$iI4N(Efb#GnSHn2=7_W?aZP~8QJ!(-wy=KvtCwi2l(jn zb3?o}lB89X%8$`tRhye;sR`p6jAt(*Q-Mj~wE7w20}N`SVlHxV`ndBdJL|))k-Sy* zSM*jhhNj(4vgs8m9G8v2ON0b}pP35N*x15o@8}&uZbI^&4Q*(XeN$@~KWF9AhdRH@ zf(+$HII(Gc4n((=wY@A}D~mTP89+|vI14EN*3r-@>3+!imu$Z~Hjwrxf_(cP4+m~% z9@a|lvLtY^v=_SmV-Sw|!?`Yjav78(g`cv(TOS?LAM$=_t73Dn`GKV-LbxP!krd;mNH;f1f~ zxrM=Gf5!&c1g~9+9vzZMDNy>dU5F_>)G#^dmleRrCx4>diM<=UV$4=Ad!6sY>CLwF z2V4AIOP;-B2KLw8aUy_}1C^@WuDPRQZk4X2^FT9I{7Oay<1x-)ZGP^PyGo;CGYwuy zAEW{8#2+?M!ZnUE;O!SjqwN*_VW17i%(!*iWL%yN*~&IaHG>U8>u`Q?7v7%}P<9u~~OBxEO z(TDB9Rc-AMN1`ZH9G#Q0M%B^ggF z2v&|kH^(!S%UeOLF!&XuFQ;|y%tu6wXP0TvH3g0`pLo`rdO{U%V^%iMx)wxKvDF#e zrH;4Mu_@1VL`wim%yY3Iu%*|MOUhP-q`g{PLTF=^hOFY$pIGHK)c8UQcc?eAWs>Ox zMdM;d+bz7M?1Ic>6>-9Gd;Ay9?VrQSm5SfWUbyrdni6T6Qx4d3FjQLwATs!$KCpqpTznuKi%m|i|Qg-DHTZSA% zuLaBg9M10g{l8I{-mAP=MlFbfOYJcd>jRuRB}LR$Qu|$Rg*jVhu6biKEh>3cZ<}5H ze>gk)zx)Aohi%z6cC=;XH#vn`CF`3KuRK=ZnA=yY9GbizaiY)n&1)Me-q5i-tY^In zIsOUh(Tnhb0>k^UBRa!w;+l_x$0eNz*41zUjf^QFf-hO(m}n!>j4@OoxdOB-6*kqR zI_!l@)Q8hjzl|1>u84ft_LGb%QzWj_xhE> z_wfa|xr=&`AUY9V&O})X5xJn}RT``#E9vftwY7np{Snx?Je3R{sP@r~szYcO?l&8F zv|f8BC3X5nsPOvWln*ePGsTtZXnUGcXP>F$QTw6?QmU$#Bqu+s`{`J0Yz+5kl9tnD z08aq4QNiz099LpVT6?03YH_pHn84x3i;t$vzucM25N1TRo3QDaVA27y46uG;-v=y7 z;6KS&G13I2c0#Mx-lW{YPU-i~OD0I-|3GZBUkSn`%Qz7HsHIM_3S!IKjCLD`b$M zomJEWt^JBKvxxN4d^+Q>^t;Y>)9U23;@J{9CI<6QG<5Q;dMs9#vKN)S4OhFcm9l-k z0K4{pp*7GUv8DtLB=IGiciUzbVLO1f{4R{fbV>oHCV2!kNeI3?Oywz^qFFpT7)Xa> z9=@r~##3oJR891Nq%?)4nfE1H^UOI~pJ9>h@>J!Sh2QjtNJ>o)*+Ks$%2x6t@S6)v zSIPJ*dBqb$TN;0$&ugmxOW(dm+J(*f5Y1!p8A#nm`&`g`mQLI;S_Z!h{uZE|Rgcyq zXJ$J*LNh3b2}t{gl|&nx|ryIcAwA|K5uMPhf zI|~U|%i&?`KWf2NXB1{Ul7*(Kxn`A=fl$;6r|@f*4bQbs$oP-9Cnp^(xt468Up6^D z9=jb%=a1iNMYc8sfw4jxd>?m@rbC4W(mla?_&#)or)2N#UU>V|>!$IH$b3mK4v#5o zB>;YV8g{C*n>rOUaX_1su(d2@4XBBm*qQo|OPDqd^lj>=RIs)Uv^iZWH5>7)^t+6| zJ1?&jjvUTn8n;vHr)r&+U5-;Z9*fNDFW(hvm-4esA927d6(M2**4!sD7k_EfJe0uq zoR38wk^zn}L)n4&(Y$G%Y`Xmvi|&)o{ytDJl*7lplu#Q}Mu6bS^hvH0tF0Uh!{iWg z6}rr}fI;C&;+lC{=D?UC-iXb1M>E%)%B5bcwe28AnhYUyr?#Q4UKVka`-{-yaT z^%=opNODBJL^$!uxAcScaC@V61rr-$0~~z{X6(~JyCDj0tD6saqnta(pnp4&hT>w= zZZW4?ID9gzzZHa(3YWngqi^2o3cGU#X5S4Oqmq67q6PUIgpM@-kn}g1^%?!fpXq5( zP-!`4qsiQU>dJ@s8yE`}!Ur(ZGjPM{E6IBfA%{AXY#n%(F09GE8}LQ-lOvIeC=5sd zjpx@sV^I*`Mn8Jgt~q5VX+wC2Uv!BULM7aRrbb1`po_X%8Ut;}>Z%$+=!B z&O({W!IZrR>J&do`zz~G$)Yo@8v$#+;#q!FdwW$@#j%*Y(9R5z&euk+Vl0z>b!NeO z*ACgt#z{Fj6y>zO5rrJzT+EpNzJN)Tr7f{~AzQ8wy1aVeK?gZ2uX@l*5*=k7qF>6gcm-T4I=R@qA1hd0l1!pqn;B~Oc$_^77*o<&Sy%5d^ex&%*sXE9wTRG>$J$K@`yWxE`+ zdq;74$Lbs@GfE}Elv{s=rXu}`k+mb9x!<_+=d^_0)9%4JjazSh8YzDI?=e`OZpDgD z0$6}&^GlPKx3rQ-y5gNO$)lQ`g$Gx6x9QkZ21@g4R{lpp%{T3iEqM2d3t)bu zbQX&_#rY7seGA)#fg1qtZ}Rb@H>uW!HGAD=!E1S_6+`QTdl@K0VJIoon8LkLdz7K9 zg8&ALTP;j-!taEvk>Zau>ZAmQW;dkfCNa64<`L<#%)r0D=}9lB>V3sfID=IL(J}yM zzY70lzMkQN2{;7q6HS)+2RQ|4pyYXU)B7wm?p9YNgvGOn#qAsHcZN zr$zMWD=aJjy6BEP{c2B{jt4ZT#rh9~db;J#3h>1#SU$q$geQ4{Bp$G8iCFHjC0VYm zL(}abr8+?RK^jKL$qR%CR#8Ao3%Qn>{(JGvREUoOMs zZF`_nsEe9?Q}WV_NIhnyvpJzy@W?jWy64?C6Kv_v!gS)kI89dEjR8twpX_D~Wr<2z zGDtA}T|?xC$mXI&e@bFN&e2OWQPBp;yzq^b>r-FF7zwD97^on~an?_siC1b7JPkdN zHs(2|Wa4y)Cj4<9lk-u(EP!`;0`1^l@hSJl3kJ;jY#oe5&t45+SHo6dt16f&0aXCoC4^xetzw~p@e5^o zfnb5)%UOe*xRUiR-k@8{~3Rj z+H^%tt6|7GY&tMeF=kHe_Ta@U9@2ohQ&PvwKI5JG*w7uomIbg$Ha;q3TJ044b)ZH! zc_jX!&_Q4Dsu=!g#VeA+7J?Q<2*h6SzvrEo*@ZE|$SOrhPn886jbyBQZG*Ks$x%Gk z82QJ(;XUR!6y)jCK@rqwH%SjjJ~^^9Y37cw&ta%6Ej9V9BwIOKP*W|D+(qpH5QuuP zpi@o@VD!8;7%*KOHhq&uLBzk;v!NH&4fl1*Qloy$dc3-%*IwP-V`x6;`N&;Gt##<1 zWPRfi@g57c90V2fN`KN2sM(a&P0)5gr{9w1Ch61xXyzVA4ZwS0Kkan$8IU_%i9KPN z^YT9n3r-lgID1jKHyjae(~#whnmVA@jcv;WIOUV)Q5?ibi#B%7I#ZQv=O9V~ z^fyXg%_65kHLj&T#u~n=YYpxNVM?)&x^aex_c8F}1<_t^NU7qW-_3{37P`{wS zHgHNvT6qEt_ifr0%2dRjHvVmCz@vHzY-O~vPl)5^9Q&<$Jw2k@5BvgE5fEEj49S3R zMlkb@_@~MmohoBgh0F_R7)Ad^K}kpdi-M}+_7JVdHWIG%ATpML1n8r||NW*S_+EqT z1~__8DdEx~|G%RcvFn*0vJR^4qs;KW!FGLZ+^;=IN=yeat6JZ7%sV}W@9vuHhsa?% zw)(zaA!-HTSIDEHby~e!?B(BQI7ASSClL}_f&Z9Z0s_F9ovWQ)$IZGtd-=ihm>jtc zM70KrUArJc(E=glHt1Ce{|c*aF*zdbXGS^oGFoweIO1%u^Vp=}=3U_AYEw^@hMiE8 zSoOwQP*Y6*g5%`Mo|>VG3^M1kafO9BX0~`dXu>27Ub~>P*DqhD(>vpG6(^d+4VVz) zgoO-)=>h~2bHSI(7?i!G^-@0}4md>@!e?}3LQ|Mdp;1%&u=2u>eRs~K6-+(452}3R z2p&7y+;R@E+Hki}TwUO9_hC9z9D_>+=~S*-Fr9>JxKcHVw`FTeW}r10L7}9LR3S+{ zVl1@pDn2n+oL}x$Iz5NaqzbmCcBGpTy@W*)0b0WO>m75|^lI)=MhnzmWN!((WV~WK z>9mPj(z)tmay7ntFx(CQRxF^CPoHJB>^)LyA32N6Q-K1#5akFi9%X(!^`T`u^X2FY z4%1Ue-_Ql-o_U39)1L3ZAEJ}~v(QUH4}?B|DXtbmf!T{!=FP~oyhWyayVF6WiMRmZ z7?NqTp)-w8nV-1pez{;n|0*z*|0O2)z4SU`Q5B`W%6v#T31@9M|Y2Cp1=Gk zn@;F0O|qqm3oN@YbW3-7t_IunOPA2Yo{nPs4Q3rs{b+Um<}NhCImQh>?@7|8zAW@= zLccFB`ViDel%}3Nt7W=@#)}_E3`%msv2_`%NxlcIBfwScO5O6E5ohC z1%0pUv%-^eDZYXP(3|tCPy0!7h&Au6ZnuQG`m||`@hfzhBF-_lVDo5PCsBF_;=1Kr z_>u1ITI+F#AjMlfY7nv>kxcOJA&(->o3g@q<$C&lU!k1sEU@VzXDL)TZG^NE71O%Z zyofKO$8AuF%KhvVbj2|q_AaRyT=n~~z4r^qH(}8;rD5@Z&cUTFeTP^aoc~>;^_zwz zdcPUjJE!LO2q@XT1PTn;#FW=ZwpM_TunrH*1&I3#F))Q%u@g<})POtVJa^+aE4{O1 zrEoay*!$4?7W?|wFqi$?8a;haH(1yXF^tdK&Or^J^6vNSelt8YuM zyQe4uu;t_N^62UEcCyutP4uy4ee}&2%a&J7V0a)%jMo4nvKJ{NStnM;T$yN+SLd{Y z^LBr5u;%KrXTiLa)8+kg6NDju{&#S_AE+6si|KHi0cKsPpCye6%~Vhau!;|Y(bCXynTOb7+?uNUzI@fhDw2wG z*Aj5%Mvux@*P_cuJ3(W!uqx9vQ?~7vgrN3Z8Bxxvq~^8&ZG5bcE91h-ld|lV*Rico z{Y5!TMf3u>6HYh{BO60%JGaA=Yvn(X!y93wEQga%1Bpy6yEXqotj3jT z{xfFLS*{V$VhiKMpHVNrox7^Ak&DDjYFEEagDkEl)kX!3>2cD^6I6`FtbG?P2-3?F zklPy%VHX~nEkpu|MIKGR08eMIDK4npSE~#a&x2ZIUM2I>vAb4s5+iHHj8FWRGRpdz z{-_X)=~Q;byUKsg8C3qJGd8{19`Ju^b^S=I=ZH#OI#37FX)(i~pF^nbitH-lsjKvr zEA97RvTHOgy-Soya&+Z^r21nW#HUC-7h<#)$D2;NuOo>+RZS72O(BSH=Kl-RW_;hz zO$UC97no0841P;k6;ShechX5=&l-|x4ouhqYNSSJ*i7Dr!W1v2`Vg=$C?wk%drjVF zr$vqkgn5Tsqed)pn!3JT6V1oM?CJ%{=@(KnK|qxT{VO7IVBH$Kp=KY6Y{CJ7%2^TD z-$i`j5AvZ;?>RP3tLZW!vc!y<`7t6o-%fhg9j!g2rwR1HB_Miv1DN~JYEG&Sv;emj z5UOCd9!3Y`l#d+UDh-U)pb}PO=cjtPaat3j`M$TdUKC4fwDSXyB{5hI8lW7OYDtx1 z)|D;gkcF1=Ydegav|haLBszD);jaKbILjlk`|ZvFLa#I^$_g>C6BH7&a+otv98tYL z!T0`S=HMN64?sd5sDPsV)U00I5thVU@2!b}!0gzAU+Is5#f_aX+IH&dn<-{|Q&e4E z@K7CbR;=`O0pjAIbugN!uJiK@hW8~6hv(RaXZuS*pmdMxxZ_tpp}^1qYBI4>obp?A zbL7=0mR)?k7tXkdWG@sN>_46;PBc^tPMO#M{udx=i$sKw3^Nz>eIrw^L;gHkDz_nH zZ&gH^h!M&rCgO(-%3ZY)_~e0uD&@CxAaZdY{o7TMp)-r;OXzDEqympWu^{k^s@_vxmrHFSx-`dozRF>$z#M&giu}5xQXjJmO$HjbGA7mL?6#Lu+ zMu3^#E`sx1vg$O+I9v|d0;9HQ0bnDRU>R6WGcf#HfaI1LExerRDKioPq#F&-|{NHRIet|KUw6XsYTcm zCP;X9Fl{u5g&K_SmF^oCPR67XwXTLq5+29 z5;QToNut^v_T*?SAvUS&>aD%zqu*u!{?JM=Qm%t&v!|=*S!8kyRXYecVi3Hw7REX* zn3A#IDW2|FdZr5++Nz!s#01uoRPVVd+?A+vZSF~VfpO5__K9DO0VvujLrL@9n~4OV z3qCz;>VL2bkV&_Eiru0ZqSI%wCjr6pX4m{Y?+P2k`^_9{_tgWJ6FR-857acMT_K&| zEKv#ku?QgGk6BpNgC8JZX16{%mk0YJLgkV_#2Y6D$(L<@a05q!*pGQF&htWwcF^D{ z6mws)eM4*@s|mBB14Fy&E73?Zebt9jaI6cWrw+QIPJ*3j zHO5e;Osg%OlGT-^bYJn1@RYX4eE4+%K+O<^jTPS^`o2uqCj+LSvaDtwhiZ-*55zCz z@idUiNL^L5(kRzSXK$e1`9y&x*Y%%PA)iKaq>`FAcCvD@3KwoN0DH9p)nN{&F5Yj} zIf{8)wMeYWck`c?;wy`2B~2l`6xAH1wTsAd#gC!PC}c|w#r87$-z)9+rAdXZO8?%m z2{{8sqCbAj2>?bqiN@%VAt@){C{_0hhP?P@acDy2H4Y{}vj3tgoIsDDsSmwW_zV<6HKP0d8C5}QqopVg8E0MP zJ1<#7&lR=n7r7r+%4>%<0j<_4?kjg6{in{`o6XEPV0=OG`1ndgCeopg%(tKV@FPo` zHzadiW3fBNjv=ar)1(?j%CF#R91&t9|0*FjfqQ)Q2^r?UoQrPtIJO{afnyGNj7JW3(i_!`F0#jm}TocqD{8wFShk{tigN#aiY-$$Mx1;<)w!gbD|Q~ zlsoe@%Kf=7j&69du0FHE$$tw%%1keAza2#FhoyGwKir*(A(=&@J8}(+IN#};YIsOp zHxJZ{AhKdOFehSyL`516fuDuvM*=`4#FZvlOl^~-1xJ|p3j|2TGW$ETg3Q7MEcAzE z_q$+nK=E%c++N3rl`4aaO)152%SAq78$ZEE{hF8CZd0WUEDwk8*#bixiY@K1P2szm zCR*^43|~F*g*rb?hddX7(rNNFfq%{zOcF@ofYyriy-vLq-OL(&jq*8AR}(-^v_ygb zZ}Y@OM7U!aBWT-0^Jz;B9~w_@LJh^n;GE_eYo;36$3i%J&N`}UxM=eq^YJT zY?a*|OrfbRXzpfkiVMhkZYKco_wx`e*g(GD3?8@z3_z@4b-h@8@Pa=X>18hw*Jc^7 zi1=17Gf-@fTy1+nXJDcy{dbD<9MEL`7Hk}dL&8uj+^(99axssgQT!qrE3{zYyleoKgc)Ow&??$@$Uz zo^PN>4zw~rmZ_RX7@z7hw43dEe3)?pX)Q(bLWUR;*wbAKT`)s*heJw#yUkCH?ZDvn z5UMv+&Xjb%-x+vu!{L2AH_=+fq=PBoWgKL1L%Dcn%zOZz>TF*dg-O!0=|TqOq=AJy0(H%u6|Wm*1i; zZ=nWH>G}luN4#^)q9woA-??d!OAxx!57=SD`mxk`g2?=;<7Syf`YS|9={H8^8rGvc zy-dIbtM$}kSq|(;DfDzOTN_YZ?LQ1eZ9wEio%fra$|68kX_EjjZCFGvdHp;L7BV@N z)qIa9SQOP6@4BWHrZqA;{Kq2jRfTaTF**B=I|r<6r$gO3`35UUC!j3n9lv!?-0fU< zR;eI&LdwclLJ~hmc9VY-xL3+gc+KnI&0&_sV0BAO^|O8I9KGtub&%e+xr~u?UUV|8 z3!4z!I~3i2Bj5qVKfwlmcev;4i*XfsfsrGH#f7{ys66~rP&|PJ5id@@|{AZsU zf%u?d(SL6~(9v_MW&iwGpWKn8x`+W8d4jQ z0kQz}qUl-}vCZRElTc>Wokjv=e3O#l*}O=DpM1}z50J48!>

    !c*&w2z*m=28Nw@ zC_U7F@XFdcXe&Lr0mgG@vwe#r`ya_&#SAeaM4K*H3b@lx|8D?uX~6?*wZaYzN=Q<a>)?*zN|R4Z0{zgRImptMA{^)-Wz(0>b zs8Uop!cCK>UFmO?iA|8NS2rhyX$aq;K|9Ga@oYl!^*Z z7Fl1nzuh9u=(lLjlKIM2Hd^mbS>a!6h~95=)3#q8QrI<4s_(ZcE&QK{kJF`HS3gte z06j{AG&y4xTCYzb1hxmeDLI?nU-lgz_gBl2&0K&$tO(vO4&n{d^d{U*~cw2pt9 zXcs$3bMWf|x3(ogPU> zlC}|9VvgcrL;&XF2`j%t#K>Kw0McR3-lVh?Gs*%r@MTdPR7| zd2qinBY%O${X&C&@bcfLh$ly&1nZv)rLb=;!Zqj%8GD&;_ZQ+@8tfvL@~d$fZ3ySh zsH+*f)T?uXW{|rXxzyhStt4+`A6AKqL9GT&SO|PPY%Tvb1R$KNep~KQe-E@2VmBj? z`upiK$z#6f|?!L&gyHNH^sr>TkW~*m2|A*^^O@}P%SI*Yh*6kO-7j5kgGPz($ z{nR#Q5vlgK+t=;m#}P}mtzN!}wQ>DM_ki<|iS3q%+%6!89?<>avX&W5fXe^Yyb?oL z;by&eba!Q=_xbtQp8{#EIlZ$! zoi#GX>_^UD>;K>I%m4!#vk8!AxBlKXe5GzY|DTHcCz7jR1&v3WZu(vzK|2jrAWVeB$e1hGmXZqN*} zSBm1AIfF6nB3REtUZ(XoCD$7rk+~u z%r{h@GrX_>lfEcr4k^DO6J0d-YuQBhFyuMR18?k(POzFENhckd>Mw=PyQKgDGXCng zvWWo@z>N845+4lT<1F0@yQ7a3wi=@*&2KR`*eX^jxg)vf)P9c9hC9_U2+o z#CMm;X-TSXmzv0dC&ku z24L8qMTiAUb7Iy?`G~)OFa!RI{paKe5KMX^GU`jc8(r~h7eEzEcU6P(BZUjN)*~Uv zLU(n}yB3C8(DTXGCiNtw;GV_+ryDz;FW8<2iwqH3FcUwiRJ+&h93vWWt0H;?1gU$nrSg22*R7 zJ#%9%PMjcq6RAOQ_T7h42}jYkgYXo^SUREN69yLA$3{9j^FnLhkUG-W3__n2@7y~x zqs-VYy;n9m*77(y&nuwe4w_P3WCn{C$0uCt!fzFV%DKY^-7K6_J5NiSB<(NT$MCc0qb@R+EM@vfVa=OgQKjrF?LRmBvGi zqN^=6=(~Bi#ir~A-p|^-a(N(se7}Jlnw(lI+yC<1l^F~n^EB1Bm+?1(E2P#Qq5xxj zwr@2-ngQdS9Uu(k;1o;m=MfO_ApcAi${V=`5kC3Lq0^#Urt(+EVY!XE>^>8v!gY z+utidD_D(SNUTF)QN}2SAtTX^PSK7l6?ap%FR0kEa6k)|U5>Y3^h`LZ?5Q_CKJwXq zs8@tBt=Rl}ebNnDz+g~TAx=NBkRCm_^EW3;f#KKjkTYciuJqm_&%|PBDFUPP1;jV6 zR#34W34lQ_A#-{nIbOEg4PC60EaiITM6g*hjlU6%Z8z_y&AM%P%UXyywd+Sv@ulio zhuqgiLv~D`$}kbgP3vQIcX{)l)mE8MiPUzO5Fl}fT`Zn`k(M84$t3fxm@MVwFNsf2 zdki74Etkz}Z|L6FHyZML-RIK59S)M_j(I}vY=Be_rmou?=)a<|*CH$6RLNzYV*m(K z0@wZfb*9w4s2}^uk$>a2J=?$s^&Ph&S7ivd4snut7S=XeN!)G^e*Qtmby{YgiZD{@xLMA?-=sqwv;y@)%h zz5oL75@avnx&EYfN7$vdxdt#LDYG{yq_kDv$7^M}vs3=F?X4tLrnfDfkQxU6TxWZ- zQEtBxk**HV{kL7e+MpXwBf;uevjjZ^r(^ZD-l5QTQ7|qI*;R;c`YjUt{b3+wPgZ7f z`S7n3UT@|*8~Nh+u5oQOk5M|nR42~2P)udYxuojk`k7NaqYUJD4as`s+Q};HFKy2> zycRDd1#aG+E}RR~seIh%W|!@6p~I}(m`esuCbqQcg*IH?_TUh}U5D`3`7+j+ zoek+yN9!ogfLZ(gnZh0ZRjp6(MZNkeV-C`|PiJc1#oMtXjd|>liVWV$uxdz? z3QVwl2lZAB?j+IA1fp8xx1;IPLX07GtvTeZkAa;GJm9?Nl(EK&pzJ;*^6YMwK;x@h zfr-r>x5=RZ{igOkyP_okEN`H?j}!eD(+x>z-<$b?AR_f~?ilU4OFOXqyRTZ&;DLH!cHcxlC<24#m-U`fe6mp!Vj4g(T> zX>ndKcX%?=NCp|fP_s!;kew74ttvN;FkDqbRx#$`0`Wac#(*)mdiQFF{*Ag zv(5Co_AxzI4=8dV4g?yD&cxs8o7ETGZN;T!c1V~yQ?k9k7=9fa z7#`P{@#fZr!5qk!c?@j$@+K@(mkqityFzj*d1g{=hL7YlS;9xz%z;!VS4}~=Op0kx zK5=t>lI*?5maGEo?~+stkJg>kHd&WF)$Hy23t0ljMty~f^gT-=;ku9F?>)#61cbpt zAW5tqXQydTyOF&$4yNqsB9-l`tc78)1T$-^{fu6E;zmy9O`&@7DVoQU)#!pYVR-8&oFV*`^acxf3bcT5Z+UL2p zxuio&H0=Qtw+g?`C9Ff5PRPrN*w+lUy?!1IpAv)mOZKZ4wmjvY7mp&Ca7!d@CL(s& z_lus07&>pdQY>}{D)$00?^5}?L~@^9|MH^%749wWqEoyH-SsKmJg}cuT$TIr$Z^nR zWIwLX+xA3bjovaSv{LKrif0}_kNRXOGFO-lmT&;jF*g@mUfNu6as6{@r!8>U->?k( zV<5@`x{T>@V8cO=SLM=%gkcrf+EmpRha9(j@|zGJ&Y4GXBY7!sJQO_ z+r1W`H}YD~UAweus%TyH$?$gF|FCkjps-sYlpcCEhXrb59qh>!jpygR&dG-56Bl@w zTfAs%z^;2<3CT?W$LAoS`{HuRG<6$KkPaKyAbqwmU?uKucv-ay-?qzYWA44toM=bd^r%{bY&g(lp2M_Bxp& z4n#F3+ed9>%Y15!zOJX*9q(O2K%H*lRLgH#r1TIlI3$Uzpe+bvtw$ZqEk6aG411ZxH$FBEJ|D$gUHqfH*L zwxnYJ)j*Z%O44JiF(;Y~2P5qgUna8=*5`nE++Y6Ome9V+ZF4X6Q|>T`d^7BR(x;*P zQ`1ht!Z~tGx&CctU$&$m>TkZy(K8F%@`>Aq2EiEky!C^=zCtksWRVg4*XVxbZ7@FE z#H2IzOyVa+f=X*g289?nFDJ$ExEv`U<@;Oy0r}6!BsbA4ZW20W+NbvJV8004HQTTb zv|g7gH9<7Z&pbOY>82z9Z?V+3PBF2roMPkgIN$GDE%8|B>8@zw4^C>$tI%JoPRr1= zgoy;vi>L+%H=|J*FZU}nj+Z8qhZqD+2>R~bV+aSfYYTlXOqw5d=d)OAGvoq~`M&J_MIaf73=iAeBzIVtr2}R!&%vTWn6iWvX z=`1Fa!mFg^}^UBTWx!&cL`Qor8(-oDPsZ2)fvCrc#) zjM~5YY`@%I&j@V3Zst1{;@Cgld)bGyw~tz`pXm8F6}MXeIoUqXaT`AWi?DZ$t|VyN zg=5>cZQJI=#>93qNp@^|V%wNFnTc)NHYQHKJ&Vad{yhH8M5>NIHdhh`1(R=+t9E+gLZr5w0ys{3{t zbn$o9lcv;x*q6~S3-I|bjBdUACHpnaR%%E(<){4uaQqJy>U`NW^4+)6$z)jt=sU;K zq`dn}rYLQc$AC|S7!9YIi_$8~1ikL(JW+?_gC`?1?T}~u8GwEtg)xQL22r0RO=o;G z$}f`L^VU_U42;1kkO>1fT9LlSUwsYY5`W@hFAjQsuhB!x(T9w;Ae&$?+$`*tpvg_e zdxBD_do3aEwXR^2RLkMj1TF*SnFfpG+M|rh*u*mg#ee4e{9G2%nGT;>?%}^E1UQ_W z?tJq^|6I`-)dS4YABP3Smn|Wv%V%X$h@k9ZfD}Q>AFff2D3lKh2jfmT$Y*k)^ zT436a*L3~hvUhBMqQ0l@&c$`;N<0tH@U-aud56XMR63()sOIrnD=;&bdZEVqA9$iP z2^S?T2PJBG=q3&e2~4|+m*T(MwPnKtGWlM~SKDWr|alHJ)T=a_n8F z?VDC%k1W4h%d=p4#JqIUZ8By)|NJ-|DtD!ob0gv?@;9Z|pJ)1Ipx>si8GkJ${N}Z& zt`MrH2yKJ^M_SMkx7Q1P8BUimqJqUv;fmr+25x7#Eo0=p6 zTl~{YFt$=bE9AB*t-=kQ)#)!;Yx6g`V#Sj4Nc%G#TGbSp%*f^0k+BEKa#`ZsJrtgo z$Ci$Qzpd)qrE_sHjpdTf#lzGDOAC%sSK3?MRdv5 zZ5R8L>U)M*-D(Kf-EE0a%`>}eEKW80H+PuTSY1I+HA24(e?eReb%ep`i+kGq3Gb|} zHu*C=D2Wd-2(MQZq#6MBv-3pGDFo9#RGInt#4oTP3`ve&-+B!P>JOPRp&@O-#&g4w zWm_Z5DcGdxH2w{q_JawgayQHZpvKhP{2p$oL6Xq+FRId5k=XKxZd#$vWVX`m$eKig zb44j{;$}73uh$d~+AzlI_-=xEy2*84+8Qy8MxqJ^n_%#}r`r;%d>c%T+6pXSb^$&L z?`g7_ccn+1ouYX~M!AuB(XwAJhi^+`nfeOAfJaw_tH@QL9Z0>WNN4W2O8Uo<{g)2F2ba2t5CWjnM=HvZsFk7jLv|1rl zwn?-$sU)Dks2WkoW=esm;%gGoKNkk_=>{{yRnTaB84E&P0$&9jURN%OIfN_aPQmJX zZ<0E~ZhXlQOzJGZg$*HK01CGjL##9jcAc2V-BHc;D@7|ALcwET(3#iyy|V@h@cm;P z?x{E^$W zO+gTL%8VsA8zBczzZCy_U~C7kA2EU#QKQIvWj{^}GVwg9BLn;$j6gPVzcV@`kvh1o7rVC{VAjsmKnUib1BR`(xiM{- zNnhAdc8qd0U*1EW6fX;Fc%U>Ai70Q+zMF?-6h)P>r*`frd|QYL zVWy|pg%XV;nop*Ot^$26O@HdkADvI01JrT3sszINk8hX@0!4>xFVV z(_YTxhMC7BFo`A|)Y1#;X5bpL(Xrz_9GKg{AHaG9_%d?6{F#JYKa$rDjuBh>YK))T z3HZ0l@T|}-+}w}XGa%6Z6km1NeKTkHp9{(g+l3Pvy2J%Vj+(BDKLtFTp0{nUQejsz z3msVBo3m$bm1Jo<=)1SKkhC%)*k& zbaBfOK$9n=Dw%$4+-QO5l<#hTm8h_8xG9}^gYCkQ&Y|BNj_31NT2jUSeV8Nb(2tuQ z&UQ^IZz)Z5v1$95TK3~9^J5d)1OP9d8&bNKDG=w|F)WQKWbk>Kd~slMElyqAUOT0c zOg$4>g?AjkoP3izNM6{f%GZ8V@BQs_*J3yKvbCE1Gd&C`vf><-=ep$grxmZ}j3hPY zcmds3M2wOV`b$dMSOLYKYkw@$-kl*RO1NsvybRQctB~x3 zi50#gr;uN)MJiVvWDG&>iK)_dFrV;P(*BYx%BWtv<*c@6>iNQs1=k{yayk@uO%_p- zZ^p^^&iB2uJLg{EjP$sh0D!prC)3GP8#bIjYA-aRSG8O*ziA_7*2Yf(0OWmV8?@Z? zLR9_mW>nQYn_atrFAmcssB++#^Qjx}{#md0*Pw%jcy=ysmfeOj$9Zj&$7`l5I|a`W zvcB7A^SXwX0TE?*i2T%9pGN3YFXMYEmWd`}O~CG~Xn*_Cg%KWy9e{{K`_}g^Xw?-L z;;bJ{8an2IP=L%s%Ovm$p6cy-+iZ@E*(7a*sOi$3ebZ`<=Sjh~FTu4p<33eN-GxsX zuOR0;yFIOm4D$2EZ+fo62DSXqQ)7*%1MSl|pzA}_dL<~?8k1AX$GT@JV z0+y*xC}C1HkAHi>dUK0~*;eL=5nu4SB-<~y&)stQxX+PO^b@xvuN^et7{ymkai~jM znENSU|0R|bS_c`L(&IPVG(~h zs26m)gCsJkkbUd0Oq=RVv&{Lm>6xa)yph|ivh5V-=^yl^7V|#v(bF9KjQL)5Z*Xqg zW$12_DLF-5LF9Z%SY5ZoOy_w!Qg|Gyf$dZ3_sUysa4*VKk|@O5eb-@!9pm;h%vQDY zE%r2Zgw4hP=N^EtpTQ?wp=+=oVYUSI^=b+8TEyr@XAOS+_VX~B7wFR-f40=`=63e^ z={p^AnJYHpxl7}Djz1MRO>DGskN;$#wAQr6ukPx@;WtU2mRw4530tk+&#MOqU zJ|Y+Khv0dKOM|0V3$y85#$4l-&X#}JhQenG^miDP#@}XKZSWdd zetK{l0HKw7H58d@7LkZ@X8vMwdF6u!Quwi@cI?2-fef;-cre|MHH7NGe`W<}3sN(! zCU|1GBC@g9vY$j1wW`KxmDoK~`q+$1IvX*;Up7%}s3iOBSYArR8cZr=T3cf3l3_G)ul7 zvDvzO^Gm9js7rCS$mZ}2m1MH*5qPi-$=N0j*G*2icU>LpLOmW9g%8&R!s#Xae+A6B zj`o*eVZar=tl1melgXEO7AAjwY>6TC>V7B2WMrc=oa<0G#&{JysP3m{MP-3>!8S?* zB-yQ}v+I8!b2%%$H^VTG&UW`I$=>w@A+&jGLMHVeb?hmx%Ran^tUf?xeu#Lu-06p3 ztN8c}Qe}GPDXY$)N8WXo#j~EF^T}1QtIyObMLAu;33l4_f*Q-|(!nMIRKXrb@lrFV z99j*1+0|rTKtheBK_EG}NeHBFk6d;D|6~CZZP=>Z@H&nQ)1nvW#b5vSp(^L_UvpjwLRD=QoLkdZ zQAym1Epx#`*r%3n%h;TT70@&if?Tmf!A>ZH9>~D?(L$BqR`$lasqM@10+NZcr1n*n zHXr`})(KA^qka3E(Zcz{!_d=oGch(cU+bd)uLO_4d}JUbpXg8I_bw}N z5^ZeR=VSRxhBl2cNo!(^tc7()-zKrzz%kJ!mpwXUt_T*afQ9b+_r%N*wbMUjn5R{S z+S8`{e!npd6a4}d>IDN3G69q*I7KtqWR`@6k?^_|`qR;xQ7P|bj4n&N zsV;@7d<&mO^X#V6MV=H-XMekn1qqvUldfBF*T^*V7%Ob5O5E+s)^MC^n{|Wi$7?i4 zU2R%KUhPW1nYA?6AZVcL(D^m$rath;8&y9`mP!eUP_2 zcQT~E;(!COtXNrj|F>G@^|+&7h`?Iq8}~qWiZcWZNQ=+OgN{KkzW^>-RSw9c9$}Rn zWiI>is!_Yv&fwJsD_JVqGjhq%Quqd8;_?q=Tb@wy{4!_p9XdA@iF;&Lp6gG4$Zo^ zumtb4LMmx4vn@On{;fV;S$VsAt;6m66|s@f$Ad()iuudKc=F{TxXho^yVL7&V%Xif z5SV(vrFuJA$f}XUAS(0UWkYyRMuJP_@iKsr-`DA!dO*fs))4neTBDLTKp9d-vm9(q zfmu?$)8!{z%C7cwNTaRempL8)V%Jr0Jug33zH$UE3XZ!?Reo%Hh8{BoZ2W-+%P6wY z!`Q1wwIZf5m8CL+X)>fQ^Yr7`3zTMwa18Re$WHy>C157;HHF}I9F_KkT}*mFWO0P} z6G~51hOV7~Q2`gL!G*sH(B6}e`M|s4)O{e8Qah#6(#AE?Ho3E5vPo(dOb@Nj&ZQ4S z$Sr*_+CL9}JxappfN(X=&|t(GO5Oz5g320tE;Ap|Vd}wcc^orq1rL$$GGi1x_#qOXjLWeecElVj zvvM&YMJnen)d~)i$O5-c=uv*G000b5RwkH7hY61WdP{d>$WS!w2(48MKc4Ev9AV0E z|C$`>gB;3WR)`c5U{je9dO(joK{Fp9n?gKNi9@{@0nvowQ5;~ShQJM0k*W*MUC4Hd z5n^{OQIMJi5vHX%@ccQSylUUMcS0yEN_1Mwrfch3VSp?WPTp7H5PpCJBFjI1)v8I+ zVqv}VD5S8MaMZshjXB)=O@%u8<@rY!D-v;$ZGob2K0i$;KtX%qBd$Z;ttW1nxqNtN z508Tl+oT;uQ;oqH6XCwiV!Hp84c9&gj4=Ba$-~i8k}P~`+OmuquI19 zGzNuL=pMHe$GAnJuHa?1^k^y=+09iE#y&1>je zWSQ*j^RD{@Xw*{Zrb~bTzX)EAri&A6Q7R#6q!P0w>RC-zV~T(QpKfPq*a&>($1gYE z_>z5Xp=j&bwOK~`6svRiw~EZtrT2F8_KYS`bu~gE{-GkoCbYJ8uG-q^9sg=Op~F81 zaAA=}fQK2>=n1yv8!u_$%zJ{IVU|bL&@62=>Z5FRhx**bM+^HYllxkSF^zsXj`TvX zN}bv(`Yj>&qF`P=jQ*k4nfhD^v9Ac&po+5@v%H9xxYg2G>W#G=sUQ54*1K}}Te5%b z(P43BPdOR0!f=SsqNSX7Ho45gDSxzsgNF~%03;3+ZTAe0+XD%%OAU~C3f!ey^?xeV zjHg*SSwFUu}2W34R?g7=cQKf?K z0I)5j=yt-|xdDOr;4#&7#%^8FXpl3x+}L6@Ef8xDF1dOyqh7=0v5P1;B6G{9CBes| z_E|5Y{wt`->3ZH>7GVGDbQb-Ms4DZvyLo1gWfl@)&2`>0u-r{oDi4D`z{DPdF zRigDbBYe|&pKIDgN8k~V#J&{r&=~F!9a1fMETGy;Sj2on=s?sr1PR*K+o5sj*3ji8XI8Drt z*0tHm?xIn!%N(J-VI0?}A+aO!eCQ7Yn$?6BIXa39e9@9h?Tl?chc=Zx8-J!Wjf&wm zh*+6xWWBpd4)aK-2sIXuDLr!lO_m8wOqQ>W^|7btNeBd+b`Ex5c+9&SRjZ?&SRwmY z8+w6l+7md#5;U)siliFZaIP;AR}vZPynpqKnWFOo7$Z~1WG#%^X%#d?`Z^{qn3i5j zE+wnkhx>j&$oEmZ$&;11BrR(>z^R8S2WUxseSjis=tDH-w}Cn9aQ93AF3}_@7Hr|v zG1FCwXs$jIuXj>D3J`RsqUtx%rwWSE_T9hJl72;5f~*YJv|wr5fs zWK8C`!R9_8bsxHd&{ERF!yR&)eVbCuo$?)Ixzyk5j3o8jxz(MVI0%~46KJGBI;SWs z*IybH?Pc%jgN=)-6ZMu87#$PX-^O-R_Sru2e0qd0zHDt3(z<>Hz^~@W=2*C6HmKiu zC~2eS=mNZXce!~eo4apYx{(EYw!QD|UbUKVzrK8?OzpnLl&-Ou9SHc;Qc9LMJ47xY zI@I^=o(7&rl0{Gc&UzZp5xxqBk2;H*5=W+axIWXRkesd8E@d0k+y>JO|41zwMj!4* z>$r~TkPt2!_PA~XSSxlaAlM$j(-_yc*`K#*phPBJq5NETHYr|XKea+IFLq8`hswNk z61QEy5(vi9U7g7P+0Tf&TRNjaMyu)=_k87pHY7LAX7bjthGst*3x=<2zB>0erKO<7 z-ZNJe-d;-!pR7-@PDFlfR#Ul8`&7G>OLJp!5%_BUg|o8;1b&xZSJzZNU;EelT5YWl z*^pwH2oUf}Q(8=Cv^irDv?WT?>g>**wgo+!wv!w-#I$?^)AjIY1(D62cd2zn?wn;W z2>6sOrOM0|89dgw&Xr0xy^?0|9OL-oagNK->?=n^UZBglf2)JVNIDmZ|99|b%GAIk zYC84UO%MQf?3ii$i414jd~`A~}d;poT4aMK;AlYF3}V$&Viyt=m|2 z+rGrr#``fJwBBqb+rUg>ya!7P!#~AK>}WO1MprR!8a{`b(|NaY>&wl`=v4B?#&7Gv!RxAxP! z@d<>N$w-%#r;Qm8(-vIdqRgtb_Ql2o4d zWx-*_JAO>Z9opWZt|==OQ;uJf!fa>9!Nv7&nWo*7jQrSB;2?@{dGGC zQ`Ox5kA~z0+Gt6+;f5rUA6UQZDrwS!rP_h7>C&X4<8zZLd)QUzenwS;@Ce;P;iezg zmp|%=Hr5n`$o7YEtoZkYERGyOi2aogW2b21h<6b~+Vbeg(1V7RV5HBn8+)z)$b)7#jtnP!`v7se)w!1qX8#`2@up{18Q8C!;AOnLn4u%ZJ=F zGB&4xjiOE5?WrZYg?2Uu%yzERHj$+gvlCrPQe35VeQoXTMKiWYRNQRklq01}h<#K~ z)oJE(D3cTC-@lo?(j5r>Ut|FM6XL&RfVBMok-=*C7}#z8YSzY>8lx&#OD*=VcFPtC z^+GEPLuzvTd97XQn+o?LmFU_3W1jytMB2yd*T-WdK5Ci_*XP%Ga*Y}wkF;ex1#FQi zvg50(^)ASLY5Z;e$*~~X;aXVmwlUYN)w7q+Z0xvxt*&M3AIXcE9D8Z#SM%q6D(mSx z^^^5ib?Vpg{MZ+Iovd`Z@a7f}p}7Ao$0ytR+yw2OQafZ97v14N^Fo0Zg7jo@T7DKq z%+soi>bynpdr898iX0%`_}5%(&y|u)p}lC6zoAXp!cp7uPX$52^Ou{Ppsjcx(ru(W zSzc=C2p7+Kajx>38!D;EpwI7^hkd=25c z5HK2b(OZ=7R_NrYNs%(BEgB)B{XvEwU2`%!@SEH6FD?#tAVvVI9X7-XDmXKepS{4I+< zCJfn#b%t{=fujW&Im}~kdiP@But8I`r7iHi#fEWrxdRnDY%B|jS|az;FHqy)u}LX& z_aG0B+Kgw7Xl6|8(|CxC9hPXOJp;Bck$xXB{6P8sfL(?VX=5VZ{Ss(S6=yc-Zz%)B zdVzXbExZ$aD#w(A}@zv~a&);X)m! zeDE41%nh%hP!VLvl>RN4C|s1DW>?WW6$Ju>Lwz4 zlDmvCJ1G30JXX=4p?tz|nq5xU62dvJ+%T zRTsJ>Yr_$|hN$n;1xd!#kQ)W~7u$K#eF_D~g}zS@Y7HO;v_A-G;(H?aTi8loWG)Js z6*whpD_i6}3Z3-*BF7>uyEK3CEnfP|b>*DAC5#sDecLX+x*#TjTV1ii*#|(M65sRCKF?n%E=HKZ zJ@-R*x?<~*H||F(%df2>akk|36$@pdVpTuN@tm&!-bkmM!oDlGDn`fgyhc3GQS;iT z6WoCEHHtJbPzq+n51di!>F9z5biW)bd;Saq_sm$A-1&wXeAaboZLVvzaC5 zbp`mqv+1>%gX9sGZ}M(D-$?gydcpJ{>d?oG-eH@;DFm+$JtF*ce`e@arT@SMz|SSX ziL`ZSW3MH1-f-LnX}BlMyFPFH?k`GfP^|$K*Loj|k~)2RS(Dih0ydG31BK0hWz$&R zcRWB)x$B|$N#7Z9a}a_d1UFgc`y{4i6v93|wgme%+FgOEc7IWA?NYQ_?!(o?Zp#l! zj_iBJu5wr1oO%s3cT{_oI#nWo2SXUX24|+xMH-LO78Ccg3wTQRk~Icd@n@w^9hi)G zvwFh$MuYypDr*A`RQc@)MHWj;bZV*T-Tcm|dIdx0?f1%=5gWUCKSSMWn1;lFn zXtlFSJyLwh+4K|RsXCAPfr1twyxr5fCn3hFW^&a}calI@SW}nJkZ?fZF#RgEmchrf z*s+yO(?*Nyx;T5$Wa_@$*rWx!_Ts9|qes0}Mz47wuJd-v(qoL*N@Ov0Sr^2lMg zh_Jzhmivj)RmO{gV%ft^FW>Y$d4>xS#9d3Ms;;kHFSXI%(E7(iJi?n)x z>Su5!Ge`4s9V)`|cN2BwJK4vozo6zH`_TpcFLZ?4DY(Z4FE-3X=pN>di+b<|mlIws z$(_%o;GUtXP~t0hlTX>**VH4BDN}xIIK&=SYb;1&x(GJOcf6cfOmLYMl0?h=1SQ)igA?M{_ z5lv%hj~PbvIY9E8`YV+(6F+)+nEWtz2_6VOF30M)g)w3y)pa$Jm3!BPK)($NS`BR@ zL@c)A%o*_d4yvZn#Z%r&yDqVDkbM8=d_}5XMY*sC~_3lx0fW=HA5y2bxAllWG&!c=NQo}#Y zn0F2OUPJ7>hwT1Sa*AX&i~>>jS!f2+3MNGT_{?>ZrBgYQw_aEpsk{WeFFJ^qN2bs} z_S8Ahd+PGAb?u&}OhLz6lo_Ch26OQ2gn)VH?VwX58)|{0QaQC#0RdhJ{ zlzEQ8?^CoT6fT+SAoJV8w01}E^{DdQAfC?pB* zaT_zx1?{p`iZv~S1S$=LhCGAv!Nkb97@p1%LKFoFAJH3hp2;;&nUD8s1T)JA9zr+( zGs;k*U)=4eI@=Z_e@ly}{)`=3*VOFTxZv+oG@_d*KZ(&+VgJ0%!R})2zZoQ7PTGzK z0+leJi#Oi^G0D|2!PMjD`8Mc$bKyY+7xOHrhp%a4GvWEL$?C7|*I}M6!i~DsLd-n?GrTxx&2Jo)%#X86-{y;k8dO6UOVSUi{hF=E zv)@h-#N8&WG!zb2Mv7M`m%%{dIzUL!X*m$?c&^1SuzSjfyrc=tty{cYN=B{%&^K7c zf@|>aY&FOCKrc1@N1?({%~Zp6iIyga0O} z`r+aR_bM`RG;6{$etC1HPvZfg^4j&en04+&73EAfdkSe+h_50~h_MtXPEzs6! zQoU*&xZE`^v~ z+^W;b$1En~X*bN5mmiwG$LYS_){71o{YG>KnHKTz{YE1^BK-B0Z;QrkI=8~EV4*#eChvZM>Ll5tub3c{;!< zpW>CD&>7OH9zr-a8Ubg#A%aY7dJNqS+=G9*EBy9K){5(i4jP?i&z2-29IbCnO{0w_2R6QqCy|L^(D2mSZf#d0$Yz0NW$9uUd!aQxnT9T`soigEl z>#yCq_#82b4E_k2UV25Z-*2Dh3>0W^qGbY%65v}eT2{WD#5HOkUfDUs6vYB?p$G{w z&&5XX!)2i|wAOsZ_-E{@g3=|z(6z(5U-0fm=jq2G0%9+{^Ca)?=_S1X59>9G4;VJ% zU}fk2U(Hv8)moxf#2#T~=URC4LId)A8sof`b_bJu#}e-_ zC|>`kGy&rQb>f1U;xqd_plAP+_@bD3T@ly8nYBNyl$H~t<4dl^0d$p_d>%?!5tp*g3r#NgNI;C>$4Bu~`mFv2OwUE)*u|JD9_kZ$;3SGv1Ojes z$Q8o|h6du;2%ymVvrXcXtP)03CDqkZt5!cS{HPAMB8+4JG?VCnn}~y_f!jwc1+JtJ zwSf6Tuc6d{C+<j+qTvf8J4g?9aa6Jsk_Pm2#TdJoS!!J@%fJ%%ptG z-=_nF{a)_?`ARLV?rf2VXb@ucH6*{k%YGoxV(=c?soNfIzleO2bf)X+e$l_zDfF&^ z5MlX)#~SrXSh>eVVhE6vL2OH)VkAX~jpzt74~nzR?(XJacVBFLea{2G7W%+tVSz=4 z!l6yiH8cD${JmAs7i=0@O4p{G5t=ZivGY!O1XS2 zCbgazB2iWNYi!8L8AX5k&a=)=wxT8<0|bMKLbfowYr7aILR)HFAzy zt5Sp*G6Q`v-&*~?h;*yCne0(EvBfgm(or2ir7M$(g||Hw2(tg=clygUzSlt3R*16> zU3;o`OKHZ=fv&HD5P$tO7Y0UU0i|1vRP5oO#2&Zuw^9vnLS?<}wS-~wMC}Jd4olYG z!MVNVAm=HVxT!uiywYD7Vam8H+Ku`u)F#lF7lxlrw}Ft&DVYmGrOAvm(wvMDSV`i5 z#I0Yz1m|_H=b%bifQ*+HcEejqOjV^%LFFEVIKj#b>q$48E+pFOa>G`Mn}6jA$O>hi&wVD>bd|9N-z*sLiG zm5VY?GwY{fOZZX5rwk9$(sU!63)}=77zJ$xzt72Z#YwTvbDOMccaYB>3jiWEX7W=- z@Z~&7{%a7t$mMw&i&rWPVtG#rI{$y!#Poq&DOVzPKr9I7pB!j)WvUYo{CR6(hYgsE zTw-#Eeh}32jeNj2Cc*WPD~R*)RU~xu0{Jpic29Fko}V>WTk^i!_PoA3-yjrz`G-DV za9aih1BqjnZe+~P55V~4fs3w;Ka;&aO>lKzy{@K0kQ=MzN0*vX1#?_L+XSf;sKbiE z>Phr8^QOgVLAN}Pt*|KXAkL#SBu`Ui3B_6FjVqn%LY4f{g#6-U>Z4kV*$Zt2`c=lz zQbAc|5geFyJk!+X9gfI+cxiX0?N2P5_D15)BIIoK9atyKFTk zR%*<}lh1JH!w22>%3r0%WdgYh&&0KKhl5;Rt%?x*#n7a>7Ly303}v z;o#-pL;H6(&H$M{bpA}Xb3E#9?6856GzJquLs}O0)vL9YG@fom!r;Ye-yD8h)SH34 zTXBc&)P80*ztnTRtFlNf`$>DL_w_eXl8*X^NJ}dFWm1NB#aLy|iNwd_@Z!eJFGR8L zs40czG@f$gND1BYOremR+J4~F%WCzm&m#T1ZNle5`2cWh33>~l!zWO@$jMcJFja4- zJ>CHsr?9DJI(X~IOHa>r3%9(fRyV!$o91CFt=j>7$s?4A?vI&Re|}StV7e|%)3b^z<`M|@f+HRs zKlk3rRs+m})~2zkQn{#0IHwq#QrC&|_b((@I9x|rLYd^KaebHZTQebLE5Q@Wp-;=j z?I&Qal|gR%>o1q;>-r(M#Pp&U+HMU@uaaCwm=>) z78uXB%KA1qGv*v%GGRbivdNU_k~(Ay@NQqR!AOzwEC2rIX?_={0iIq1 zb$zP3S&J;LRzh9--V3AKpFxRJzWpT5F8f{U^CXR%z0{P%r^ZJvdh1lY^B%LTx*9@o zh|pNuW5zf)chtNHGExDvsaGH4to&t&mXt2@$mcKz&jhT2~#2Q0YWyC0>mr5%e!d5XirrOrzDy0?tM7P2EY*HXcBH=0Iw4B^uaz25UIRrKNUpkz-N-hlihLSrP46L|D8`-uqIk z%iEi^X95Ih&d_RQo$<0nUU5M~1c%lIUAM1hgIPh3nL#hRLB@&&kKiw!ttP!cUgXkE z$z*d~7N^gh5?CwChfMws6$zxX5-0?QFy$Hsh9pF&4GI7|a8t^8x;qR|5Li*;VXWa8 z5F^Y?wM_!FW!7DFEkcLE^#ztF(W8Mv$7tu_F|9>pp#RtcA9Ps|rB0ZT8rtPXC-KZ1 zx{$AlH8}_VESI1}fxw%eY7$s{7WQbigV6iQI*eID<-Qkx!pWd4`BG5Pkc~y}!9Xdx zE*%vtIn@3#wPO%9%R=Tt58rX`pURIQep5p zj4sG+`;T_QJbb@gU_}sz@*r67(RD)mX<+)5X(u&4{KA_;KU$6eFvJ zo&wlPFyIL87N>0~p@Wm#3GfIIqC^$Xpk^czLTAoE>5L`Om{x~IYS?&jV>4P686}}F z6#=5h?w5#>a%`jlu$kDuDJW4x|EXiq;p*|y@&o3Z5voHuX33Yqwbun!U5+5K);nxa z2UqhMekFpiv)`*OWh-3GmDymd#BMqi{n_Y37iU>eQQm75aOv78^I9() zCv2+yLC|p!LFlqDa%QcDpv|w7cKys8*36pf2ISfS+SB;OE#@)S0m9 zWiRe@u}qlAUNO-p$GNmb0Gb^iPtQ)R%N}&vr>&=H zGU~sVi?P>2mVd_?0(?EuuSSkj8`L^JqJN8oMfAMT0njd&JD!0MSfc=tNdb@&4pA%i4Gj!bR$4-e^ajr{y!RKncu%tWC`7i9ZQ zBP)UP$je=WWr00|&uv><0poD#w8WI6JNIq)2YHC6(W2+`C8C<(m?}h}D=s|87!9g`HdK=5VEE1OD zi{&&crx8=G`@Dox{P@svS;cHeaj)0{l!Wu0+Qp|Z-{H%|TC%A}mvQ&fwLR0>YZ zg!U(-*kZ6p zSa#`qp4zp`>8XkSme%UonY@fxfh^eF@CJ*z5V**TkK;)VQRRZse=6FKXti(VNz47yZ6)WqhtQCnrFYXzw^ke(dl;urw`-h}u)ejI^i-(p|ts;iTXjs{aG_K%UL zqm|mnR8AlN)aI?n;||@;C?(2V5K|{2oshCFNYwg|H*q!qhI+_6WzBr*OSKg(ziH+&{ALR1vo)~`H>UT3ijS*~Y|YHkr>sH(zPg~)@-_-i?$sl{zs=mU7ih?@ z-xsCh^M^P#iOZ6`J51d$_Dr~0jz1Ijc1t+mZ0Zvb8aV-xM1FuDf8Je)I1|Rr^rmy; z>6~{s@b>u5N%%3*7*Q4P8MBt-?3K@@%j(1>+J9;_;?%}9Xj-@~;rfGSwMa);4pZ)A zmj0^Ko)Lf8idl&Hv2?S}ZaUwz>bdwKH3{8WVY|3tegq93d)BZzt8nSQr9#1m5O7D9 z;#levL*Ukg|Lf@p0lv3lwCs2iadQ7mtJ{=$n4y+J%0*^*u z=~^=eMszc9ue3-?2VFPQ&#&0MCzQ>DK_`*1XSsVsa1rjsGe}zNseO z?+2H>nt-E-rH|Ug!K~;sIds6nlgI99Se|Cy?rp%=%7Xn`T|Xu^@N-%C|3Sl1u^ZEC9F*SYFdv=EHRIpD<=;8(ER0~ zIsSC`kY|vmDuWwMvG%ukP1Luk8~H{VU1YVaji@&QNbEzweqtrO26>?QC^A~HQbEbm zg*5JG@lflMW~GBSO1B;Y|AJ|LRLuue~IV)$YPSP~tcJ3P69a{JNm* zDZaWPCazj2Q=|4LHjR^GrJhNZedG=2aaVSxU-E-Yr{t#pSz#B(!G@KK){AbJ?BjV9 zGs@&SZ-Y`~uWwl+^!n(IPC>|c*wCIYQJnjbIZHf{DZd+ULs}jIb4hUBVHwVD?6jI? z6vk1b@Mij4;!P$%Na(L64wz%BQ|4%(gW$y}@I7@IkpHwEl=pF5=@<=8#smiZgeCcP zsv46yN3FwPMcguwYG)HWSakCV8+dqjfmHKQ_Mxlv6JsO`4of-}wsqlGK9XrSAyOHZ zd$H~p+`)x$(kPB0PXqkvi#T9~7&lX!7NO|x^cI{cPaP9ADvUGxfcd=@=qB_u#+#E> zYxL~cH+r6U*Cg8X1Cm^TzAEG4x~=e>A_!B&WLWEqDDnTvJYfJ*Xq ziW~?1N+4BtE$E~zWnJWMB(&*|r*h0I%O??aEJvk*=Yd?AyJTykc!@i&yC@8zYUNq5a1K+zn9cZAOxa%2SZv34xeHtpjSPb4?77I5p(6 z%K{=RGXaMp_=WByT%Pf|pgsTb(#hP;i=N1Wcln_G(|Yk&FHp3M?m_-J@m5DH!rT7q z%Ksdyy}O|_7A+#FlxSOPW4&D!eWBC<;xcURvU(>_{x<(+n+daO8ThN1U~Z zLzyYS{hQsch2Mg!S=Ov_irSLV>h6S;t;IKO~m$ofhHJ%qqn&WqsyFXclU zm78wll|Ta1!iH@jec~`)B_M+iwEg!~cGmwL(vK?Jk3{~LEAauqFfM+O@098%ab^9x zQ9uF-PHQ#1H5bbFKg}i2rz9yhAzI3X+NU}e;Ul8EW3Le#^8w#IA_y>QtC1ZA5ug9l zEC+lDBM&hD9#@hz;Ni>vRvd6;smtxKS?Xvcz-AK2oa#R`*E5W!c^RehL>#XPXJUYI z3~tH+K;2=Oa>@ZX2+H09Fej9+L!nM%ZQ@w{OI^F*!o^^b*nJKtLDl ze40D99uF+hYN_{8-W9Rvu~aOoSJUeTLEe>*v|7p*P~4mUN(=HqM(S|=xN9epQx9SDY^kOmj^ zwr|=G-^3CB3=aKF%MY*MgcMvsUn~3(TOtsPGC28seqokUO(3Tp(Zb};n7ce~An#9g zs9U%*nhN7ar>ayvgTaJ>=Tiz}Ps#)d5OrQp{r~uS%cwe{Zd(v{cXxMphv4q+?(T31 z?(Q1gA-KB}++Bk^1c%Tk-@UKjxZSV&UyV`wRMpsZcI~y+TyxHmPoAGOKrZ%rlBYHu z*(ir45>zLs3V~!QMjbhXa(Qnr5~4dAWZa~XcgqCBCe#`txO=c*m>rUe;D#1v<>F|Q znlje#S5Lm7M3HO_TjK+NxmicO|W^h z5u$-7d0PN`eB7jBR>UFcyNGZMI9y@??F{Y5MDJw9e^2UJ^V2P3jU4z6;iwJlUCAQb z6+3Nt7*9}}80)trT)U?uJ636-n!%uZlM4E0G*q{3>W?f;x7@~hSr!ZKaP46-G4Qmm zgHn<2e$_#~D?RJgTlk1X?R5|aF1C@1bo_w4$$t}y!E@`Gz=`mkuiRpH@Zl)nCvwkj zT?GbBAgG`<^+>)L;C<7jbZM3FXj5dZbGk+9R3j**K<)2s+x*PylV&> zeML-w@@yyP%)+n9x5KPPTMPYR$uvQ@1agx^HGjHK0t;_B;wdm=NzvlKpx7}5e!$_~ z%Zy%ch4hJhnv*iGo$K?NodwJcufUDFYT~y zMt1MYYEEz9&x3pjrLq~o{Aq0kLpQBH4ab_V<*k2>fXxLmh{(gy$Xv0zv%|NBv$r=s zh`Dxnu$!@VnWf~O`^iRf675Lo5x%2yzTvrSnd|7n6<&QB%bXoIHumM~U)rClho0xY zhn~nQ&Fo0V%Rm=7i_z?WS6zhum2DG)0s_DMCYM)`2>U*dc&=Xns1d<(!lNJFv?$j1 zS^Hk*_Y{%FGYWNFL%|jjjGB&c8DNn_LFQbW%~h^?m7!1d?R6!GME4)F80pz{QYfqVn8UzCR9;nF*cMzpDr1dnYh!tTC7dU`pUAUD zbaNwZnf53lc{L8(X}Th;m#~b5@oYP>70ilS5XPtxRdkk5j){?8|y~VDl#>frLNZvbhUmDO#9+u@fDAOxU0x= zR&=$H+a}Hv@WlGpZ{WfkN$N>^nEohQ^^cNTZ4uH-(Fe+}zvf4^p7$WIi&fhLF^cgF zSv=j3?A-TAp->LH_vIBpE!LEPq1OoANOtAW)W>JYm?VF!5q*6R#+h_ud`F2s`*i>AQy@%kYj$^w7V7?-Vb)(x z8Sb`51c>h12jkK!T5I1%JF}divTRIF(t3sjY7-8Q#-o>{8+k3QGR(}JpqOJA3d)>B zi6hWHH~D&>jPTv!<9=oPbguO0vni3%W8xgCyanL3z?ynbze_n27I3$_4sjiQNc z@ygSZ1e?6|cdieNn7`x^RLIYGOC$3BHZKpi;$QTcyj3SEKdAO=|9tged1}U?>13tH zqxrq#%#P^DylSDQF<$J#6n1E|I8?G*{FbQPNlkvk0L_(^GPA@ss2<0GobSV1v=}W! z3{XlgCz>VD&NJm9lI`&ge|g*AkW10E(64@1(uudR^j?;$Z9i&K{FFk5PtirNi_jqo zbgELJ{1dK{lRk({_m$v#*a%Awv_gE2NnPnm|LM_oMwISh_HcNo$K&zP+Ht!Hrttb( z3Bj1W(LtgcHIwNilNz@uYCeAwe*w>B22ew^SN}mHqvOC41{h%SuXmjB&ZzdvQyMe5 zQ>pHI1Gze{+g(L7*je_l7d}MqwT-X3N6|g7G?(%TPYc}N7@Emt>2^5M9r~dg1%HPn z#3H#ztQMSGTpp^lWu!Vi>%xSy19@krsu8|xzF~E@=QF*nyI|>}!RRW}YxPG&~ksB@b^t+J$_=KQ8DP$o8(BN?#;ETJCEslaZEU$ec&6 z(V;q|EV^BCD@d`3nr3upt~w;?j%XBc`n+Mg_C1L+BBdNj0nEPf4Ksq`MUkR6BT78Y zR(#z=vp1ySQcu9T;uMuPz<1V;29VhQ5r>>k<+ihH%=!uVM2A-*>Hc`UtfCx@Kz}0fGoxUsRozN#D z`gSKJerNNPgYYz)ch%bqGj3_e%@8AKxHdogX`b$`j)Ic@Mnz%eB1FM`0vP-9dlbi2 zI?^o|ub8APzVB|aOa{1)(R|r z|F=8W`u}R~k1ECTYsVjpafzXnt>H5#G#n=DWBt0}zy7lF0-AGWWEdF*4?Ckm0=pmX zSB1C!UX|u7vpT(fDn@R%|1;<6>-+GQ!|nro-rob8Bc6T%KI|yi#kL8!xo4VTZ{B!& z1*Ct^)QHUU6#wB>J>LF#&jBA+3U9Qwd6IFnyRLAn5dO7v^)SoajWgm{(ARx={FDdC zns1v0^nE6=KAwLOm~F5fKN_pDQ;GRP^C~?zzb;-q2pa{y_*Y`=r#VEMH2URMPlp1& zE~AqFT4_!wCx0Qn-u%50{QQ>1bTh|PI^?#Wud2fDxKx&=G6~6P+p|2%@H}4aFWxhT z?~1X`lW1Ny2(r%*Dx7tVRt2DVdbOK#OGs0t2X(GeMo)<}Of^0+c?3ndT1!lk zr1(->k-Kyeizg1Qbk*i{k0|$F+p6aS4pvGGpQ(HX=QfRHZJ{0;ZaV(7=1w^Bf{WgS*2NvZ7Tjsoq(}sY*ol{ zoiA#?P91cZAIF<4wP?#dDw1kF^X}N9X(Fvi23wzN^=~=ahd{*bX2w6LQe5Yf@cIf^ z_PvB=Ao~#6)jMz7oaxy-^E5vAlE5>A>wz8lBQ>g9GSE~^;8IRP$!9cEKEBY`P}s%W z$T1c0+htGpwXmF1h|$3s3=m~<7^K%P!vC|0VfD_Cz}?Jj%rftqo**~J(Rt?I5}ZxN z({f3zzExshfvMJY%Lf}GDoFS2lMzl^p^UK@wfi7#mSq$dHz$8Y7E!yY-~th3={)nakSr7IdvoY z#|Dv2M6Bh9$tjmArBFM7hdzE}lg;Xlbha}8{~rM}Gr9sG3==x}$2lp5SfA?*`RU`U zF3U#Q3%m<+aq3yLb9@5u%HlISzctfkqZ$i6dVU4~M{rQ~07p=hr%f~pzXST-?$)oz z)VOgkgKtwrLg@^K|$04j*3!7g6K@^lpPvA^%=S}22T4Ua0zDLM8x-b?inYtzK+;xQ9}Dj?%fcmhP*XWHG-Y5 zNKM(sz3~>Ie57N%Uff9F4;SAlm*Tuy)s_HF!y40|ed2IdYjS(2=t4WDQ}C#~@5Yc;El1*38j2^|miyupAcV^-D!YE)r&d z{SuJ5I?F!HwNmmq6#VA@o%BQM>ST@b268W1&u+L3jLy;yO^#HYyTH+qC!i!p8vyy- z<9`Ud8+s6ccq9IzkQHB6dQ5>`Ca?0)j4>JGs&6mRbGO}^8l#bs-y?~sn5Sjr8K~zy zXk?W?T0k-98_35Cx-o02zaT+Ax5iU`nVgji56S zj&ljYx@Ivf5}YQmLq;!wai9S~4cKASx?mBb%5;?XNjg&v3I3pCl;F&VH41+3zK6yU z=`QD-dU=Np9HNGLLQU@&heF2lcKHMHnIQ(YPwf^wYku)v>>q46G0?G&+C^8BwfRE7 zlo9gobV|JnLlzKA*QpHg{RNaAM1b_Ww#kf84+j75nBeV!-THNh^^Wa5!1RQ*vukrT z8{5B$nf|uQd@N)QhOipv#t!nlQEjzl@vPb<5CKa#++fR;t9q)ReCK<=Ny&O6Hha*^ zK3>3{-0>YD%+jJ`8!Mr!IV%D${Kmm2^%+E9-l%`iIZj)o6$nda|K>@nQksrYl8=ic zzKmr8``>>bK&F3Kg@5UKq26#|2pOJaw^wV_BnHOCcb5|TWh9MM+P@jx`l33kz2i!p z@@CsU4i;7zkN$Yc>uzE8$FmU}mPY5@lL+U`HB!UApaMd_n;RJ;oHt?>?$uR}XKeFNEsNff0M%bp0UoOyf9tn3^RzTPB{ck3 zjI1IwTD-V`)_0W!8{OjRd$ZMlE6m@8CW(vZC%!Ozi>kKkWNO%P2!G=EGjrk}i+ms+ z^J$$_IbC(boal6Lp8eXBDV`aSGpwF#BB$GzjUwD?*Jm6?=;<(S#YT<+U$G@cJ_$MP z@Ii{?0iYtr0)l<4dw2-3R0tU4Hyf1+Z?+eU+`C8p>d%Cjg2y^=R=zv-@F3+gGg;r{ zR%OVwcL=OTAd)}o>ySd#vnY3Dw0dF27<=jOK?^vO3L8@x?$2UMqPH5C80qQ9^BFWQ zv(0btMW9+W=3}f+K0ALFJ@n<@6`l(d_)`R0>#j2iZE;;h)DROHnD8ALS44Al98bzJa^ z8KCf#Rcfu3>dx_L)vd3QvR@-MHkZAMu=3Aa#k_b_)MCNvxak-_Yit3awKWF96C1ji z0Sf9qK*k__+&3NY1afMGj*lk4yzitC*UX5ET=G_190W2#4%4cp#{vmf7&*Hl%WYk< zh8M}WpK$VAunSHv!p*Rn+aC5i>rlE*-&w+aeuJaiwWc?%{FT|#HzX0=Z7059W5&Y! zlVt}VzR+y(=Wssp#<$y;d&$3jAT4Lh}OmMu?Fk7$}q9HlsmJ;!v!rFk0jNN7xV=h;U- zIQBxYzvIsEc}8Aa+rs#{k`emK%XjJUxDxn{v4gC!CY{H9qL=1)@F;MLYbc^%a{%({ zXT@Ku>E``8xv{i+_`J_b;$SbCjcy;=0mnbHd(x0spX$R>^vI_f)-P_Px^uZb?} zRlAgJx#>tl>)3346TlVzg^9cxVM}Ph1R8yxY0SJrnkTpP{UzJ% zen0(aoR7^n-CNw>VvkvGh99f{y@;Nd0&a7PE|@Rw^w)zzY*Eg#{0OiZlyce+{@Lso zDA7|O4`n@87~YxMODUEf^N&SDFFTtzTjaG3#G@rDpx8|@k@4mk91ll>d{BIq_xgtrlfrV8m`DSg0@+2x3f3|{!6 zmdcj9Y6lV*d7y;n0zPG!YZ)pDEX13AP2PbaPKj44;{177iO|(Lt0=IdkDgTZhmM|K z@`6S^BE^gkw}QYN2xkl)pQ+IP@Jd9S=YydQ;DhP04$@*SQa{r;1}`8yoJ6LccV|=1 zLiYEJwR`wefiai!?~uM!37S;c`wB)wHtjD6O2h6S$8*3qtn`7T{h?Jet$x3i0~+t) zWY3yx=N9--qY3s#Ryxf)()YClhYc^HCo^`9tPje}Wf71wd#>L%i!n*kMl|#k&g^LR zMS9NX!P5N8Hs%6tnA#AFdKMP4mMCH?R1H{2``*ydE_-5(v+om7Dp>GHhRU%8L)cG0 ztX>4D6zBop-A5VBf&Cz$e;#r)bv#-V=UZCFq*(O9RH8itW zzjg@Br_A{7eIFOCUV^YLQ63Be9qrJhs@fxxv;km#RTgF8aIx?Psw+bJcn6y}rEZ3k z3yspq1v}NA>UKY|4$o`ljOX=>H&VnT+ukw+^!R4cE(rvVP8uP7!J^51hap**=U|Aq)(+Lgen9A_zm%xG0N3pTW*- zNYjFlA6M6F6@kfXH0L7z-d*lUi=s(R%QBaE(R7<+N)n%3mc{=ruZ!=-ut-uza}#mE z*s*jMjOfFX4$j&r=W(a@N}kVDQ-Cbrhj&OJN8cl@JbI=6sXr)x&1nHbq;=@HKvUO! zh(ES%T^tVig&i_{1^0ia$QgaE;F$jr^UgSQ0jK+ag6{t-Ck9G<|NNH{bFi@d&z$(k zKrdk%h@bBox#Yu3?B`)9V`vw6KWq((07N!RXp+HXzJ!$xExpmDqy&yPWbDj(4kFR4 zgph=H!r6dH@iYGQS3_6(=haDuk>P(O#eWa~<5<1Vp{ z&%2||oAs-)ua{M6M}n?@ly@8SokwwhpTzMzo$p01k`uK+O@;TO`$YzfbS8fjVxb=Y z_ff||d#b-30dMmL=v`Y^{p- zjx{DPILcqHoVhNdjpSvP9ul_k+A(a>>lc30fviX`v(R2 z-VA+~@ITs(&F(24NrNDeNEV$KQAoy{%1=0-SE&T6uM?4TrzaKUG`_=(cLCx2Z+D7m zbUKb=_>St8XtyVah!sdJtiJ+s)Q(04$%i}Y8Afw8v5C;lruQ^LptW5nT4j3p)z%*x zUcz=#%gc)oiHvxi7(VHw03ZtLA{8dTky>raLpP^~+QLR5=)8O92c^w+L2WHy&1lFu z3z^cs(v(jfusnMT25@pvk1*kLM!l4HiH~q|=VB@_@bDLiX>N*SsqSYpYJ_U&_M2a= z)35)F7@8oMT;pDqE{!h3OsY#7#&^Qr6MqNZShfjdJ-fa%Hv{Hqx8=$)_aV2@WG5b?GgIfWJ%h0t#!C3*qP-|EDI^nR_Ah?q}Zq8KZt9d)g>~Y zi5xcY_0#|KbX!g8Apg_h#&+ys?lLe6(_TjS+wxe|z^3$Du~b|!xlp2sd& zDVjjE{zmMxfdLq%_mJY7)ORW1%D6U%`3a1M-RIREY`uZ{;FoDsfd{@#_T0dhl9^4U zldNl7tD<|ROIOpj!zy0Y_HZA~%T@??t*WV(1APQ@n?c?DIG_I2sb1Rh^ZaNLncYp+ z=xt9Xj8z4{ik>xx6{TID!~NfxY!x`TX+?h)eZb!5ngPoL=I3&)8X218&X(nZ%e2&0 zqr+?;;0hB$#;r22h(F89D2IDYUE>1z>@ETX?# z)^e!^fO@5e(p#i!^^^Ewui}rF5083HS8(Zu2w?aATzdeo=ijUqcv+^CLtc4Zo_GUHQRET#iTHpld zfBJ_cX+yS$$1GZ_;o-)s&29N^4JuIjg`9aU!vM@eMqFarq*yzQv?uwEGD<8L|9s@o zS$T5C=$i=`1eQTjF1qc!E_0`xS&G$oXl4m1&r)f~8j zG7!OSKup&bI~j=fdy%}t4{m;PVXV;&&O7?>VSZ=S#9@Wa+bw8Ecgi-($vg)2Xw8*W z)>@jX#kH%ZAt#@k%)NIx4 zeA}L>(5SQ+YIt^N9SVOCO#>8UtE0R6in#@3m0jDO_QXH$AOK7OhyGtr z=bfO34qtcbH^t_4YYU6FHFlz z{wI360!CoTJ1W3_3hd;!W@ z?En<+s#LlN1BP6HYHSr?%+(~C1B|5N_17jvEV!(j%=Fijv~_V$r=cAF6G@$fUC!A` zRj5|E)3G0pS`&tnS|OXz%h5>zAJ%Y92w2TJBm5WC0c}6wO;8YT&m~Iebe^ofp0RiL zZ@3#CP`+J9kdl3b|5i#&)h{t0-=J_E1qi{(MxX%P3B)4z=R!(x+ua^t1g26jr{ZoN zb32LCV|Od{-)GoJWRBs>xD7yVH928Kbng?TeJ(CWK!!Q5W!D22m_79at zYW}(<3+HeJ6ORcd30*J4!~6GJG5}pYO@EMvK)Tiw{8t5!)QXS1w=*%4@Bo!(ErRt@ zM=UAm`-G3B5g@P9D?_^Fh;GMdvc1c2w*55^;!rXs$*@=^bIrpRJ+VQKshP-@%FY+Z zs8_7b!3D=T&U7R&9z@kV6y%j-BP>dL9XM4r?8Lk+nSi}vJOA-N9UW1p0ElFhW)j11 zLkHWgEi*#)Tjr1HAkm%CDFWfbCV^0WU22G|Yp6);GS)oOreI(s>`9>ON9d+wmXL3#92E4~Aa7*Rt znuSp1=P`f{74EWnK5HgzfJ_o>7smigM71QjW>~b!B2v8+ZELA^SN3|JlLk~=d% z*{bpJ@s)HQ&i2lEGCGAwxcJvenD@)QkxU@S)~aplppr+up?*!;08Zf5+$dhMw=_I_ z`IxI%e-ct-X{@z{D*@MPh`M>4$>EDn(i*8g#dV&?6LO?p)EY-p7ird+9;nwyjRF`u z(~--sm526HO{$=LR1k9~4ur*QC(Nw2$`%rkJZu!jnayDfl9Kl-gBYH*cFD)^0`O3R zco@=w;^j=qzW$E@fG@4=_=nC#W4q_{xj}(m9uA?rqWaBTeiiDly@F|Fmb779md~`a zbF2ANt~~|Ci=&F8#WGAIuXql!`+!Fa8QVgsPDCnZQa}w~<~%5&t=hLdEuC?%&j$;_ zkA#rv;lH>Av1rLB(<|kQJgDe!r^vFz;3^wj{zCK>w=}5_019K=K7P&zpO|$KTQ+l# zCqKGNc_X&$l;|1#XM@Zp@LCSKCTh9y16pw!kuvf8iDDCVgufpd)Mdi!Y}pTAUo4OLMqm-h>PWiG$&_f}g)FIbA6ndP4s z{w5`=%Bj^q2h>(k*4%z4v$Ca( z1u?O*xTm>0Wlwo*IMA0HVR2li%B`C@oh|UlqFz5^758|0^>t$_Jw(4JF#51f^;m*ZLt9=218MKn%RP_`$>` zgCbM={j`ETGr)-g1<*hHu*Rk7*$v!=c#Kn9gV1Il2 zlQ{?UKf4bf1Hl)>e{Da=ysIDt)F#MnOgzHeJOl)j$8bc? zG7G4fBmxMkq!Z~iyltBeK+>mRg+Rh(Du@qlR<+RURA7Ka!l|d(WMIqpok#5!TC*I^ z@7s4{N!O`5U^1b3aGe@6XCE>y;MTtDz(J~eehLt$(!@lpjt+?vonh3n<$XNvc<-bk z7Su+zuFzWUuC`s^#F|0Jh>$mySIKBC$Ku-w9@A=FpokPP z!uSUiQ6|Z5=`__;(XM0@+^_4`i^FG;+P(Do_fs({#@imENouZybSy*LKefh^7VGLo zsEDyWoX4|>E$}VLQbC8Z~wxBWt>K5c)vpae=BPnyg>q$wYhjX{s#ztWw7pO z-i8{ms`bYWq^*Nl1jV>S`@gKRT?imNLHNIrL*+1^&wJax`B<_Mi5BZE>sKL741IF- z{k(lZME=rYW&(V@o@JC*uwhyIMU7*0p@6j7PF9T zS_b~eLM<~PI6ppM!MGCq0+3^u*DDR1W+x+zu%{#uv{R8^nMyjZx_&Ra4Qy+umx~NH z#*=QI)b_&PKb~eY(@!{;6Y>J z;40IkeAqDsAV;fQxnLMu0iX;?@Ge6@G7cW~HI%a0v#LBJbZX5Z+fc5HOb_B6R}*$t zdl)au&CmxRanUa}E8;&!$WE~}dJqlH;>129)a>E!l1mbUkjHs)1_~kvwtCA%zN-#V z?Rua?=aX|yc=aoYex%m_x?4QaHVm>EW?;u%dir6;9Pz=ugZvkn6Cmj7hLecFl`uPg zq>p2Ka~$PhCL)I?3ZPy#9&}=Q`r(~WP+FP zr28}So^=L(Xm)d4qIISnq}0kvMVgZ&tWxQHPQ;RVh183{!hOccFT*KB!#!JO@)^ds z=9X#*iF?*nR=yW8hL^ru8F5l(3I1_zdm!93xlV0+E0%09{(TM3j9RtvRjZT8@cXyY zLT#b`pZ2Fb8#CY&J)Srdd_)y%-dK$mJIPQj$Re#~+Y|)PrN4lAF~q%*)VXO6{V96|S>%;1{@#VgOas7hSry zDzQ)XYY;m1N|c?&b+vfqAQa!u{>t3Kh%7Zdd8x^J^reX5r_XwubGsy$C1 z6rQmncR_C|9zb{%t*XYlpTmETfL%a&$DmqgMpqxwO|to^@(Ycp{QFC8L4$<#d=48g z*^9;~Alh9b{Pn8%lTopT<4^IiZL@11srK^B9?g*6&E3#<9zO?qcUqe|C+NCD>!RjuU~`1)r|tKKuDvP0@bf z*jN;Q^gTK7$KWsHyPONy&Nw1XU5`loPZWpMuE~dCe1rmt^G_+1#sDKU$XO$XZuJxzMae!VWj4-Xn}b*o=V8PT z{9>Y7WAYc2ml2%ZF|hjLm@}igRrT>ctGipEPv882Ce!ply{2J%GnFI#FsgiFU@2== zHs+Dos!hkoTa*;fv9^^-ev)MII!80R5v{mv6_6|sV{aUEQ@>(Mz8Ra~K1H|+2q$EB z2TW4qRX0m$Y`3wvcz%Aj-8MhWdJ=GC!tvf={}TTU2TH2yJrsI2=e)yijkXKl1P2a= zy_$nu6XJ;-N#IkhkG_PL3t!l_e}iw)4M-ubIXZo_wjoIWW(Q z@c5^u6+X>O;v^e!*v%Lt@)Zi6*3g#M0+N}ic+TJ2s|CdDpz@eqnwZMC&uR3knDT36 z=@toFWh)WsCKD%&3sFsvtE(qS?&Zcy6BnXq7rP zF9=5E;3*-%^CcGtb@w3E|2ZVL$K8hq4lRymF=x|$;Z$u>eZlQjgrK(Hcbn>jKgx%_3)iVU<)4*dmb= zc=nfgn$*)M)6}*>5Q+Jrpz|`307u^q(stnJ!cnXzE z|J!cg?oF4)-L1<2Ih0eF=sgR#b)lO-*sw+EoOa_ViV=1Z@1E@v2$}6ed7)_citN&e zdaV$NC1M}|$z{o1A@Pbl2$C0ftix#t60DpfLC~Ow(ve^BAhBooA2d#3r0D%1L(w2b z*RLd?r<*Lsi|J_~C}2i0#A1&Nio4%Is`8x3K{j@`YAmEc_Wt+XVSdnFsMh7c_HWrh zRhn$3gCwiN^mlBWZd$>#q=BUFD1k)t0fY>)o3CI%KE&pmdIu8jHF1JK=n%ZK3B!Z$ zbc8ffA=Dwzkn9gy(Llxa?Kp#!dz#U~DS}N;@S}qMaC19tqJr`SlX+)}wa)T?ej{tw zIrhl@!^I}e4d=)iwf0lcX@W#X8Y((Q4CIPEd_xv$CH>Q;^`uoTh3XsBp1;j!H-HkH z@~3D?e@Htv#E)ROLGg_I`0wC8udZYVBtyEpW8^fDtdEF4dNs=ksxn$lqf%9W3iw#a z@_2ULQ>cP4C-L`#qRe;UGzRRPQ>)6HoM`#_Ov3neO_{bocL`uVBkla8#gRkfK6?)< zRP~^w=Qc@T#Hr;jj(}I^O7-(=e+5+YVBNnv@*p5LU(xT1YphN+gs@#7jWQyXUpy(O zkHQzEsFo?D1}c@WmU?+pR_W2cm!-|5H-L<5HjmA>ENR0rlxWZ)hVj$Y&z@@ z|AxY}nY3vKZz7c)&iFZxKU!#QJI$ z&iDnt=2lL==Q|ZFobW@pxV*bQBea!u^bQsXBK=j*P`P~^41DgMzY*}P;;P!ON_C$u zqBh;1F<4vuKtdYWi3Qu5pG7K46ihHVUlfA45Bo&@-h}<+$OrI zup`5{a^XT9Lt{h$m`Zgis{_Z11IHrBIJgjYC*m*rrtFP4(TguX2Tts7AZ@5!E(e)O z(T7{EEN{p^S#;cL8tI-FF2!y zmc#l4Hg`WE0N(FtA#^xfS9@jpg#R7n>ccWP_Y0Sqf_TdtV$c|(Me#JJklRytTD#st z__BLr-yOG;8{RA2KwQ1hZ}dk-jp7c{Zp)8n*xi)muG`p^sLlBky-T+!cRJ$pBM@$8 zroiJVkCQO4f|u5pTB668PQ2c$G>bU+tGvl3g{x;^!RhnKiIu+~S$MHrXXZ`us*q{k zgL!ngZmJ)mzrViPjpsw}`fE4G&*LyoUznf|?_#6%v!j>(vgsmq;tkNrZp_UetmOao z*L@s%k8L4`Dc`}| z1;vnatG_7RsaSAIT|(D*h+YVvN*^&Ly?Ag_@=r^i0~C#TugyEw4wY|NY}pL!c-1<% zVu~Q1d@Q`Dn#Ky9Lf2%-Kl#qnwH0Isvr$DR0Gifubd#xf$MqQ4W{X+kTb>Z8ZG>^y zI`X3Ypy1bAo*db6g0neF0!tj_d7P+D?pPqfT7+OUe(ht);?E0)C|e+dT?BwRFOh~` zF|yD&)a9gl`c^)B65y;|O zfOfnZEbykra!#a~jpc3h-KON;_oEgp#pvgawL|S^-@mSrg9O4NtfuUMUD*=qZB`wu zqzQWh2@)R<;2KDq*m`1~w_TvfL;&XcrTkP)Tbx_Vayg>T9@?_*3;X%KzeZsfu3cR{EZRB}mk=xO z?EDRQ=Qor8d-(KJP_E>(rhEGh*ypWi7gyV2BG3D^%0^}HtGSUev}?87A#L%98psY% zUL98HaEXafjGFU1XW{Tx0JP+rD6p;Ewx7!EIP1LykOFW>abgcth6Y${P14`bs)?Q?x#nhVU|OxqL-i6s z3gN9>O_KG_=zKJ7De~6wITjhb=+?*{&!<4I(GhL!~BU!h7Ld06$r#GTL$>IY41z0 ziZBc?VSUB7bB&P9WlM1tmXe}kHKBXAQrqe#xi8$R-lWfZ6aM0Ba~rgwokiGh{=?2g zhvd0MdT8ij{u1bBNs-;Z&o>`Z{P(^BZwv#c$HLKF%B80|wi!N?6>gyp%Y)t6Cq6qSz$&D^DuB$)djk}<8X{QODK?>mA_ z6M1M1r^t!{N3{X$&q_A&zFKxo4zho@V}&(vXW-voe??xVDz#948V&CHaH04QQi^S00BR;2_WD{ z0=zEp0kWQyzHXkWnFK`4D-X2xDL5jew+eXHX-ELNc zM?CEgqd$x^6iXhUcAt8Ux5|xrxdX766DhExEhc(^RzTXR0w1r88V+z7vNzh)f(<(< z0Ow<(c@guEui;M?y1XEw1SYIoGjX*Q9(eSY}%gme2=8Qz=au@-_aVjw$@_* zsvg{zGT6Rp&)cgkZQ5D;(r|S=wa%T#(28gYdi~2*K`dhVJn2$%zz>0W2x*m^IPFPG z@n5EN=T;RSrR#gaMvh#v1>#Mh$yWTN0KBF`4-4At!O{ilCKVn;(ys27kJKqK|8U0A zKwe9-&}}J@WdaeA9FRs6R6{<^>u4=7P^u!ZgVd-WkSojd(8VAh;;^AHkLM@!r4Z<% zeU2Q6)P^0v?;v^N(%RBFk(|zUEhC+wuz0Q9a*xC@DHb8(F5#pA;lt3~n3)GRz@b3g z1A3wW8l)_1!HeLD3x?7E;w&R4~H=0cRNe z-9Kq?C)+>AfYHAKhJj2?k=UAu2@7)hNf!~RLPH+J3S=GRi0{!(JPj-^bBGt4+M*v4 z;HBNWQ|ek9vPIak#F4>;RI29y@-r#!X%*^!d!a9wR9P4yROd*q&SB3DRkB9}9t>h> zaTAR4TQ0?sV!opw?VH2SyzR*={LI};ZfLN;daSOGOrdXrGmG=XF=b$%kRCPiIbtxe2=Km<7R?np;r)XeMt$9k6pzTrhljEck|qovH89QIGNiiezD$H zVW5%Q^=iC5Iy0RgSi_zt4X(YR4E;eeON!&wY*L{!k2+-!|0={_{R0)3$-+Fo^PNy?i z(h9M&4AiFu7P?71gt*WF4CIxNxVsm+C9Hgw1bENW2nM8_HR%y(VC&+WdYs2JM_64- z&zlN}+@hMc?E(q7P1Qd-m22Cz}`Dp$a&+g^*7b6VC(@P{S9kkzD9*^1zf`6sQ zGS3Melw|I&Zic7tv(FPvxQt4>LOHgC1eqLpFySph{ejBl9GDPesCqN zX+(fhH^P>=G4_fXPTHr_WEr#OsivX*aLEkG%5!hmPpl7#rd4w>G_}5yk0UX(QZrp) zcq8d5ow?tkn)0uua54@^G5NzM809s>>ceJ~_|{XO(Zrk^nmq~E$&_Wuhy5;Hlo_Cv z%}YCEShlAXa&El?K=rCs;y*&Q*byL*NeW;zL{_uFbkr-*QOx~q|eUgXX^wMSMX)ax$m}X^UB3|+<0o=c}7+D zt+70VZt&*(8QAj?e}rV?MUx;_+C3e}FXHKLOUqjT!octdpnC3og25M<(!1(=%1leO zjMLZ7WAWH@I}{9Y%ynRVqXqnUSO*P+YtZZ>{3ufj0R)*%oD$C+=co!hfx6(IHY#t8 zkI=PDlBa(Tk2yAV#l0Sl$A=j6IQY_kD%4(fyuv#|S_;dnb}q)K=~}eamU0WL((X?6 zRU~s_MfENN(yhg=)6G3xb>+}4A+yuhu&jHB5NmDt@j^BQBu$_qt8sxUa&U}Pd63D= z3Pif6|D}#A$31E*m+A;_3>4K6bbwe1UuhTsu0l!N|8Wz2=Emvm$A?xCCV(+gCO2bMIL?YpKm zLc$TJe8fB=e36!Yg7xWGKO?M@p?`(~V$sj;sV?`sT)U5aa&S>=I~NDeExZz=Pmwv; zD>Lc5M)Y4*Gxh>jj+jWFWjY`vK=VLkp^g}MmTrDwlbi6@jZy7o4*Wg`1v5TE1$Bm{ zQKrN4QM>B(ul+csi2gXqg`jm~`%A;}0*S$c)f7}{tJbcm-pr7t!PJ(XS8b*Vm=r+4 zPg}F}K%UiE4Wo}X6dvQtsA~VUZka0f1 zF|X@4eMe9zI{Ey6u&$UD%J23%_kvKd2A>KDicZO7skkT&7j&{&b4sLS{V>Z?lV2JM zN!u8Hur1_J6)(M%=4H}3?=Gg#@G1b+E}rTKH1sbL`2{KvMX|0s<0m@Xu2so17Kxh5 z^m>m!%T)*0dYt2$Uk-oOZxtrfXE-Y3Dt|~uORY%rrNBL2IUp`RwF-%ZSn*=FrFZFv zPY&b;lzA-eK3JsjCCh7vMGAN$E3T^d<2SoAB~FNy8K92^CFWVmy3y`n=+jL$mj)OC zOll;on7R@XbkMCE;})cms8Ne@UX=>zZA}+~U~S_268^Ghv?ZI@i?7X@Wv*)|9x+43 zhy0epN728==?IykBPWwt;|``uUkD+6ty&la=Vg{1lL z!xn46^WM07a$~CgPA@m^H4=&yiNC}HkZ7)%&-o%i-As&_}KHs`LIDTM;HiHdu?EwrfF-Hc3HTy$V! zlNyqJa_k2Vqz5Q3f815zq#D0TNMS_Qw|cw0cyTgW|LTbPjg{6m=nPQ9mE&yyRHpJD zkc_eeTONC?r`nuh+~{A+&IB}8+=H1eT6gWAP>tk-$4_m{NV((b#Y~OIkJ5G0QQneN zw!L6{jjWC|eS%#xx)oDKUsvQwGd}eKu|ho-68=)lHMY4)DW5kr?(Wp(I6UT>Jcknz zyc8}c4>$d#rj>mvWSsV}gB95V>?JQZ;6?Sy7L8G2(34ll~m$WEc( z*<;TsmiFttatPDE-fJGdv3b40*gSi5xUX4*1x6?0F&tosc@P3P(Y@Bfpt060@@XzH zI-7Z9FD(e&M*O=U6GCpG3@-iz)C&wW6(RnY`vBT(qVmUvE{cPs0mV!I*x@NFIAp4# zoaW2r1WetF7 z;USg5z?1J=2N*ZCR^cz^QcokLK07cgy^~BKHK$JBw_%i!TvRFd>r%Qf35AZCr-}3Y zbQnMMIBKT$W+HB4;!vcZAh8tAym85$H!z_p-7+EvqBgG^98}F;27CC{^7JSuzZb-oCz@$WdFd}egdI!!72aWBK!X)u_*(G zzSaSl**X53u6C}gX}{ls==WHCeDp1!G=d!g%;ItRHRF$fpFrIT!Sc_VgirVakA!$B z+R>9*^bxp@WGSAAfoeFsL-df(E{C^lM~CONYWZ$n&+tP8$Spswms5PYPq7md6$xwr z0AwQg;qUXn=j&Ju@agIta8!)%X9CRr3><*8EbP>%qR*f_AA1p}SXT}*24}M5&5e~C z6>v>kSRYqM!>?ib{S!6(87cMl{?+6+#RBwSz==E!owDdMV{GPuu#~8_IKa!sUyALX73!di=&h_Q# z?cGO3Qcg!rh>jxOAq-?cIsbq)YX4<@6QyZYpZtkW2sS6{ zcAp@64Zt#6{@klKb5;h)T_&%b1cGfebcmRry%QF7<*wThKV9fuqiCe!i2F8`Zwo7n z^w8`r+(z17GcBNVnkRc?9o9^>N++Js1nn{5qA}H_d01phAUWlPJQo0GIe>-n!qbjH zcEr>L9`@T1^V`AvA49Wv`6a&Wk($U5_}D@49{}Wh&;(hLhR77{V{8OOBP`Q&rW*s& zf{lpi!%2UVdC(0ki@%Ko1uT_{Y=DX1@*%uah}5(*fQ7<9c^&i#KOuJz}L<=0t4eO^`(_seCMh zWIUF_3K=tMoKM@;c>MGAs!ZLW7>uQhXjz3`uXDcM;%dC@;9?c*9k9&Lh}->VhM_yS z9nCDOad$?;=TybQ8Bu^mSBVEf^F(V;J>asH>R0l{n>FZDmTnoGyd1KO*``Kp+iVYt zn^PaT8Q5GGs-m09lL2`Z2ZZABXw}?-YbIR>?79)Dkx>A)Vfw5KC8BCee~$ojBMRm3 zGNNP{Frh$htH`A!-g$H?=3C0zNw@1TRx{M{gihyRWxEW%eyRo!C$ zu7`A@!Uc;pALMQyF4-V_Nogu86069F*l?3lDW0{X9(BtYD57Tgv3(+%cfnt&s7W&O z77hAn+KNot@foSR9A~h)8pFQ0Jit6RylI&upV}=sT$rSPy_~8VwiS_Lh1!n_wIV3W z?;!|{7CYn!nK%~bGVFm&Pqd-QGznR83~WaMn|>p^RWo?CKFxPDYpz=0BPE!=*l|1~ zHuPRFJ)+jiPoMiC+hs&8QG4L@e>qPV&UVTyuzqxAOr%@MI|Vuz+d||K%L2Z`_@=|j ziqeqmP2&nv55>l-A`}%{ughyz{=VuOO`3JCa?MPMQ!aob$xTo5x04P=zLB4-Ii^-F zi^@uw3gS`L5JnYo2Q+{ig($kjcP1_tjq?f%fGpHy#cyKRFEEY)$jr`PTrcdVt@{gxn#zPvuv;@E)Unk3fan!*U7 z%Z(HT8STJF#n8YBKyv{USIrqW9@u45zKVPctpfPCwb#!Rqw=oKlK~p+@?5tWluIbN zXviUa+cMLJ9T=5G#ZfQ?EK#WAjH~-QkZvY}f-u-np0sn~kvd+^Z(TmPJ-WB3t5{SP zb8bP6hJ4V&>ri*ZYA~wi_g9{bq%CYP6<;|7EL;nj^Dp|$f^zUWB?HPLh6iL?T~V!Y^kCRS|Yt?W`-P51*7?)#Eb50;GT+ET+R9vRiNp_LibtitNZc|#mUl>2cWtbXX_&jVIn_s6=v z1kESpuBwWX&ABqdlFFV|0>*is2n%H6X}e+O{xUaHasH00_^a~jsn z2eL>k`Eo!yxFz7zJ(2kINH1hScTT@jCFvOxO(!q*e5Z(xbyjdFW2lS3r+xC7&I!S* zhbQcsY|UK>S7dWwoyqmzUJAN97ppSc;H%y^s>C!+uPha+yzif(h^thq;xaJpwC3n) zVyu@K3u^#`)&h>NmGAQRK(SjSQ{BwJlOGU#>JLn*ywwyte`Q3m_fME9xIhj|`TMMm zJ-$uJnViy_rCXo`3#N9x5J#b3LWhSL-9~hn(%H&TptV`hTw+s~7db~xwdkpRyP>k) zbUKPJoSX@)tNN|=^VKD=-0khO2D$2_DbX~;KZC8nb{7!#cU+wJ&U!;<;M_#P>8aR~ zh5V1J&d;ok1oZ$rX?pbW0^)lW()cGf>CcC<5+i)ehhx$(hHEVfp1WBsxOjPTHh;vV{6F*Xx(LnXa$4x``)aXHIe$cSg3 zz+nT?=rj*qoXMx>4#-PBaHlH_$EHob~9IEz) z?i>fWS4$I7@d}1CbNrz!FN~UCk*7nPV4<-cuy~+b9%v1;m|T>$)1k5#Bwl4|_Zvxw zJiCCqDV&fL5l%+m3R2Ednm1nf;LI+4ApKNAa;4ur>zh|f_J)_^meC#4$)Iqz8+|`C zC|b|I!)eEwYnUQ`;M!cBzI&N5FFt1z{{{hIa|Xk_h>;q)I7COS-k6>{d*;dVPnGQ5 zj4Ao zOvOxgLJOt8e$-}eU~YjCo;y3AHLJ7GSZ9rcI}?A!d0iMGeS2No8r>x=qp0y2I{5_b zu@7yTmgVs&fwsFgxV#OoiC1&Xd7tQ%`fU%xc?y49peuV}Acgzo^Tb>S=i7(L{U&{CbIt(^qwq;n?cWh)FHkm~Ab$3Cix~MH@{%6Jg^f6Xg8;Q;R&R&Ko2}ZYN4;jFBGeySmxC zlm2ZmkR^Wx&#BbRC-7UY$VgFqJg%*pl+1Be4UzB|NB25xmMz$P>2bM775)pL<#s6Z ziXeG?=!lZEcuF)7?k6mzaUb?dNytKGfVc3n8~CkwVvw1rq{$-{WyAv$9{}+;zvo!> z>4_h+eOJ*Bb0~=ewB+&8ADH6zxIA%$EV7s6lzL>JoSLyRdC6SVJAc< zX_^uwkCEFYTAD$l=I}|wD+mbyq@uhwzt4vn>zZiPMUY3Ut!7C(;7y7eH_Oi} zvrBBWq8ZmzyGOILutT0bxDNd++esI+SPQU1cAXw?f5~5a6RpO9D@7Y_?WuL*boTbN zYY%C4n<^iT8$7c=9#ogyGI7?;K1AjqKF`7?INtLL?z3jUtsR_8{gX!wSP^k95f0o7 z9UHNf8`-dgc9`SC>@GDs=E-GfLeCI3BHv2V21-X&SLlqZ2~AYna(F6&ZdLuF{!B_e zUSCSnNKHqUTaW05JY~}S6xVHgwCBG(fl!t1K>C#g}yd z5<4CDCm^DnMQH=I7ygb9fZwE*)ye=b>m!7B<+P+ljHSo4{{tl*2U2@6Ml&|=VG8QJ z-O-NC9d3eWHD<+8Ka)Q^W4z2K+ZtMM)H}Y zZHv>i%ncN!7@M}HCK^c~EPK`1hR2-&d1=f37_Jjm&myM9yo}Q^Ag=h^^0nF0{9ART z4U^p9w8O!AoFen?vK4AfGZS`Fy|X>==Z5of_1jsv|BC1J1Kh{!uah9FVLP}*7BYg; ze0=<~awhEHewkG)bL{S#s@=1N+8pmHTm1_RYW+#0ja%%J?rU_GmZ%S+p&UnfHjB7o^` ztP2oaG0k^s!*n%t_fDOAY}F4K6qMY}|Ea2h8g$@DKp0;TRv?`axGN$nGYcI%D*-DL zBOTM%hlM=>gp1@qjB|FT{|7<#-}d$Yt*p6#tg7IMkc|HuajsDO9qT(gWAhi|JiHBr z>0eM85ElUg5%49o51LTFq;|{Hk30u`|2+R{^Nb@j(1uINgggl?lJ`#mNk_zk@)-5d z#rsC`k@?J85+xnDshdpExBlL2dygmn(}BOQ`gnf6Vd}8xx4~N<&sUH9nIFhia%xjk zMcv(qgD~jXN5xM^_FI{={C=;0ch)YK{}z7++Z8;>05Wmd$-j!Tecw6U@v0@JDky+W z_=zF4cQx!bmJ_>Uv;4hdllpjFzGmcAWXPZO#q|7qSEfp5ccie2L0dxhI@w)s4lm5c zJP&Voz`3u0G@p;UYM8=BU5TEQ!(436&lpNnKba5S^@u>=(bcPS8``BM?uXm0wWmjV zf}9gN;5FM@#j0zM>>r0(Z^^Bzip9G3;x zu@Ini{I~)?hMJ`~;?+VakcAoR)NNEJFpZqGIgNRsj>e%x^AbFuM@wUWXGB4t8U^3E zF3)~9LON>r_{GXanxU^I04*{R-^XSME3~i##coNKIm@jF@yIRX%(;>fH_p9@02DB} znJ28;Y*lWJ%jgxcRiLWE<7q2%1ji+01N`C&SpCsf6~l!$z zkavqP)ODksRuAfqyhJ??wN^Z@H3W_#%OEt3S<)8M$iG<_6=58HDzHt-B*J}D6Ux1b zv7P-Qx&yYXO`#5{(YYhVLPflaGy_kXg@z2<1#4px`+_lbK)7wrlPnkeD@l!SAUDtn z(A3R{*l^|%qVl5x220S@A6C#X699qPaYrd+x-e5vrX$@%*s9SJZUSc3GDOQ{n`}Py zoHhD5K}0M{BDp01W7LC^FcAA9jbWVp+YCA+MQKSCDit_)&vbWKO!sybRzWvzQL^vA zVTemyvPJs&mnk&BrZ^KZPFk`la7q|$VJNC}6|89v+jm+{4`c6KyXxepEr7B-rKJs| zn_3$>&&PY8LgcV|hIHOF*1|lS>cFn|b zG89vm`0IOzkQ|o_6|2ckB35|@FWWABG4v6>400SaQ4`9Zcax+AFG2W$TSKTS=I?Zc5RODc*UcZT;oJhl; zD1*n{wVYsCjCCv*dY-g$z&x>^D!XODZRez!eQoB=Tl~kITRu?`U7#YSO=_V$kxRHL z3kSzZ9gngr;es>VM%M5qHF+;_5d_LND#78j(N#-M6T7-zs4l(lZ2;~V8$5+h+N%Zg zpK3)?y%A9&@d`YGl^$J)B4tsv5Mu$5fi_H@dTAEa=Z8_M`sTt#XydLFOapc3Or{h! z!eO&KX@>(~OPp!Oi{_I*ICFR50>1DL`KxXilgPpbF z0+$XQ!X>4CaYGc3_WZ)++#Yk)v~S-|pNZJqafsQ*qap+HJ_ebwTOftf?GK~cgU*iH zu{K3ddrsi&T0u&(Y$k7_fDSAoOe2h}BAJG)L~Da73aX-EU4S0-*lRN$4X^#VR=4J0 zzt{m+`R;+so(~iO@+Yw^5T$*{?i1ALag7(&c5~GGuy}&anc|$ZA#qXIE!>#833?Rz zP4Vy=7^VZ!Tf)G(j>&DB3FKL&j7j;(%3ZGN9QKz&;tmb3Uo{12QGHyZmMXl8%OfoY zIIN3`^hEjAF#v;x*yD4udU2kLbaA#WWrNQwyr({rr=$|avnIkSh7HCAMUYz>_7GQ% ziV%fAv%l;Gz#n`Sg9J;UWk1kNy4L{Ii{n1yv*pv~4QJu7DYp2XSH78n2`Y}mH)O+5 z9F~DA`5klTn4F`MFqSZJBO4f{c0#7?}-U{e1|PU8h)1lYZ2H91J?n zCi17?A_-bsmxDoGp9Ue|cJFt&rZ8Z3&joyzFEBAd{1oNs%)D0cLxPYw2^_OeCpyVs z*sTQ_Nz6&C5k*yRdcwykCM%30QU;rb<*FM&X>L;ubi67jb}>i;kwMSmBB?qADb5{7 zLP85xh5;zDHD@mvGb)i!71CU?;bmw?`?SC~0ugA^ut6JG&$za-a%{~KC1JEH6?04* zjpB-jpB98ZdcX)D++z!YEGYN5Wa15y3iS@htG))D8GbpA7R`ES4`i-B$^!H2LZwUvR6D?fvZ&x`+Xj0BrkLh(5gzi z+6fx;#asK`;trcgil5<0TimtEC~1#K8T`J}-RyqWv*IqjtF``t*3EzKI- zc1M?k>&+9nb>NWv^@G|@M`{n=x^7M!airPxhE0 z%z#a;>sc@RARWR8&xLBT?9lG_yaH`(lhWjKxr&|oKUlKMUsl@|pXhNpY0} z-LjZw{6U83dSgT!=XD_@-ESPGaNmtd$N}ZoKD4?aCJ8>O*1B3SeaW-zobzELjfrJn z#4xnlk+OxZU;Dbru~W}_zy9iO7}@F6Ky+G9BUphURJd1=}4x;%ySIl1xEKspXUC8AkS}8+(j5K&F_|AJ`7Uj)#W{u`T&0;bhi!A{|{{2x!IqHRnc0xg`y(pd#tGuL7 zhI@e1MAH=~>04uJw8;%r2^n=KxE}yr=T~i7C!hWp&Y!T~&XnuXC)CZ=ku#z|Ovy-hx&d$6Ry}?jJhhln%pC7Dm z&-a3k_{j$aksO72e%Jc^Q=hX^L)!d6bG?tOtT%N^Y?`3Vpd05ZeT;yJF<*ey%ku|N ziT-H~P%~Hjc?dFXg>Z!T;4Fd667Kk6Wn-yZuG@%Ndfo`0p6PiKu?2(0$FDton{klw zeUvKuUaAb2aTj;H9=X|5qe8wIP9YRzFYJ-4DN0L3-`6z?v`62H;P|~h=2DNPf>A*2 znbIWP20nJV>ld0-9;^Os0U;pza7gPY2xd&$xvIp%#Lb>g7e%+hJ&hKi&3 zWIw-3V>{ET@ehSCYzER359b*I7V1!;Dn3T@bI%jSAdMGttpSmH(0fQmVqo3Pq1(tB z83e-Bj$Rz8SKR`37&QUiFv99N>GGP{-)W^!bU|hmXG>E{IQ|oY*-il37PZHy^s7M< z0#fprh3kepQ}$g^QE4U*dibehTHosrV>fTASDeCtKruL&6H@e&zi0uS0s0RziN&Ml zY~RHh%?p4^?VJ~%W|~aRb?vNr-rh|~A^-&gA?1vqO>+7DP~ptLcsyz>zX zG;ik^-6~4YQqVmLt;GQQoMOF=RjxagQ80u>4y%Q{n@u@f+xD_2fD{&dLfE}WyYGak z&(qL5&FormYY&XXp=h$nT^J@1i1z^ms!!pkieMubg0T+~ziGbbW!x&=>K0tbc?_rj zuH!eTa~FlTCn3I|;PE2pQ^3rW(*RKl;kLS&IO_hwae1%X@5cjnQ;sG0q8Qp(#qsNZ zmMQPOs2|hKnVHt=-kUV+%EDPDqU6hQ{>x(arI5xJFL9G5GCXJTob7pxWe(M&WdX-k|e7`&~7!d#H?bb7f@Z=Ydq$ysPb3ny|eor>!cv@O?>IM0HlDtiTbSDa_oM{R})v9pjl0qlz#Pxwj^SWqXRnX z58@&p6{BhIN|cnj1!E{wO3^V{_}4o2)^GBk61%%Mvw{FyUoD{ zL1Bb#(~5^P_SA)rfj{lC;^@A{I0U&(x*B{OL?;eeuRB#JkC`#y+&h6B(_QGZWL7U(CwP2;30^p#xzDIyQp*|FMg|v$OmMvCYE9`d{6}2fF_Qu}ys|2Mq~3 z{&4Zc+4Jq$pM(wJ56IaYKY~;q-Pwh3sg#QQR0YIdW|u-<$!@8#`ba_;zrM*^w*A82 z>@S4&^=#)}!O7Os?H2v#)7anc>y5#+kM_Q9{lrHpmn~rN#nELqAR~nTo z^XEXH#S)hz^lWB9O%?ZI^?Ogdy9;#()>hlQ=y^N(M*BwboW)G0%@c9f+3D+;y!|eT z>|WdF+u!#kbWZ(5j?T}I*|s^L2LrwQDr7Ezuk)*U;Ptg=W;VsogBz~-8uHNl z%{QX^=t&E%Iyf2taPPk6Mea5cevx~`{%q2Nq#U}uQ;wY-WQH*Ib+7t39(>FW64Rng z%G#7qV3X~LZoxCd+uk+oF6?6^^J89qR(=l&`E{G(@anrJmpvevPJu%<9vD)8ET&1G z>3B==Bf7}GJEqvW=hq*XoyaSQ<6hpBc$cKAo{X6j$z9B8Kph+rl-(vMaGKyctk;aY z74NV@1vzNR?;`*Vo$99tzOTMg^U!FX4H#;JdysBZo}2iK%ofK|U9^xd|#0J6x%NFPF#4HNxP%HM=CC3a2vm;B@vf#hhsm|p(QUQ3;Hw!mzvXfH34AUlTJQN zqI?50U4jz0#>l*I*a)Zx~oIT)`TyZ$CA-B1#2+X0ZUrhg5w$|90hfH5!~8 zR1_N#*0444ufVB!?4)!9Vq=a_t3=36kuZ%;=$lTBEFux)#29h~9(*zS#5{spW-f7~ zWaNBn5u9a|PPS+Psn?Lx85T)uYnw3ZCCY@PvvJftAK4_qJ zPd6kh5a`h?dgIw_Z+fFPIk-1ksN1hV>wFC`8GqKp;O4vR zB_>y8k~`6Po-6Rc_JDpTV>;#BP62 z(Lnt_q2r`9vbt?ZEnSVy}`}Z z@8B%_h$rfZWu~i|EM_nh#QA!sQ)gcbHJ;`5XAzS4xHou(`XPwOr-gX!>AXL*uf-J`m-b9+AL_`O^6#qj z#aVb1!o3~w0*iP8NhLaU6n#I$277#D1S75}IrIoqj(Qli)tm;)QEhWZPz7p_D}`KJ z7mV0;sg^@vlF4np_k0)K>*}AQ|K7*OIK^g znWDdHs-}oqo*LlGpdZN2S>*@n12L!sy*=oloiRG5t^5^M6ODbmy?@eBGlZX9j``6Q z_+BL82p{bYp+gdn3N)mhn7YhF>9Z7C$%*P9!CWOcF3c<;ba^ic@T5(w|N}CWzAvy&GPMj{hT<2YCg&ywMi58d!AVsTT zwx)|+kW^_6Rb|LqcZNi$(lmzUyQ8SV@wHH`P*HC0;D?e%7ads76(&49LN>xvsh@93 z7l2dZfyX4lht6kd{iY`o#qVT5(SK&*sN>XLHR!{`==$WwEezd4)iHxToQbO1+(e-yj68Uz)cQcyAH z_GCe(dji(&iftdovssPRJ5CB7PIJq=zCBw)3q;2t#X2Xz%L@f2CQ;zs3q8vtR_1Yk z8`Dm$N>T8K42PbJ+&WvnXa$hXw$n!sMddUO)Gyof zm^`y`NaU(ZKdQyAAq5M?nQOw;!YbIVMbg7wL+Ac`QlZ*Ul_)(XVvN$Eg=1ez=st&Y zV0b+=dqW!X6_g!jJ>O4RBWYdZ#gRfSY(0S3l8F<5&a9YR=Z_o!{5xlfHf;hTJ$mXW z<1OBp#Hf{OU?)9F(r)3HDzrTD1k|b`y%jgln^L1^UjMFVjUGFfpEy0zcdnn8AgJoL zZHr^j#A4}&D*p11>4`k@u-KK6ZloY5zD*H-b$%=#;~^BiOVfN5zDkU3TI%IR4OajZ zE3r-kw0TNX?3OUmR#L`ZLTnxG=dIh($SaqC@Q(~RZ2lzt)CQvcWTP->zk5Y!WgvDx&aYw~(sYLG$1;00IjXZA^alzT(q3P@}Itb{*1drs2WH+%!|6 z-7X~KrlNh;tP$o*srs*OsUr>^Pz$por2(X8V>}NIe6>F4wtc=9W#VfqIn%ehW~G)NH%=wFqf?_LY6$+` zPfIt0zF!z}V~0^T$37dVvGqP5gEmUM*Sns)M#0F!IGA}%soJbx@^A@r+Pr|-h|K7% zNK?xo-em?ML(l*l=UzU;ek~WrTvbgPw(+WHQTv*+YgzOd=Mz_%_}~&+tp(QIagRmM z4st{VpY~i!)G5PJYcq0a);ZV0il?hQZWq9NZpuCUGYYAbNm3Qx3F?dzHlz9&Cs`A! z8sCs8UPYU#25(F|@rn@TfhvIA5#~2-V^#KQsRlu$M2M!WALje2My(K0nRBLhwiNFl zp$4TQyIho1NDA1;lb{%57u&({IJ+hy zj6LSRNPB&KkNlLoaPq#ozGnutja11z7*x4?6!Zu!bu;CtXsA<4XDQqtaar(6XMwix}1MLVQ*x^{2{@s}4pOKaMe{Zb@lw*V7gk}2A{SjxB5e?%w|rPM>NtEE@ziCl3}J55Al%lg5(GyU_gV1EAVEBw=e9sDm9`e^#r z@4)DLHPo&5@lo6d=q(Ohm~%hs1|Z4Z{(XI8_;?1a(T6_c1Ku8PZt2gi);@)pXBq9_ z=-wQPCYBegmG}0@zercJ;z!*SxbV7>*`;DYGF0PL#-iRBww<960Dj*V(VN5I6R;bn>;3iMv{|?E zmH{AhdZ;h#Z10>fI{sk>8gOVX}TyNU@aO&L#@Lk@kP;9oDbm%Hs-R^(52W&>j-$3s)l#fgcKW`Tg5fCzpxO9t+hffe*4k#`rydNkY%Kz5i>1yCRtKq8 z!P9wZ1hiZuLgLSIOnv)h4!HjJs@ZcPamO1xzj2RawO@@IwkA)_zJ)?^QqNxMih*8cST>Lb&^`I5H#9KuhM{F^yu$J;i{Fk-z(T3yTj-@Lfrw8O5lf^W-XlJbL zYFolDHcBVH<03Mh>}f-eMH^a+8A8gZKlfa8zZ=FNAwhg8WV<{D=YwEyX&B$QHdH_Z zex6vPcJW>Ru$=x?Yeie74RHBwpt&sG!*@QmRHE#X52u-y#P&Uw?ir{EEV;i7HgR^l zQVUli2>@xYA+CK44O(+NS8VNpCVzsP5g0()o)xe_*Qrx=IY@bIQOrvEwgOC3BH$L! zl*{*jl%a?>eoqa-UhootPguPTUF5guT12CL#gV{xfX4}Zh z6yvjNA})n0T$BxaicbipL=$)Nnz8s(<+l`35C*B{Q6Z>p{RVfwP!kxdxeXDyVd=8q3%Nr)}NO1Cc%D z7%vcIyve`X*x)u+!T^belE&yxj-g0a?xKt;DOuSO!e5G+Ds>%RG!+YZsuf@f65tke=VE2NO{E9n+@)S*Ca?|x?n+S44--279 zPvqqLdP9g~Dqh=`g7Mn5rz^9C^%3V$H$r03{JEM-tvH@o%K-*R112OUq&%L#svmuC z+PyQZM33NeCxk5oXj{VP~=h2;~9R)Hm*lpYpGb-0+8J7GTZ1i4hnHx>{U z<253Vo9O?rpD)5)zDPS=4j{kb>HclwZ9qCL}ioH7#|D43+%BUuwYKj_GgK23A}`X)r!A5;0wW zcDEbZhB(8t)TLA1HDEC^x1-aXB)^o&M!Lu(9+u#~XZm`tR z*r@*x4{%&xoPudEJJU7~50QGGLJZC<4g--ey+-0HlZY~}#<3Lv)O{S<*Kw6UFK!LK zq?LD>^ao&G-|H}SQ2Pgd%Ry+CAcsd#S0=za?u9zn`>YgbgHQQ z^>B3}wbgwjPoX2ClLM8{r6naQca$_`VElbX`aK}_o|R6SJe@Dcxad}F*X@dEnbK{@ z+g+M)@4GE5SbXd?u>He*Toqel;Z$ z&ToK#I_}n#K4@eIv`;*KY0b^K#$nt&uN4cTGnnQuw!i2pdnh9oft<0%Q9ad9U`Mez zq(LHt21}s3-uH=nhR~hcr)B zU)h>z+nmzvwNrflu*I-v?lgo@i*Mq3lAQnvwua&6)RE_#w&7+SqOBsvn@$$O`#dR^ zJ9Q~7r`@Mwi$@h3|AV-+6b-*#1p2gr1uKMi2~Jgj;t{Tc7>k;7zhQza)BXfwGyaYr z1@kc?ddiCLluxKdUlc~HDyi@O;kTdtr^kE@jG3`AW<%Sbfw7gm@S?nabuGzqO|cEyK^X$0j;f5N?{tYSatAkQU!b zXN&i5ThV0mE$nAr#W}TA=UrdiOD6)f#}3(Mx+a}@iUdH%DDjPR@=1I%=Nkz;m200O z+UOn?X3{JXY}g023{y*ZtFFooi3)@#VUm^|bW+5Mg$bI&=LEs^O6b&vomb-oIQ1duvpcnx zHqGq0Pp?v7(0pLoy;j}EJ=2yzm5fNMaK6A*q(Vz3jFFB#_e6|2AG%qkAp6L_Cf@PC z@J+K=WSj~AJem^l^{w}Th+P8Y2S8u*&Rr4RcXlj1@5)$@krxJ#?p9uq^p7M{`RFyL z;}~M!pyM2vC)I42E5)<=SdjyaA5)mM1Tc$LD%w$e07P=QKXT3aDQq68!0LwV4*!H& z5-<|{iV<_0kZn&1HC{9-fTEefB;2h+q|r=U4j|31NdrqX#C)PJZA<`Uj%&zGMhp2G zaR*yFiSssd69k-Fy8IO9P@t`BiqG|}h4eai+rLlXymtM3ZFdNSCY}jxz0Nq-G-qG~ z2ZFPn_g54j6$ly6t&qotgYn^0!`DjK#2Md%kLe1Me~UAPV+hyF9wMI&H0T+r9RMXv zqOhnSX^uOW1usLR23-K4-DqWf-@5ggtm9Q}Lt~s}Eb)y#{2eT0#agOvD|iSlTK=^ogG<*LRImuTGTiC!-LhBkaoENyjNWrf zNq_wO(kzE^2X}ndenzjJoS$&f8%^320x%3Krx+282Wov_!KD_UORD%l=Ap}DA5=Nu zm%cbm@RDpJHSs$o;d=K217b;A&*6yZ*<&;@jG+dzcc{*PG_IyxE2LBr4yzN}vQsL- zk_+uG?n&m$;D)wtYU(|bg|j4c)u3;=w3We|Up+;V?)ntv*lp*Noo1~WJGItAX9PFu zsyM0kjPTrT4Zb>{@OmazQ`iXp3&y0XY4>aFw3$$kN-J8V-oHymacBeS_A>W9J$~<1 zE6$Z^nw)FCkWr*{DL1QD%~!Wy+`NQM)K!h9PNbF^V}^2-*|)o-l}%l5vM7#v3e0vm z&L1;t+K&i2Wbh^#=&zn4B4ob3r8CP4703lsHaT%I_|qPcjt{$|D|OT>;LK_bGa5Bi zXttR(yW+46dqejZL0Nghe!m~-md@O-zKib3G)IS(8kmYyKm_51FOgSyYp9t->;9^|Zm_8?8z9_LJaA91iMuu+ zET0aTMcx361Yl5?>S1~|QgNYLqiqC_$2EbPT^uBBZZ5UG;|&%|?FobtSfaG6O3BKF zXolO^X$~_A0aFJhB{2&kD@(r9vy7-v{!6XZk;1frb z0G~>39%D+4%XU7fsKQ4+Rd%8V=F!!DxAWA9@Wcb$=S8yGld5v^*&nuOrHR2$6?Q$2^9B-){h)c_u? zENMW;eWj?L=K75xO{de4b3(H9N;_` z@Dn$sYOT=HP9QkiEy`vJn}2zaJf=aj;o%qf;L_e{mL=!nOfzA~7r^Ts944QDHZym{ z;ta~lI>-H7C%^iiGAs=uo3heb^f{4#c<=$HAFmsA-5^NWh|LXg zMK08gfF>N{mo)POl5ldQ@G?W?%zv{o29zA(uG`999ui$QX4oquOUG5{NC#$CS``BN zO;rh*^eHC?|4O#bL>|LZDl@l-4GgteTga9*` zxH0^-=R?^t-+g=RBbZw_;V-Ka>B2!=DyIL?nV+5UxQTf1V-PkG*YdjcW4Ui@$?N~r zZ#!9!n=jmO(WGOVYQCIw|1_-w?22YQX91}8Y2<$ zpcK)a>U7rOn77pj#wyITI6Hprdi+8~+vDIt)T#~lZQbm?k93aydmuAmnoS(Q%8xaR z-pjv^)UZSztGUUKc1%kGuZl4e@e)m!f=C~R;uJQfOvsIpsFQ0j#G%_{3k zlnRQtms|;c zrBTHwXykLrGIQ_!!qs~>T&k9vzwLJAEsdFGvQrfgm#`IhI-C=bN&hLaMuhL=uhZ_a zQ~NkHPPO!>&t6gRe(S@V*0Rrk+p1i>=3O5!G1Pyy_4WH3cHd)I=Df?rHpWmC3|PTmQ+96 zZ~r~>h=09MX>@zd1%vBZ#g{tGO?j^;Z9AT~t<$@_qe7_veqr|Ai_5BtWL7WfUio-Y zlbY%0T?c<&d6VvYU%R_{saNpByA?B@$-5cd^oV<~A(-oR^V`IkA>TQ@cjv3_m%d=E z8KS3h{^X3un^j-jn{*P{@0qgmLS*+ZWH0n(G}sQ5oW(d@*O8rP`t=X& zB22(t`;M!{r?Y%yx34!+(D!svh_*>JOfj%bwn$7fH%dw|Ha9XdF-f*GPc=_8wlp;| zHa4>(tRfa=eMW5mc`n94kz?=oPM-9$TwQzVo40!yH*E{|(v&;U);f!QgWAkbT+`}> z@)fwdoOGtNeq!2W_}u&5Nu9dCzkZ$DnLcHKzh~qgZqd{8UZiw<^7+DjqS&RjvA^RW z+gyQn2e;4Al`hx)(KmzT>Es!!6)T0`u6g;wE-)t9Yj0BJiJC5Htq+|i|IYlFaQc&U z*`d9QPu`tWcs{N2^Z$A8=UJW3J~mhGwN9O0X}igttfL`!&6crb@0(#iyE(!n)bu2Le From 80a0b51a1de630eed2da187a0c2ca76551b7b774 Mon Sep 17 00:00:00 2001 From: Oleg Klimov Date: Wed, 22 Mar 2017 00:36:28 +0300 Subject: [PATCH 64/66] MJCF: fix cylinders in MJCF, also (possibly) fixes capsules in tiny renderer --- .../ImportMJCFDemo/BulletMJCFImporter.cpp | 18 ++------ .../ImportURDFDemo/BulletUrdfImporter.cpp | 8 ++-- .../Importers/ImportURDFDemo/UrdfParser.cpp | 5 +- .../Importers/ImportURDFDemo/UrdfParser.h | 3 -- .../TinyRendererVisualShapeConverter.cpp | 46 +++++++++---------- 5 files changed, 32 insertions(+), 48 deletions(-) diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index b1cbdb5d3..563c657a4 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -618,10 +618,10 @@ struct BulletMJCFImporterInternalData handledGeomType = true; } - //todo: capsule, cylinder, meshes or heightfields etc - if (geomType == "capsule") + if (geomType == "capsule" || geomType == "cylinder") { - geom.m_type = URDF_GEOM_CAPSULE; + // + geom.m_type = geomType=="cylinder" ? URDF_GEOM_CYLINDER : URDF_GEOM_CAPSULE; btArray pieces; btArray sizes; @@ -695,13 +695,6 @@ struct BulletMJCFImporterInternalData } } } - #if 0 - if (geomType == "cylinder") - { - geom.m_type = URDF_GEOM_CYLINDER; - handledGeomType = true; - } -#endif if (handledGeomType) { @@ -866,6 +859,7 @@ struct BulletMJCFImporterInternalData return orgChildLinkIndex; } + bool parseBody(TiXmlElement* link_xml, int modelIndex, int orgParentLinkIndex, MJCFErrorLogger* logger) { int newParentLinkIndex = orgParentLinkIndex; @@ -1027,10 +1021,6 @@ struct BulletMJCFImporterInternalData } linkPtr->m_linkTransformInWorld = linkTransform; - if (bodyN == "cart1")//front_left_leg") - { - printf("found!\n"); - } if ((newParentLinkIndex != INVALID_LINK_INDEX) && !skipFixedJoint) { //linkPtr->m_linkTransformInWorld.setIdentity(); diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 2a60cb197..5ba817b51 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -562,8 +562,8 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co case URDF_GEOM_CYLINDER: { - btScalar cylRadius = collision->m_geometry.m_cylinderRadius; - btScalar cylLength = collision->m_geometry.m_cylinderLength; + btScalar cylRadius = collision->m_geometry.m_capsuleRadius; + btScalar cylLength = collision->m_geometry.m_capsuleHalfHeight; btAlignedObjectArray vertices; //int numVerts = sizeof(barrel_vertices)/(9*sizeof(float)); @@ -785,8 +785,8 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha for (int i = 0; im_geometry.m_cylinderRadius; - btScalar cylLength = visual->m_geometry.m_cylinderLength; + btScalar cylRadius = visual->m_geometry.m_capsuleRadius; + btScalar cylLength = visual->m_geometry.m_capsuleHalfHeight; btVector3 vert(cylRadius*btSin(SIMD_2_PI*(float(i) / numSteps)), cylRadius*btCos(SIMD_2_PI*(float(i) / numSteps)), cylLength / 2.); vertices.push_back(vert); diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index cc188e74d..cbbc481c2 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -401,8 +401,9 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* logger->reportError("Cylinder shape must have both length and radius attributes"); return false; } - geom.m_cylinderRadius = urdfLexicalCast(shape->Attribute("radius")); - geom.m_cylinderLength = urdfLexicalCast(shape->Attribute("length")); + geom.m_hasFromTo = false; + geom.m_capsuleRadius = urdfLexicalCast(shape->Attribute("radius")); + geom.m_capsuleHalfHeight = urdfLexicalCast(shape->Attribute("length")); } else if (type_name == "capsule") diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 1967cd729..015342a0a 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -70,9 +70,6 @@ struct UrdfGeometry btVector3 m_capsuleFrom; btVector3 m_capsuleTo; - double m_cylinderRadius; - double m_cylinderLength; - btVector3 m_planeNormal; enum { diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index a3631e9e2..520ca6710 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -192,31 +192,6 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi switch (visual->m_geometry.m_type) { case URDF_GEOM_CYLINDER: - { - btAlignedObjectArray vertices; - - visualShapeOut.m_dimensions[0] = visual->m_geometry.m_cylinderLength; - visualShapeOut.m_dimensions[1] = visual->m_geometry.m_cylinderRadius; - - //int numVerts = sizeof(barrel_vertices)/(9*sizeof(float)); - int numSteps = 32; - for (int i = 0; im_geometry.m_cylinderRadius; - btScalar cylLength = visual->m_geometry.m_cylinderLength; - - btVector3 vert(cylRadius*btSin(SIMD_2_PI*(float(i) / numSteps)), cylRadius*btCos(SIMD_2_PI*(float(i) / numSteps)), cylLength / 2.); - vertices.push_back(vert); - vert[2] = -cylLength / 2.; - vertices.push_back(vert); - } - - btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); - cylZShape->setMargin(0.001); - convexColShape = cylZShape; - break; - } case URDF_GEOM_CAPSULE: { btVector3 p1 = visual->m_geometry.m_capsuleFrom; @@ -257,6 +232,27 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi visualShapeOut.m_localVisualFrame[6] = tr.getRotation()[3]; visualShapeOut.m_dimensions[0] = len; visualShapeOut.m_dimensions[1] = rad; + + btAlignedObjectArray vertices; + int numSteps = 32; + for (int i = 0; im_geometry.m_type==URDF_GEOM_CAPSULE) { + // TODO: check if tiny renderer works with that, didn't check -- Oleg + btVector3 pole1(0, 0, + len / 2. + rad); + btVector3 pole2(0, 0, - len / 2. - rad); + vertices.push_back(pole1); + vertices.push_back(pole2); + } + + btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3)); + cylZShape->setMargin(0.001); + convexColShape = cylZShape; break; } case URDF_GEOM_BOX: From 049d9a5ca66c75cb25d22972b11bd9fdca7047cd Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 21 Mar 2017 17:41:11 -0700 Subject: [PATCH 65/66] Update OpenGLExampleBrowser.cpp revert original width/height to 1024x768 --- examples/ExampleBrowser/OpenGLExampleBrowser.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index df2a83021..42250d589 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -869,8 +869,8 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[]) } - int width = 1280; - int height=640; + int width = 1024; + int height=768; #ifndef NO_OPENGL3 SimpleOpenGL3App* simpleApp=0; sUseOpenGL2 =args.CheckCmdLineFlag("opengl2"); From f4986707989817a70973fb43f6976c8b98cb1890 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 21 Mar 2017 18:10:50 -0700 Subject: [PATCH 66/66] :%s/STL/stl/g for Bullet/data/MPL/MPL.xml --- data/MPL/MPL.xml | 48 ++++++++++++++++++++++++------------------------ 1 file changed, 24 insertions(+), 24 deletions(-) diff --git a/data/MPL/MPL.xml b/data/MPL/MPL.xml index 7ed5170ff..2b8408323 100644 --- a/data/MPL/MPL.xml +++ b/data/MPL/MPL.xml @@ -49,30 +49,30 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + +

    I(-T*e-*Z+UI4Y(_mU zy!D9>Upz`2K=lqq3GKRsQ~L?|G&w$9@a?2a>8bm)=xw1h!)U2?=n;VF5PsKrtX{Hk zA>W21SN1`8^C7afeWW6~4*qiKEU$R5sfaAMb3E}d+Wm%S1U(zt(9yx|1^2nfM3aBs zicx2MgbNk*;^`aiG+>nmVwfwiL&IuZ0CW46Ot#48mryFVfsXrXv~2k?l57wrv>Jkl z8R(}Of~yZZ=qhu~!r@KTya$T8`JDUwUF@gXLpb(ij;IJ)BAyz(8&`>1ct?aJhLwRt z5@3En3=NoxfN?YmlO1myjJ{vAAT#00N%pV=;;3a<5Fc;sAK7eMeDv)lvMv5=K_u?3tDu$j3m>YgOW!94y zqUA4ah$f6B7OsdOeciVTh2`ZqXiWlksg$6~{s3o(`eAE5B~LuqM>_fEB1!*uJpTL9 zOE!91H?iXRejKSOlcX~>VqIXlz*du_nu=Hm7#uxccJIngbP0Z*&o7(N1AoD%aAY^6 zwnc$ktT*8bW0C6)vQmUvbRoFMKjMWIEy?T|SB)$90_LcnyKMijRCEMZ^F||%)(o0P#{POH^Eg?6cc1d$i3h8A)ERdAUnznO zF!x#A9lJNUkR#rO!p<9q#ZfJu#H-UHyj$;#XnEOy-!vN)W<6kLO*fS#jXHw5{;(mb z9sAJ9Z9p|-djN81%EsAR!?aT4}-dmid?)6>K_xJIrxzm2!l4g%9 zpt`{lkKi|T$n9|o$FQI0>ED_pcg=1xzSCON%Wj=$X`MhqPpFf}TOvjIpN$;js(J+? z0ppUKQCb?AgG@Txk~QbGsXY6bByV1dvQDRA$7WZ4+|8y}Bd2L&=D^IRSJ^rAq$L*Q z!=XLocVjHt5uGSDKZqrJ4|gNmewB)f=fNCPrpj-U0F&);Ql1x;jlrya<7p;i`<3E#@LcyX>FXAZwXeStnJ8p_;GOYN#gkpYff695`cS> z6TAnC8Kh5n3SAFheaT{*dFYK{XXve&MY6I?Nz5Ec{Bb6fV?L@9kE4LGGrue!+}97; zthObSt(Kv$vVF>-?OjmSU69rXiE!2f#e&=ZwW*kzp5+bx4D;8c2RXiA7^-m? ztlgmH8q`O7HlM-wKZyLZW@1)=EkGdMYS3>y_OuD|75h@J`+xA$ULDE1uN~;}JF3lQ zoN6kf6fiqdqMVj~{vjk3fUdxs7Bu=@sWR?RThwTH4d=cBQ%4Y;W0-AvmH5h!%N)as zUJh4QNe+90r1}?+gs%&1Y3Q}SQh&JSE-<3)lV1yhLonK^`rcdu%>L&J=PbLe!s+X_ z#C+fn^m|j8vh-`U(E9ZT4v{tUOqyZJJYkOQBS`H3ti!dpim*fRM9E>^c|VZ~aMb}dr+^xqxXW0MZ_nC@8V=DjRbsSHOw2W-V` zHIDG6!46#mmWxMBK!~gQor74=y$1ZPCS&;%1mUShD83&&=2%s7Pb7AyOnbP3C z81>$kc$dycUgI*9ZaP#5d07f`(a*6roDZ;4MAdaTg#sNY<`~n`yb))lYGX5}o3uG= zFj_Nfj8yQrgmyc95y>A7mt0PXh+&qf!ohcdv3MCN>-DxfE&63k626Y6emG8f^Hm?- z167z?3r50VxCsJHe=JlzQ1eG#!OMrZVWUok=+&@8bil*}e4~(1(leC)&{%=0UE0&W z+fVSD7NWv@0}P7aE*nS2(lPpWr1s56!R6By6Y%MzwYfMn=mSLq)_d=1i!DZE5#tUcI(Xb=C<{hVBQX3?l zC3kr#f=xvX)Jxa}V)N=FUSUg&{i5jxZ6ES$J)w<$pf;vFfs6JnS_5JVl}$1#m6-ZQV^seEdI-8RYIugOBA{d6L^RTH1bx20sE?LvLgF;Z!``N@f?<4MW zKM_SvXipugs_`+mu^f}4(t#QanC=rrdBemnV##4!;@o*OTE62jx!K`9A1-H85ovoe z`BX&En3Eh668V-3G!28qW68;>=w8Qud znQxEf8L>M>Iec%5^pB$=^V7s4U>?UXFTBEU#ay6?O+~QPxXk{7eSU)D!iKTb-?9%{ zybMX~n)zZR>P7p~?qTLq_tM@H!@PrM16${8z-&)T9x-Q(uEH?Fmb4lqqQd+$BtbWc zPpq)12o^(Yr-E7%^guQ5g4Y5t_HaP_!FDj6=E3&sSH2k`Y!0?17ZbqIt~`_U)@^oTJy0Htid4->=C82FyCSYZTpIEY zCw(fxJ7bM$K;3v@Z5Ipb;^#|$4C^X%3+zjKOh}+M4>M#8(@$0LSOu68mp9I*CtniU zhS-wL%D-ssup^{kQCoq{NwXd(Yv|}o8VzpDFiljUQHx(bdJa9{CGa!-CVIQ{5MopN zh{vy=6`PVLVdDUb=9IRGuP#;y46{~sp0*J%-Z4mK(zhF08)r*WXQ(5~r&%PrU$mH8 z1e)rgpT>sE*-T;3kA2vF_FWu42WCHDPWo}dA!M;@3idP^D0*a#7S{;JaK{28ykSU+ zICl97j&W0++=c*V^xDBPYqNjQ*+g41uua*m_kAK}116+pkXX6VyG@RU~0Oo>?x@>0Oc$A+3yTC{V4P3RDESPvqFh6_- zyV@@0nkf#$YOv$)0XTeJ9@l|l_EeqQEJHiAU~DVwvhZ+`zxXE7jTH=4gU9Q9`aTz zHz^8lo9as@gnbmYb~r9B^!Fp*G*YqSwN>Jn4*H0_0<%?^T)^z8T3&iyJdP}27x=#T z16`)O52r4k!83xeqqba(o@E3|??#k=a4)ug1T#30t&KJN3i9o7hP5TYO)CP-qusaVC+c%i>`7Y^^G_dX+|iHJe7!%ah=RYYizAy>#P*QCm{zilV`f1?5-=1n zzYVPvo~GGIP}q`jokQq}Z5@@%RtYHAJPq$&==r}Ms0P6T`_4$mOwx$OX@z+Xge*@c zRaJgywQH5wr6H6ARCFVSzf;7Mmtm>`Zdwt1Zvb-*Fl$$hQVhT;$fpKwTK7B@9WYH9 zBwvO?W@X{DhhdmmBeNc;S(|3#R_miY@d)a13P(O3OctCACUey0qv1P0i>q8#kmRX7 zNcXFv*x4bGV;WV>NmYPpav7xf)dRd8)a{7X4RbVu>{7l62ttO?d;X%63oP=}>G-#%rkUtwuNW!qoqV3NpjyViFG_0l$Fh57M$fsz2{0)UkDd1JmjttIc4SzC4h~wYRIY5bL1li|vBQUVJjG?0*26V0x^R_a zUK*UiqiWVlqpVg-`dA@o2H4O6oz0|kaCrt>P_w=l1cq@_eF$0sW4o%+InTa>AWO3& zr~cK)$=+1?q4Jx+dZ5^xw9|rO{%lw&f|)q5)vz<0W!b@R@JqE+L%%u|D36K227Tye%&T1rT7(%Ykr1Iz1K;}>i~A`q z)NVggx_qJTWuy6OKEa*_p}IL>j;#%q87#G@{a)CSkMq}2gPSqRTIF*-9>+=%>e>D{ zx)@5{7jJXb-lkJ!_Lv6{9j?k z7BE9h!)4<XHDAN_dDpQ=EeL8) zSI6#C9|<|0f#MMvbWQvijP-;FarB#1L2qs_zJ6gm;cuF%elrX(CocxcEN=$VjxX)V zgeSQ)ePvH&8~vY(=3Td-)8PU>AJrTCs25|CUP_!_b_YlIKZCW-TtO@K5}lXF_z0g? zE+B=^Qn6C^sL&&Sl%n;&tDv;Bjbmz5`3(Wg)OO=#cI9DoAKWyp!T-{e`(vdu{<_pf z?LO~^R?gSq0!?fxf=RQuwL;yX_7tj|v`eg==Y=-@h$NM5Ut&dofJQBf5Y=OU;jeGw zIA)+Kzi|Uh_npb1Wj`(%DOTR6Bg8Ob7NtxeT&_5?JX*9<#O+-G6>wB>duR2+V6+_zMnBy(t=jt4k zyK)a%R^N#@Y(0wXeI)U&h6X8Yqgu^Bs{Cd?U{+4-Bj4<^jK(SL$fn)<=&I|Z$mQ#x z)dk@oo0A^YejLs+y@ss=^Z1Z#+?rdM6}=1|S9f^VdArxl+TO3#3 zink^2;H&upn+?3s%K@X-RW5%THkw{JVMqK=#M8v5!NkS18)c{J+A~f-m3yuZ73VQV8i9jn-X!)`g&gRU^=(`wO-=;8^f{u)d+g-DN zZY=S9_!!$C2}LDiJ5o)%Va8ot;9nA$DTa?$pRcqbHI=nL_v_sd+;JMbKz zieLv_<{fi!RgX6~>G(-5r|Z4;Bd%9Jh}T*W>ax`lqzx@4cD)%g9qr$5Oe=D_NEJCf zqy*nk^Z-@^p?WxAzI{(9Ez`3WcWtyIrn`@zh)w6nuj7aK)HiGGt$HZJF8z@YU$E8W z#6nL7IkE61yf2Hb+ldy3;Nzx=39P8E{Oa3X=esfY{$o&LtaUOV-+v z%?FR7$|(h;>gqaBeTNZ+awu^RxCjG(Z+UI4wzwWMuL#x>KXrI7x}#I9(8qBd{e9;W zHJi3aIP}4S?)k5YTIMel*=mNUD(q>15jJN!Ydww>j<2>O&7-1)+3m7Ox?gWGS`WOw zK~b4uw#|Re1)7pf>aqEiH+<@Q=i9&H`MhpINLh?HBc(fi6Ky3Ztqp0KvlqRP7$z`` zo$7m&4VZTiyUJ!9X%=Q|vLjogYLVO69CA-TSYRbQ!=hq7uD~o_@8@LUl*jk*{Ln^R z5qloHJGO|z#eZdq+Lsgo#}0@y9_+@#qYk+8N|ET5{+(l4sxeaiDhw*}u3!5p56pf`-|=OvG#t%D%_(!xWc+@K!;#mQ^E4mlPY&>5IP=b2hCK z4{SJy{?0rj)yZ~=pS#}Xn8m8#_B>$jZ}pHhKc9j$ z$IYu%0!`Hu{>9Oqpt}p2lU$OZ;L>fe)U7lDk182048Pey9CzRV?llrgwD`7oC&Ync z{!ihu3^46mddseOgdw*$JJNT*EnW0IjD-4r5t58baM6N|c=ii9*HSI`gRuE2nEiw~ z0yZa|EVrWW5gKGm&qTrh@=Ed1ppNAH{+){H^sG2Wq0cdsRjauHn8*!nWiy&n&?&%x zpB3HkV>*f4=_zAFvg)2wu*usJE;ptAs1w$hca-ZuvD^~{nd1Jp$CEE<*M#c9N5r2y zXAtGiY1l0_PMk9{hhu`^*+86jA23Vi$2w12pN(#(L&z~CiMl$dkzbPoK%fau)eRi@ zyeCUMi2OP7R_^B*HnGz0w}_8?4<%bSnW95x>Ef6bp=7|OEBOAgMdBC98L>C*61>oW zX#mV$O_!3tCvwq|lXgU7<4NhqfwAbYX$$h zOv{oovsUw|h@yQiTsesiU-*6OfSdNI#<7|DXmX1+d2?YeaY@*T)PHA*sR=QpQ}3>% z;%2J2>%Ulz@m7WEEr78e)LYTHOFFs-kDD=6}`RpvDXf(*Vj=s>V4oW;%DzLSnnv-Uw2xgG}?e=5L zZd&PLFzTH83on~(iYzm_(w2`u@WZ(siI=GkJ)`5sG3QjyerACA`*-!w^5Fl3IqU4n zE^|$6{9mb3(aju1kG{%fL7Bk@OQXC;R&s$RR>)@`0==mlB)zG@(ykG8!l$~v^v-Kb zDKXtr>Lc`~G0i`PRo%nTS$H<^z3C4atN3HiKdLqgC-&GA*GLU~YI2#frAuc%718Pq zs^hmo>mF_zi=o*$G{d-oq5VD0S<*cpcj;R1UBcjxed&+~y3!1|LWkH=!xQlw6RgT_ z1_9fcC+&&uLkl?nKcjRiz9D!&1%KiX|8cbhc4jlX>IK|D=)i|kgbUb= zKN|v)R3-^h=#rPR?WrxIQMUVi*@yWaA1Lt)3CGrql=G-wJ!8>9r8`s!Lb;LYYTx7tD5ac!iVt z?}ZSs8iy}|;!1xJ2F~wdGx;X0@wFR%(YKCHOfW%G)>z5f_Y4h5zk{ZZ94Y@)J76-c<7DAmP3W0N_TXeCioJZ|lp1kEP+AEj9(Q2izh4M1MHog^gPLL)&RTkv zmm+4QmZIhVfrh$wERHCfMn}Jnp@zn5(3wr$shdR(ziDQwaBvo266<%$irbH)9iar5 z@gzfd*|jX=P74c3$ux<}BDuk6XK zKr^ZCj6Xf`p1?S^$}3`xjTWBScm{jF0XYNo5TkMD@CdVWNbuVy{_GKs4%;M?OZjcd z`_*fZ)GkHz`=&-7tl!NsZ&io)!GPJ^ULFbfM{au}CPfq5TOx59iG+>sk zdsq5rc_8(Q~-g$JJ#<_(D$*3pkjL z?0zPaP_Gns>0*|rdx8JeEQm7;^i=V zvTEmAWY-Bsep?>$jKH_sNo;;71FJ0qE(A>R*r%n7HpPqUR@;+~C$FMWJ_V%RkaZlx zK5HhR6U}M_tOsfs$W4`f{)&TEAIGNoh^EdlLKpswm)Ldj>o7FQvj=Un&q!)h)IIZ-UudrNZPe!&=ptwUJPhUQ`C2$O6YjD$U118GPQT9BiL^uza>j(7lmaxO5$hcO<#(c_VKq+GOMVt}P zz~!cx12gMSV?(kf)*r)bLODDM~$Ygz(6x%4hCdaksAOMnfIVy%DQ?cR7k9L=#AEbQq$2qf zQ8T#<$2?RWcYgrPv;VSWhXdAt;-Nh$)xAg?I!2PY7ki4@Z{dSn9*MQ9DfU?L02kHH z!dGsT@Q*YzLi-eDB)x$751Rvhg%Y>%V$qPB_`#S4I^U;J6zK{6Y}Ttn_3wbuTp1-h zFd`Po0CRh-h49d13Hhck7ud<|`XjzLWV3=}v|uX2=P`&k!yExK*toQ=8=A7(oNURt zE4aJ#7qi<~k?4sLUF zo7ic&1;1%oDvT~*Hjn8iJCUD*>@)4jrZ$qD&e?h>y@#gVlht+?pwM6oJuEypkge@Hxx0CV|Zyz{Ir zxhNC1&hB4rr48e1=^M8=P=?)y!?K6+acq`&Xf-sUG+k&Cz^YP2XtFVJe4IiyE22@= z{XlW!wFII!-+(;aQY7v(S;H}dRj)vAz#NgQ$@|E%QPEj@GU<`J^r(-PvhSp+C~bQh zE;>3B*MheiOFSHJn_)F6?SI1;!}9G&oo5nB{JIk@$W@5?ff2;1yBWcxP`o;BC&%ch z@*8WwEbLz?Pd$->ysp_3v-~8Qvw4zIb59s#Ygyctgb6h9;R~zj*nd$rZ?$3#{=-5C z61P*qq{U_}nrzf6mb$MZxi-B?*Z6YLV0<*kw1+qiZki)tZXft2kG&XzDk0>UmJ1H17wSoZP?1Q|p!YUpPA0u$(!hGIs$3k`YZZ@R$)^rfxbVJZcO;L)I_wHWGmAynxV9P;Irm0hYnR$;=#Nk zX4k+8I|R3lQwngki3y3E)st-Wc0lcab*A|*j7ZGsE+p@^2E8$M8prfk%}I|3%>Fzp zd6;7l^kn2fGS=Y=O8HWx^jWQrTCXW_p$(jEg7GE`)vc#0c}sl$kUH+;kvYE|`M2K{ z>^V^jDNW6&-?vIU+@=GuOzli3EipvFkiV9zYSJEnS(DbydCQ=SLaygP;xa}P7tK&A zH#&WU`og7pD>*Woh-7?Vvka1wQu*FD*u)|9tKYAW-U4zw*2Rs`8oyP18YG`KEU z_o9m|6avH8tG3R$fSK|3mvd)(J)zyIfy6XZ58qEzDwD<+2>$66xGMTT>~^u3SEG!M zs!9<|ql;}eraSB;(;ep0g?Dbk)Vw+biy3d4&F5Q5cmLQeU-N? zI_kWl>!yLkTB9rKxAK&7*Y(|k_b(Xo1B^D9akHkrj6W)`2o`db&CkMB&1aCGez4Sa z`*YdNmzTxj8$|L_)*vs3yQt;kam-fpNQGGgn52#&vIv_DaZ$)XVqY60bjv@iT>n{J z#-<|pIQFM(eBY%SLP8KXu~p#0SNHME_+5DU93%XxLvJZIMox=$R!fc9f2lb0Jt_~gLKTL^3TR7BjMDn7$LyGV%-gbv21#Wd7m z^={fT;TCr9-zWsVTuTki1T^~AAe6KF9mnXZY6NkB>FyOTb2>DOMje3F1gsa^#xGZv zt&0`esC-c9O&mGi6}vsA*#BKQR(oE-{nol%Qp1nmcSI=~O=68s50dBE7JnamN7M@` z6+Q;X(8NcsdC(3zz@l?$56`BX%s@kKmkPfuQo zaC@c1Df92(G9Pe@sk@9kuRoBbS@seB8ZIQl#{Jm($x$KmPO2<hBIo+R~4@thu>?O z6X7P_U*(0Kmqn4w5pVIm`eA6u?g+7;TRZaBGLd6OsxWzgIXOd3Hh*n6E!#ej80P5E ze&5xxQLHQVjjZKDn&-FZaxXkK6=668=A?~^@#}~y=)bx{qIGyCin2=~$)B~!$+r>c z`;$_!va1e>9KDBQ5+wb*{Cf0toVJu7Fl;Yo@1t{DjrI} zJZ+O)+U=PS-42`0p($~6-;L3vt#2rAPGZVQdw-0_R|?9xWGl-E3N>!y?CJLS$PX(z zU`Gnl=p94yYII2ZE!oH;@0s{((Jwr=%MOl-RsC)%08_9hS$_YV3+;mkk}GAq>6(BY z#Jc|wI$OPwTT)bO2f)u0Duv(`F>`VQ-_v9%^RYpHYnr|!4$bsjPtqo|B?tTtpoLd- zY0p7VvCaGW9J5oEdsYLc)asOckIaZ#+YBV9{1*ssCxc1Ts1DR+pvo)4dVLa)I{%*~ z#eB6_*r7ut-uieb?N1k>uX&?M)3Jy6L+&mVy;qNBKfjC(orZACBGvIjJzyqoS}z}d z>yr4oGd!D-n~}q_T+&nPg~%|4MJKUCn-d_<*2IS|nDfQa^iSBsHxtWx6Z*2o4ow<2 zNMe_F%?vbWa4-61s+sg=Q$MMz*Dh4A+M!>w)tvmd)U?@ByxeXesm8m}JIixKzkHg= zY~7d?SZM$>S;ACA#o>IF1M}w=-u;kUZ%5y(ZHwGGm`m(hu&h72Ik+?J;H)QgaMt3O zZ>o%-88D~3zBy@Htdkl1XHSlQJ%;xG$|I$p&+{Ir!Xcoo{u7QN!1*Hjn=0{OrHFG@ z=W%QAKD5K`y}|=eC%P*@NskVR7yR^1=!XL@sc}A0u+_{_Wdy$f)2C08b9!R9@a3aD zxvM5aga2lduz@o~Hh;r<2N{NyBAAQ;YlCA`5$sg`!`U`8>_;0RZlb3cI?tZ|{IF1_ z)x(sAzMDn;Z0ZDtIjh2G#De8sn4Zj|=SN{BtR`;eO|-M_2gIC0+_pvz1t{wib>jiO5X9L7AEh>yY zUfc z(mQa;|v$aRTb-TOzHRQzUBMe9TwV2YxsIA5&)@SJM}^{bUXyL!(OO z3=Nvp*=sGylzAp|NrWO}85%@$noE%eLdHVUX|H_{5<(I(M~0AO&h*}E?dSPD?;rc` z?`Q3^&)(}^*L~d=>}>P^}uCZ26Mx3-Aj8xUEf|DVw{NeRg}mR35&`750~xH}Q&qnJ+q#k;5fE2 zn!;TXERurdNxObH$lDTFI(BwdYfKYI66|qFK<~1}CmWoJYxp4i+dD&S%ss;~KV^&^ zVBDe)+HYTxjUK9*kv8-9(Ph?c$hUuP$fs`>-mkRaXPu6z5J`bPp{hQ6d58n6Z|p`D z<9M6xBt)-0T9J5K^zqnAu7Y1@(=D(r*kk?(c*=WdN5F^yi{2Z$}#Ek=5{<_4E(i=-Txj$y}Ox_+uvT$dY2T*&&?IZ?MlMISqPpsIX#YLMX*Q; z_S^Vv%f}ZJ2a?xIQph)RU$noEC=R$0PVR+jky}6Zh}{FjIEGEKfG2GxV06Pr7SGEB*2H2ciHms5DI@zot=2$toT#LN^r%pVmG5Y1ykv^;W zjh%aUB(;`3>5IG}9CKb)JhlPm<*(wRo_c=-ts7<}uMiSro}W`~8=;T1dR)eFOiG2L z2DX~Moy)PSZOMOG5rb4#KfX$o9j9Q#u2;X2jK|H5L*tsJb=vL~Me8_4UuZIf-cmt%9HN9w-(`!J7IEU1v## zuG1u!ZOMZ4T$>(t?Iy)%bdz*Xn9=) z`h^e_Buf$bJI>*yzu^UA{+j3Cuxc#{x+I;K2cr72cxir>nouURq7IYiO4q6np#TpD zwA9xFv(-G7F?#@WYpc8BpTP{V+{m09KO~`M;wjaPQJr9T7R42*pSe=VUY(9!FgN8( zG0(*RaMtzsE|BYe(X~wrS`}ou2gF;VVijDnctqp5d51@&R!UV3u6mrg*-u zQVcRRC!=e2BBS_pRpZ~bi20<|ZQkIzg5A8yB7FW6J{)-4?+RREyA`_xYT-6zU+Kzu znZgu(C&_PCC5;~b5KXkPk#3blAhsG^cniRG@FZY=;7nR*r91U?HHI&hd245 zf<}G1t7AG}4V$P8m?FRg*M%r%G>oK`GtJ3TvwT79;jfDPk}rfe2QT5O3V7kn!xL{@ zz@E7`uxr0kNMNM6I7$~^j9i5_X;{%OBU_W*rWa62YYTeH`;VaKQ;QZ(?MB#YmcgqN zFeQNT$=<1OtM#N$r<;?8*JK?0P}4Qw7g$Dg*@-ZiANpldgHIZUXEFWe zvRR?%ed#bNzn4UohjbvJ4k@VEw@e)Jtu<*dkLQ?ZS&DcM82{YVbJLq|qOlI*td_M@CcAYtM1DTP~iwVJ;p8 z(rQI*F5ld;49P=_9dYJdJGwPA9_=*PL4HneLtbo6Lz~`c(54>mu=(QE9OElv)S^Kn z7;eLGpw zI}sshw)H|H1k_`<>SWY66tY%!SK(oC<2mNVHvT|s00zH1qWt<&jeh)LMuLooAg?8v z#9x92O29BHNzJ;w@b7<#FF49sc=?l|JF;UOzPd+2b32Sf*C(42-+>Z7HZ~ZYT&zK7 zuPMZL1tX#{KMM7b-_TtFWBR3ni!%iCtTII3k;$J?WxDdJ?-BrY*=s@F6e+%zT?&_P2lUD4zNl zK5H9NP^*EbiBb3nk^MG7xhL@j_wziqn)wKvdpzS(gef@l_Llaem*Q)LSnnpvu7*p` z1@CtQXoP+_jc}rrVbbM;uKs|zI;zZ}zqziE_`rKV)z zSufx4raq>4_&`u98=Es#qZ6IjDoXIX+m<$UiKeI9m{OHr;du;GpB^_)n??=-Ddcuu%DEitXD9b53^&l)r8-NUbRJedr?~vdKe6bJ1>QX&1qG}aM9Z`KBZlb;FB`xp0JEolmg3=EP1Ns=8S!{l zi>HmvBIUnli>!B$HIA{ugH3?(xw4yEu$cdb2`h%ZU^et+2ORu#L$Pggf+(%nhp#(y zz^i|~7V|G!aEz0Dq&f;Pu!m42^&5^3*O`$Tt+mwuMJ!n`C=iuBtibAaY1}8x&Y{zn z?BG)rnH0f3(p_qEq=f;xIQy2DV#EIB;*>-)e5y84%JaDYa%uj&PDHtCgEKQEF0HpQ~A;sTiO6DKKLEF;j@e`aKwXR^4W-kt3J zQ6jj4+49TyWjHkmW(Y#zk@3kCKWTnk-gQDp*Q*8XQTJgc#4hWRFxA6D92+u#Wa-2s zlVFuNt?nYnnVKBVu{Nyw-2Fn+ms1n-AtbD%Qv zo8dAaNcw|4G?OA`Y0twhJ`2b#n|k4p)md?_^J?;TVj5oeJVY$IZq9F7G(2grx%C2! zd+7m(ot`-;p^Z7YR{fFQ0Y$LQg+<8TYY+ZXXvU9J+0@>Xd5=-iZP^vUPHq=CRpX~i z!pQTE)~K6Frg-jU1UVV~5&sdEi&tSl1AEdUvV6XP@fh)&!m9{e0lHr93^ z9t~+?+LAzy!Sd!d2rzqH)07DxGLe2?b8>F)5jtgiE7j<-amaN?Dz4O+#be!=6tTa= z5c~Ds!+#sLxxE9XTGzB#;(aOz*<86OhS%&Qj3GZQ~5v*qH7Jkzr0rS}H zz0zuW0;&|u$$GuFirI&ilYz4_gnr1$DcK1)}{W@o}V=7=B1BmpMd*B8Fg>>i?4>7EkL(Vi!#%jhn`!TL;=v^D(2yG>8w)S^i3#v{}As z?>BKw24Eb9Co4BpPDWu#=0xM?X;kl=t(v*GC-P|qnrEA0?pR@4_5WXrV0MMCK00LI zdwp`$+zcIfqeWj|)FItxYLm3VnzY_(G+)g@8Iuc`%<7#*3%lu}kV12^x%n+*e($vE zk98MRZ3(C9=OL~Vnv)pjf29a^c+ZS6n@yXOzS}P1z@ME_x>t9)vINqY_GyrQ%XMkn zj_uH%qfy8OZW_GPP6MX9?rMji{z}2L8un=iTjSrpDwTa710Gw=r3ff-8Kw^ZpA^AL z+#(lGsmR4$GPXS`wC~rSo<3nBWe+rwdS2>DzsFw?80MRdp@0ed)?TqK_Kzaui#a)X zPYtiyp;FDh^Ihp%d4pI^-;`LGZ6LyaMLOP z6WF*}5#@S7{Mp5V)b4F2XiUpetzOwqaGiJ#$AOw2)N?;?PGTW-1+zuWb~YN2Od7gE z5BHp5C^@?vp;~Fnq{S!Iq<%sTYF@usD*f1#GE4&eJz)?12r!>j5sIqB7W9vS1&J_? z67$t!RO*Mkcn?%raSg5ui^4w5Zeo`M54gwU$)xM}OUfeb=iCD0*_E`@FGDUq{P!S6YR${9|c z9(dy+1(&gB>TMod?W}zP|9)wPk38Cg*7zmSkt1*8juWbcH-Fq|(zhY#`vX&CboB$r z%!O(VR?`5O!|%5$e&2MVJ4RR#Va8%{z-SNEs8A;^MR*$BfH>+A*mN|-6K7uKvDKC^ z=IH&eW;oQj6$(kbFHW*HCfA+Y;GIvD;)cUVgqw>)@GKu^!fx6qc@NzLm{xBWDC`n^ z>0Ad3;(5xS)|Kn4qOtg95YN_O^aQSy*krE(dFF^+5|VvGi)IZUAIwk)oejc z)2sM^rZJ%!+!etFG?^T{hf}ZSWAhbx$bN>MxXO0|GM*Jd3RZo@)8{*&EVnqZ@JAC~ zpApS5neygV6ELai84gdIhfsIG{GHT>c1~`I=XqE_q#blT?3V{LRokE8gEadlKg8^& zWvsk{3jE5%C!NxeUw$%KkxpMh7se^R`77g9GT) z!4~9veG^qePmN{cVCuX^j;&r+3jKrz6z6t0&fTl64wqmO*&H9#Y)&tk??Wl6i6rrE zM{;FL4jS3{tk^oV1#w?1uO$LT<=EHe+Lk1*_CSqEFC-e_c|^`u!?|55%#W+@t5WEadNB` z&HfvWUOKHOu|u1Y7C0647F$v+?I(E7{ssJ|y^&XA!+x8%3Z+4qHnnLmCs{Al(Uj0+ zVzZ-I^jRiL5mPtIQbg8Kx$sE({Tize55d>l+0wjHH+28i2(s$~ycuf3QN*UUGx(v7#qQhnzb)Fi*5odL6NLbIan-h)N$ z3Ukud{1EaCIYR;x#uPIQlOnP@|DP1WZd&yW7^?>#>0vEwXs-vYk<(*iiCtec^pQbg zcj^Pp3qF6}QHJRWPa3>BrvoN-_fm%vnEyWFnmPG1;ScujeS}0$G~ga~CPlDWs##rR zDWX-tQ(SlT6IkKTVB>2>G}1jn82Zqf`cJ=1^E875$z7N39rcNN%pD*wOh5Szy#O%h z^(!2%YzY!xmztCNJxWl=^bC@C>{PK&jvP|gm<|;|%nNMOQg)3%A7<$u1D?%4-i^- zSg`B>W|%%_vEMLRicnvZjV~Oi!dWoSn{^G%yrf3EwzMuD{OXp&-z{gvUG}kf{kpa| z?M)}T@Zd0xStM6$K7e_(B2e*V#{hKci8&cIqfEH^W)F#(_oJ8v(=b_hhM z;=!BDj?D^>lC2k|g-^WDux@9I7I#}NR^Yv8=(j>C_G5{duCL88ujF0l7Qhs4-J;0p zF&hQ_GAH>?hj7Qap(H7!KwzhX_AO)ni>;2F=nZ?e3;Yn0Rco7GuaZp1N8>>cLxf3z z{Y7DID!$rhjMQ%YJ<+eWhW|Fb;SCLY=$(L>xo(`I`Gr8#<-0lAP-a2zPu@;W?dS(b zs^@U;&%QjinpFg=w>x6b@uzun5>q@%x+B`+Uvpw49u`)pc8D(yXpo#SCSuz+kH!17 z2RX(`#>4vsZL!h|y*LeQh{7i{as}3-4clsDZ+VVK3>qh zKRFwkL`Ld`p{_P5Vwg@8d38ybd=3DkdHha}DU>(2g@7@g^-P%K0kIA1f97apuv{rx2i(!Y5aIW)optt@I1J7fotfyO;a zi*M(|ye?rJb9e(^%>}^py-=f!-4ur0eJ#k~+U`QbGk;aG7=nVvfbujro@0E5Jj7pi zt%tPVTwZuE#p9;VU{c#+ISH9C1I;sQP0uLikavBJiDF%?sC6%ZV>YbknCpOfU3ya4 zaMK-S9S5{?O7$1zoasS12tq?TijZdAckJ1RH_b}m?PFQGPPSR4{?YqfvyK1IJNy&!nf+of3yC| zT50{2t)AzePXuN2d!ue5oqJ}phC7FHWYp+|s$4?!JZ4E;3}M`~OJ)1H>( z;FY%cdhG?3eX0)fy9v=@iC=gn&HB@rD}vdvnMRNb+3c(HCP}L+M@e_o{Dp@$U1_tf z?IjglJ8tOGq_uGz(`_Tid;!e2ugewAabe1GTT4QF7~{3}r&U^TeBd|}0=K~x!4hNG zlg3;TEN{*5FicChdK7OQoP^G~#!C0UsR_Hi-iQN2CreXHPN4q7jw02KILua4A!Ggm zCUjn`LT&VV@s_hCIWodtk+|ffO2<7{FoAT13kMr{?dgT?Vb|lbE265tipN$jc-aB> zpXDf3k6MbS+exVBf=<#-RXqyV+ax_vYb!BK6Z~&r1Jx#`x!POENzK!FAxbkW$>T-w zNbSNNRsD}Dh}kK`We%@#_!mei&4Xj21n5f(7kMwoo}ufolX_QtzUOON`*t2$cx<5b zb=zecY6pk-T@9s?{uPK}F3VdEEx60v$MMmukWAkzDjL*(bXq z*gnlrSqXj*=)bKh;Z5Xw0t!)v-C4S2dlKHYs9Mbbn?PH%@<3J%BgCn$`TVApz{>_! zV*r?r(_$3rXU0+69hT(J`Cnq|TN_mqU#1D3LoQ&KmACPm+Bq0ipXURb_>3;gVtjwS z7OtDV7@0Ztq-i5MlZq$*kWNoi`tt2tp}kROJb#f9VXMj8$}xQbWAd%yxr|RXw}6pT(1vjLA~yBB35WOKlNRrz+@+pEXw@m@pCMz& z*KJ#HjqeA=mgh#o*lnk9c+oPBQJ1SVbHHql9j`dBWINrx(~`U#D$+h*?@KH99u{2> zRbU@05ihFi0=;SZxL~>RKPiH_B8(Pv7n?P-L+Pyo$f0iKxJ11d+Ohvn@x72wc!gUS z$DEM2>h^$%+xN`DD?5a$LM%zc6?@67uu>eh&WzSI+~-*lY-Fq6#(W-I%_hJ&7Rp%> zhBo+6O@Q`@2sH!!2;|w$IUY!*e%xOWIeT(H7OZm5P0*rLMg}tX~Fpb}CNj_H? zO6l5Xu$wT4veA?59J--J58M(Mw)(p`=B>O{p9q*<2i7RXtLv!x221kdW(JLP=|d*Zb>}{5Hqz+U1_e$Z zSc2K+mQClW=y4sdK5l@uJo?jc*L38c976_$b|zce=b~Hfu8Cpz54Kty%rUz1|7JE| zBJS2I=RTQEn=P~?z6&F%&s29pUz%|#f)yT>$K9d*`X-kmSc8A{misv2mou)^9ZC~c zMx&wUgGk#*4f4Zq4~lMTP6gMOxSy^E$7I1<03K*p!1V3VzWAE&KM%M zAp5*G^R2px=@D#c8xDHfLylp4=%lSL@VarEvBq*ssDaj_*i*B}H|_S1?HV zG%i%^Z)r(vjc%a|(>!9}w~AK;jn9tbvi@+|kyg*`*bH+4nvW<%n0_+oj_wY$ zlh`#{Ux9MXdeITz`$;2K^^q8+wR~n10GRxA2m5y|2Nh?TS(4nB2hf&=lVr)vRmEB! zFd24O9`71r<_nF5C$ZzZr!bxT3-49WPBNk8v5@Drx`MJRp;x(ZW>OzIbw+QgFs%>}OgV{J!LGT#mQPOFv*e?=f$UQlu6j{i z6ZJt{yL=e7JC=j`oo-Hje>ZZ>Jh{F}2h6(x9ts!K1?`(;N$wVP!eMQ)h?en);<{&# zF#B!d_NsVmZ&JA|MZ`rt#Z8wB@zK@EC@^g-zIZgF_)c(;XkDI#y_a>w6)z5nI^AkH zWAYkvoq2@pd8^9QRf;frY(%*VI0 zk2H%Ezv`DE-P_U!k5w27u5JpkT!HXe|6Nk=U;D&P=MQmAp?nUV5126_A&Nd%SEHe; zEy>OvuOvP95K>xw&LPek>Y61XFbhh=tZQgX%uGB)O$l?M zpEmXY8BfVENB8%|W&4iFGgDxITtClINF$;jagQz$oWQ^wv2F;dy_%1n?>{e|8fD8@ zb675;E(2y|n7LxF_g-{uizT_(BZ>x}?nwg5!XTk62M6CC{+|@VToIIH@~$Dj$aDC% z-*UVl*_E{Y)(RE9*)3K(Y#^(na_|>}C^70wH^f%6RmR)`On6?cgHPT;6q{s82D&Th zk(ayi{tr<+D}qT8mMhQ76@mXfE=9B&`GAXFA3ia|{~(!!RqRBMw)%?0zr~Q1kVnvEUxYZ(e=ElcuoT7|MS%6B z{Bta+w(>{Kj@}X*%R|WXh92b3&m1xSLM+Fegtq{!rXDaiXWvj3e~Cwr-&m4`e+z{6 zsk2nNbF-0NQYNlxxs#hO*c)2Ma3(f{92GVPirE#~*A5~1*S8VtFP_NX{hR0&=0*08 zH6dXdN>O+d#W8ze0|l5LfQi`lP`PieKU!rllz9FsL1V0=RQ1>PqkL!^W#Nu&auVwr znz|ztyUshwwKdk9bfX2N(2t)?hR2RYOdrUI?IV@|Fof`0mOK%upHInjZ2X0%`;G)QC@g3^ToF013Y7eX#{LFYrb_SMvHZc z?!jK@c#t;j8rhw^^X*Rhv~Ep{x-8{Bg#2iYN7$-VM`sQ~>W52tMZly8Rz@)cv)n5TyIICfEp#E2i zFx9AqvPzaB@)ha$s@gqdp}$u8yljZDJ0Mxy)nka{zq$(Djju%M6Hj2anr<@23NT-f zY*%=VIwt0*Tamt>RtR&{vQ$ouD#3E+IqXvK0b5=KqeWmPE)RRkt@1;9!1?sLP(1LD z4(>QzS4z0KogVU7A}yFzPZg6Nfmk+QTB;o-GR!l1*NFi0=W3Lq>)1B*V^=G(vHwUh z#DACS{jXL?Z*d{^R6fUXKO?YBQaR6xV96K9A-izTgSmL*++V1r_HFv-uoaHzd5<=3 z%%!ul;*jCUBKkDKov#MT$K7K9^9y)ZI(icztW!Z%;c)r(`0d#mU5NV^@+Ebr7|B za!xe%R3pLB5ggM^exQQ^^HJ5L{95i#yVzTiuB)SH^GRdKGqXul@4g&c&9Wl&9Lu;A z!CVn6b+OZ?p}2Q~DYe#3L@*zk*d%o%U&m!4pM9^zgyC#aKa2X+&SBx=C+GK){Se4 zW3f8X4NXCN*0-TQO77yFidh_kWlRcS3|x$gcTMX;f9PA0*9UY_e2-LOusfC)9xRf= zu{;6xYtVM}Kjw=kyWijnn{Yg{i#;8)bUteJ7aYR|;Bjo79c^t!XJaS?8AAaH;*1L0*7ar{Jo(-Mb zB8{Zlhx#F_S}TcNX07I+k<0a{YKozxdTk_q{}O>TLLp$yYYt_TVMQ(Rtde}7_}qK%prnc%F0&wM;Y4DFT0OpU5egkk4bp$E#T4(CSZ z^GJ&7ss=u(PbWi<9-WmW7`z%xGoPNNd0s)nz|URju%8w5M@u3wjE9U-0VeoVl*7Zw z2%!-$9m8H?yeyO0jk&7``k#>Z;J7X+PTuF2{R`H9Jk| zI75{p>Zv|;_83R4^i2@M*vf@R8DQFvGg2t5zX&_JSP|_PYN++t9HQ_l=dK7gpo!TP z*np<`_Sv}TC8Wrlso@&Il$O6m@$6ioXh&SJ|G*;g@b@^Zs%(chKB^Z>v#mL%wJb$c z0_Jo(cSWh*5H#7)3W7I9VOez=IdlOlQseHyw>_IH9%XLT*ix~JkCr_M+%9-I|D=6B#2mAtuq0vN*{%M?ew=ApyH3W9*azp*id zn7Ho+>*7_c=e>(R0z5tL#42bYgX9?4*)S>M474QN{2YT@7mpE^cq|elZtlT%w-f2f z)+({0tecH-MSfU!hq3eminRR%DTtw%C6{5IIwB!+UNkT{m$lf)yV3FJs)- z7*27)C(ZJt_nqxSEflTDxQ0VQmi-RVL=OftoEcyI?EZN%u{McgV&tx&M!+<`)=x3U zAqib`wjwo$4paStspPv`s=!;uIw>^ zV@}97tyNrewIk}L4n+$Nqi!R!q}wI~e9|d+zs6whUS+NbmKCAtlk{Ij z(6&m0sHP_`lj%rkPT=W;?kcuv`Hd4FGG=*cbb?K5=r)6 z*CpqQv&1%QLpf%OTzl#PW~^GB^2o9@6nNN*B&R0QFZx4N9iGM^*Y$F2H5+MUbFmsf zN><>YyBXY$%?|I&g3ZZ0A&k5ZSb=O~Kfr{{t>l7^F|o52#Zk>8IA$&UJz)>s8!+}g zekhAOgd^_YOe3%=-hg3~#5DpINm0BE##3!xM)ZOv zp+owe=)>zX$&RgtWY(Np;_hZ49J3Byoq!nvnETysD3=~siq>jclMX%hpf*2utF|l$ z#|m@?u@*%Z>&Du7W@e>uZH*P|43qTQkZ5lJ8{A?$WMrXD56m1)UUk@sV0UAJYz-gJWR9%R|KmFoQuF60iE~%>x%F` z-;U@te!<5(bwnPqdi12_Z%p($lOOI{w99BKjyWe|903zz*}=i>*axBAQfo5OK@;aq zDOPpv;e;H=K}?u0v?!#X;h2IpH*xg85{_X5Gu+nG|(c|{gX1K%-gQ-K?SdMX)&unG_#-aH_ zMeO8YW$Xc1P0QYR*OfCWt%46i>U!v{+4&PQSA^qNFqE};#ia;#%E6?FJB@45m53y% z_4KcbT~Axk?bTDH)A~ozp@}EZ?XXzPR#PK?2o?e6O!F9pOVc`W**R;n^U+}8*vJ#A zu9uWTTq}vYA{qlv^4Skhj=bQLlUOb;i>=;uy%k=h;Ur}a^TWsgUPHTUI!fcEcc?0T zvvj6?6J?kHd7tJ9n8$7z3JIi$gv-_>t@UA)e=^Z|L_CL1@CQLDC(K656lRW%S{vkyN|p4Puy&@~(3oU^GW$ zD0B}P(Tr+q(kji2j@rLV<*^T;8W^3&1~lcG2VkvEAQ{c71d-(eW}PWIGoA2ow_-F# z{{$WLBMo;xRwKH#jicQfR-nqhKH{vah5V)+k+o=ey}EMwq1guWVWhby?2PI?$>bs>dW}h z)InJN{5f2cElUwBT_JQy71|XzQ>a`Xrkpr$EIF_f^qj9vit~xj75ScL@jg2*ju|au z;s7H_D-}WJ+i3-?CMJ3}H7>s;IX&1dvST|}brIj{*a=5JI>lqFa{}(-@)R&Efn8x{ znW>oFOdDwp4G&_Ob%cs%^BvfHf}rg*;tcqxkB(%aehM;rQ6Y{z-HL2< zi{%(2xgt0Tn9E)76fGia>Ae@$WWoxG((wMo%HNGk5zG~_D99ey%(}#-2v!jkox6sQ zR`nk2C85hR5@6z@;?hp+G4!7=Qe2CFFoj7Hi4rD!>gI^VP= zhC8C^&qK>d%%0v{ieSx2ON!jE-{)I=tIj&_b4NVDmHo!!Ywkm-cE&EW>1YtSo7;x0 zS+f^C+S!3#u6cpa{9VQ|sq$961TZh^>y&%b2GC^}tx55}rNW1+5k$AuF1}S~u5T7w z&EC+=eBpKK8D;~Tu0Py@-$6T%%W)s{t=DW4apN5xx;+sIi#yQNonSmGbmW){x$r0l z%)HH#(sSk~@%JffqMb4q>5a=K(HhZW(b5{s1~loVXJS(d?=z4h7={gKY8sdf#teZ@ zj#~rb?LwkC-90M&7>-ya5P?)SMLKxbCRIk(>z!_pJPpgl5FI; zIghkCHG@kLeC{9|L$Hypen*e-!h@y9O-(+Ea|)ekv-3UCy|0!MySnVLL%muU(ers) z()m11j&YMuplSefWN_TD@Rl0I@3O2(3$G(+q}mCx`0b7VlOk50ha;hS9+1uo51amt zyq#zM&0h5V>8nDOcPV9;-Pj zFxd1$yXRbrU;~<(Fr=1(!ah{zm-uto2*u4+`-;O`{u7PE5&k*+B-*vL6)nAHh8U)g zT;Hh0Lp;^7F^YAEyQ0>`)-WpK4LVbkL0Y2DB9kJVPoBWJJ}S)OcbOD{CRF15UeEZ~ z^U3)X^nwul)JRPnI4w=YwORP#vMx9#vP!&R)|X>G0tU7m8h}~yWUON3=257u1Xgn; zgDx|QCF&tjXzB*&Z*G}}eKtv0b0y@hLRN%pK`Bpo479zr$Wt;zZDbM(1>3bxo9j4FIn@k^T_*fT|zBF3z~ z$Md9FRs?fJ_+`Jx>aQb7qRJN4Jc<+BO^YJ+J%8XwmbSLq0HzaHGPKj3P zF&xuLK2@I#m_LDkl;$fF(7=&4WWtY?!s_93R0TT{kV$C*a$i^+t#rbtRIA*>NziCSVWAh_Td4B#xzTbFiORAurfj`{~?QM7dy}5 zn3gie3oyge))bY36fwHWhP1VNf%jc5P(835iRzM6*k>Db)@_9LDtOs=Zat5WcbBCI z)&un*S&e*$anv)~YocROdNk_rReWWK2ASv6jovJ7i;!nHy0L~!5t{(B^VbfC@RWRE zwwf)O5!V(+|2eP97&rz^Z4D!Gz@z58wt!G}F)(#MZk!kHsI zX}6XJl0IB#+ZxmO3nv7I*|?Ttf&in+(pGHhc25z})0T8D*1#2A&Z{g+jgel5QmnP( z2TzaV9bJwuc{DP^Fbmf4te(>GiQT2u_EGfOH>oC)AniN*!UX0nzJ${5-``# ztX0(Z{#|^>&X&9>ZGrm6=BW;z`3=?86apx-0`rZi=%Vn^dKalv?7(&gB0 zG@u|;)n@p9!E|~dmm(?-r{h<(mAs5%MIn^Uw2 zb;HE69BYogk4L?bxO=s7`fQxAL=7J;t)w5pRjg&Bq|cJGX!j0#(eV9y=;cs$p%$0a65{EkZa0i>=P}JBvG&enn#rKNP~=iz1pZ zkZA8R!pnq?;>5^IA!$%5zWitw$DET_Lje;sc$LEZhcE3AY)d{B=Yfs4lWM(PcQI>* zEJf%T=;9$71zd`_99n^M!JOI2O@%hKcUHvFJ;E)Im8A6OVQjXoM#vvgrrg{6A?|Q+ z2gjt!4KSsEIh$ao_;e+h_J-ADbv`Mn8(T=Di&{}8MXs}d-5Yt0T@5MTnAJTOxuUp zlGn?cq|m!F@h5Lf8gBSMQUugD;i+eFoMk?5vPf;E#3ZEx8D$lUdsb(lKi(SO%i&ja z6o;-f#h06($LSA`VJ1a{H@kw>APu9|u^s(nk%P8{B#@Nu9m(eCOmyjzC|=K2CmBhR z9P=DrHh_5rn39td1NSB+=l;ugY=A<82C*g3L>wIJ@>rBZ7 z4dDGETm0n6U}|BLgq}r)k%-eK7ExXW(zUT13jRQEwRmQYPfT>o4 z4k}Ca^2DbKTQV{>6wyvch^tlv#}vIfh8^RLFE4K%If4_;om)=u` ziG?Q(UY$CCDV%f8{-2gg@oI=IQE&beXHUr?I^~ z{SDl`s&Ao1C(aHPrkJQx{h2xRS6?r|D@vcf|9FEsnrI0O6C?NBngGU0Z>fW3>m)(j z+?H%?r-^2?%Opdd)+j6;o?!`uirxt$LElk<1qsBNi!*e z#kw&mg1I6p##G_%ub%VI+O;m9#FQ)Fgc%#3C~tMVCHCDOi-WFcV0&9h+;zr)W2)q$ z&;~Hoqd@SuVTq17*^;2XI~>9$?k1|AtCTD&LPH0JI0J^w9c-1fi)TeJpLE5bvv}Y! zDqU~84fVLIt+-hdEZTI=M0x16EXsTb(6RT(?*pIeMj_G;$K%Q}^I0 zGmw-#s7$Pz9m_E{rN?rH)ZzCyfo@A(XQs zm@9%w5qt;`bPYv$_M*Q1T9S($BLp*pJ>vTx?Mcf)bBlL46^akMgE;28jF}FY$X`Dk zPQpRR4fuNI{tSkQf@>+&`8s+ z34MlSi(y@+l8BJWShwP+m^hCW5yBzHM9zY4JY>CZ1IJVo{jA%_*g7Tpq zfn`PHmlR?qMcglWhqPQ%d8-xsZDRb3u>=zL=M)3v-doYw(83Oqvq>0tm#88+Pl@3Jf4?J*E+O8$C^UHz`Ps3Y(0=m5v)J$N3)lxsY4RS zI6}8d`*9t}&?`ygLsxHfs-?I1@mw^SxVt%t*tJ${c_@fu-oOJ57$3mgt3RoH{^cN| zp|&LB!BhJD-f8IxU4*pyrEqgO+uX7&yprRZn9YG=lVR0I=i^N+OvxSRBr-2D7&SWY z6H9#~$duDM#JM;`Y(%jf^A`4LfY}0=yDQrjlcGK7z#dy-YQB}4T9~V9k^^{F#JWZ= zzEx*Z1XH6}wZ;k$CPl0+v>-3a!bqa2J1QUEoGyB>g(SQ-BB562#37zh9P>`zL+=F4 z@(j)5zcXQe<7Hc7-lbG94i8jyCw{1I^C7J9D~@9{V;gyBukA@kk zRxKmio2Hb0%pRnKxKUTP;^hD517>+t?WOC zGzwdY9ntQp4il@Ds^zA}XzJL@JS(DcjXa=9-QyOv{Ckm05r*x-e{*&Xq{D2MzA3H= z?N;=nanZe`t9^P&!h^olv;9NC*f9z%k+fx-k>@jd;FhD$sLqZn64+{(E20`+EbK|kcYV!g4Y7i~ z+TsX49vzN$7sg5B>Jt?kYSidI^;y#Q@B(yk%xR=;orKwHl4Z;Vz+^YBQH&nwDfS4n zBk#9rDm46$tNx6L;zLeZ2zNdl(OKRBTU_-^7z|j9nH0fhri89&jlFLmsWPy;)G=?1 z)KybkGFblwbqVs7nzHXwhIt7#AJ{-$2h78@;fj}Y9*cDec0}rP33b;@Rq1zrF1SRU z!?_1uLGofemm+4m!5%H97}wmqi6eu&ao-=Eu}08qx-IQEvXAT|JvA$(E5BYtn;&Z53d2r$sB~Wf{=r2kpqBW!kjtbd2iI18a~XigAVABRu`&W=O&+#g0>8 z$|bbH<%2U~@@;~RI-NsZ`k$sRbPnNB%frML=VM{S+j``cFsxWRuY_Zc$y@bjfO+>i zQsF&&3_V+DN7f{E7A!xmS2e$}9Ha-D9m zYq36EcmzhXE$DzBe$%9<>suq=R70GX)1R=L_EE;v0VeKusN!nh6?9d;9SLn5BzEz# zP(AS74pPK*T(KVlx4-w}4gO4u&}wxPGoSS2sdtcToS(4jZ+O41{sx zMho^}H`$)Jj$=m4m@k0QEL^5|d^3PrpRyxn8 zO(Tq*dQhF2>By`knqW5#GQcet8BDAc&4bm*SF;d~=_c1V27oEM@2Ir(ai*=d+mVv_ zzVtvBFLLg4e;(_`qzI>;OR-J2JO4E&vAw{&fQi^V!ItjqvI}ia3?P%2G$$R8r=$JD zI?*e`Yw?4>o*Yvp*Ef9uQ#dkJxf~hO-1T;3?-~uk?`jl@`IjO0K!FqyzA+sC9SxIu z{>LX>efTAwZsm{H*PBxd$p@)cO(Q+cpW%TzDX4NmOS9xol}Hhqjd)C@?3 z`Ejf)@H2^DI$yH;R;`98Fl-}5AT^PBB=2*x0N1RHX?YL+JTR5urzy*(%{=^H>FthlHM zjqORFevP2xa?cA4GgU4;W&>vaKyAge33r8!3+;&Mxc4Xuq==n0V+7AlpriFFfSrtl ztGu7{C#@js0dA^#iK`c!#fI}gh`M#X6psqpD}3$R(rY`t@w#U(k;&b5)E^lkhOv?> z0$0H7yuDbFY+!_4d=1dOu}=-5}&JHJ~j#4N5X_Sa7D25w4gVo z=tB=TtbqdTC$vozwcG6!<`rF)?pEcCGd%P;W}dw3TnQNCDo4fnE0d6?uN|@Oc|jQZ zEt*`OyAr9tx`karld;A~%Fm&l_H6s_Bh7Bw?e2+E)@Wy(`D3-vZu?Sk??yNLea?1i zU44<*+w>;CX_DN_u>mk!Upp%vwb+dO1K^$Z_mQ;jL>SRAYEV>LQtUS(7+;uG%+upe zKbnMtG75Q1Jlm?fmp!Amogd;YEsqQNyEceZB46X!8%gw_;dxPGuocJbmpfAe0Q1Gw zP|<2dEUF8!BiVOWQcv4?M00j?A>aEH?!9|41lSjG3_I=~@*${LkO8e zerxaZ`Mw{&Kh8h?@a&v@?mlbnwO+4P9f^z<4kYueUkZzp_K9shhY`QS@6h$5r^T1s z!Z_xfj0t3GGg?xlzKuhj{fCpUTN9~xxC1%#Z!-$?Jb^bMgiGKrXB}PT_rD{n>=>?! zV69fh;RkTs=yjxzzb1-?1FyR5&7>&s6xM4IC@ypF#@D7%erVxmrAf zher?4KKEziREQe$#~kGbO)ksjQpAlLkGOLZQ$<+c1B)=zU-+`u0kSI*j=P`j70;9g z5moaapsJi8{%Ey~V`}B3Fa|IOy|L<`Nh&&=IGos?Y)K7{43Z9=bVXGQz@W)V$hs8=2ZUl1$6;MwOG3#4Dx2r0B3Ax$3x2G@QJLW2)fm2~p=M zz% zX#n}@7D5hIu0^x2SBZsE_?7TN05 z!L1NeuR6d`=USY_bp#e}*Z8>r3)SmKoX6C^0lW1$fqM;Yid5M~bYCFMV)4)=Zx;5X z`?qVL$cJI55ioExQ~?;vge!`NPN@Q3V@s+=YauJ$%jzeRF3$*Dl0Rcd&5ImUatj{T z|KtkHVq#z3W@%sTdMSEFyl};*A9YIUDs6x(XtNcy7@`&!CQJShRI`VcF;v;uJXdM& zXG`24>fu|4lDebWBN$0hh~39D@Tv0b74Tf~3j5r-%GZWf3avolZKcymdfmLe&}u?k zdTGmMY44^*U;<<)1Wz=>40Bk{2y!OfA`!OJ}H zV5JE5yI}@RRoy7JY>jwx1piz35Cz}dDjk1UiyW33p%|wj(g?4Q$mZQ8)XX5AWBlZd z;3r^STLvhHw#gLrkK2;YE#{!HG*(^GVVjWp4l1_d2W))yIJowgV$(M;p9m6U?p(rA9bBs=ait#VPTC@hoYJTRolA{Ua*4HeTA6{)#`e0djDw83DV%kZ|Rg(Jg53 zNn5hDYX?C;bHDn%S3UGVfo1FL7uaD(0CvB33$rp2D@8Pbj(vF4OuRq!GkP)iG4)un z2)Am8qV)^YXt&f@v~Y+g9kG5dznd;{ji4o9o=w}Ye3ocKhp25yi!;-OH@gGW2j@|N zNl9|ST8g!d6n=q`ZbP7LWPSn8be3?=elu);W-sz|@S}=HKk?_t18C%m>2%Y{{%{0! z2JLs&C2VbCWlRUa6vhWB=kAzKE#n*Af zGe|x%v#~d=L!%?^3LX9xh;CyBk?GwAL0Fipj+wBT?h>dmXqcVowhWy`1-XDI#iq9%`_0P&Hig7t$B5 zC#Tk@;kzlngfGdds)7x#@R-8A9CKY>n?8Va;KQ%(Er+dAFqdHf^LWo4V6L ztA~*EUE~>oPwIJ`do~+pN0ejMYQ+){?6pvI?Y{vfPdPwZxc|8Hx zrn}GD60gnKv~Z*rFpF-AO9JI-gMKU+3Rz$#kD>h6E2q`mIEgDaaHcO;c?=9S6dRAxF4O0N+ah?yg4TD z%o!Z^`5e|!k7b~mg!Y1PCN*v!$9PHf&4jhZV+?0VdO5_$#mq?eEGBrW&qC}n;* zjI890zzs0{i(Kt=M&#t(Ukqz=& z$&aE1HF)q%7_?VMV%OcGW+=I=6O9~K3D*tEFq7mDfhS<%C#EZ`r)vnq7ub^WmL1UN z=y=lZScX!w=?fV03{A=qsN2=b#+tBQ!P@!|dHStu>O!{m5S|R?Z zG1co_O8;r!5*X&MoDui|#;^3LqPT0aaDJgJ>5{b%H7$rEJ(4U1HY_7=-)MTZPOWr|0GGSqGu{rxT$RrWh3>}#`(7TmW(4C5w$JwpJ~`M#y{ z_aSX$vCfug^@v9=?k14yM|uk`qn~0nD}sgUnvmB6o%4e8Ife{ zzt@8Ea*$xnh~pT?UKO~cb09uD;tpo2h(L{O+@bcO^zd;ps;`bwUadYSPT%z#MYTwk zmaQ%kUwasG%mKhaIG6yK>*0%)eb%@l+x@mgH0pq6T=ykWy|1aFH($r@-a%jomd7Q( zN&ZXtY$A4~%1+f=KDC$H+ML42H)jbrdAq1eK98MSnMh|3l!_fgPw}-`EC;t~fT0tO zlxMo^L!Z2DNoJWUZ|j2%B(=6FudvTBb;mBV(rp^=!bDoxH2ij)+EYJZwqtdEe-|TnA#B zRw&pNp2kUo$3yM&5>GrVujpWxb%{J9U<1;FgGb={^qC~N`&Z$|q(t$x^+MA3mlt;3 zc2FEPPLDsdwQ?y!4VXMLOU1Y3WOQmTywKAw(X?S8g}*)%|;3}k~Q()~U*EZ##_ZS95*56%@IHtr#H4o~pbQV%gcViw2zudq_c)@IM^+~fYK zC^5p8%uM?!y)tS>1FUy)xx&&jgRp^4Hg;|-$HmKQkWJiS%rH#7I;%rRlCcp+h_-V> zV+x{0#ou5uOs56Oy6+@jFWk*BM)E@|1x)q#7b?AG$>>|0Ey-DNnQAY5C7s1r@uwUj*oN9QU*Vf)!j>93^@jUU+ zd<|pWzFU*M4t}Kf`UNQLbyNCl=q7@$ni0qR+v3A#!5nj0exct0MqAY;Z`JiZsOJk? zvR?0_F!#zH^|yFWRIh}w)nIkZ3M(w?EL8ent;*E@#24PftVsTZc|_;sL}U`!hU#7& zPgH4LN#fj(VtzY+j`<4b0`R-32aI3eO4W?h3s7+zJF=i-CfeW=t3FjT6eZ|g-~~yR z5is$EZg%W{22HG^Yk+fCVqt4R4uB3S-L@TFklU4X?`=XNceJ4S7v)#rC~P)>`2(0G z*G8#Ux3)yvZS07#c@f&<0p-A6J&@fN*qQb2^NfIDYL~-VXMUa>Lqk%ycb_h~^spSS zGtxs_OuACViD&rx$JS)&b1e3;S(FhQo3imA;6;p+}N5;k8GXEn)JKYh~zIXr+-Vbg!&1ZYQOa)sI_FS#vf z$Z;@hf-{?2;~k`1Eme@j=VdA%1r7s1I>`v!jeV5JFL=g-%?If+e=v-3~Fe?Q$oj&4Cx ztm$3l@hdfATjey#s$C@-F#i_%o|}x>-K5JHbHGe|uuQ2tf1mjLgdOo187TG$PF6b= zdkU+j2kVcgJ zMse}3(#_!Alwr2Y-Q8Azd1>gaynFwHxFX$-G;SHASm_X^4mq`)58iY?U4wOd9N^RA zY6nzuVN3_dTQG6K6+6Cchg;GobpGIGxW{-+X`KIUx~=XCdJtPf%We$icjF7Y02~kx z2aI+PcjaEeoGvT0Bb$=8(@ojIYSWRw1!e_SLLOtkryKe7xcd70e87hDxP0uwG zAsuD8WYSP@D(_dmN%*iMkUI5Uih6x}D+D)r!ZEYu&U**ITqkbIQ_UyQPmk=#@w-*D zeDo^yl(II8LV5)^q};`EkH>H=Zk_KfT=@1Tm;8pVY=L{Mh52en&7t;XL5}tqg!diQ zqQ-+Og|iDiae|)%VGnJdjF|wKen;mk4XxJEWuWK4`}>C-Fz*4}1cA?%3TJ%4@R-FeQm8ii+DlbUk2t zA8kjse>sN^B(oPN>Dj|%!bfc~ zpv)U}ioPrkX|6?*Vh?dlFFB1`1sL@c1G_~*(0Y8=j*R*JoPO50hb{Ye1f4WET*7fT zap=bFbeUx<>*dINbOn!`4`U2k>C(x65>S*7LE64*MS6CLLq|Oyh$yxx5f>idm;^cT z*aVpGw+E_*^<6^sBs((yyBFPOYfFM-CQwg1P!k8GV($V6K0S^pi&;4MJ+T;vC-%lx zSNqY8TE~%5=U_5tmM)o)cmgf5{Vg7E@&hZ4d^v`7roaom6ELI8VQk1nLa&~-BX>4U zrgIldT0>E zxueK%t3HjM54|3DmvT(0oZsvP%)CVxRV!WF)84UmM7#fcVcxbwL`xAP`pkXF@5W(H z2zTdUnCR``-oN}cp480`YZnZsDSg+W9uFPK&j5(&wnw6k*R^QDqH8#3lY(PT$e1v| zG>coUIvagWYz(m@Lw5S1rX5d`G}v_P=0kM3I}MvnPR7Q1?|B-=Hd(K(>{pvtE?Mo{(@VvRiu2!DIQJX*Q z>G_+@rSsX1lwsb;F?2FurkD>r;QPBwPK|RcB;+{n#_iz zbB%{H{lX&~t;8O*dF(~O#_}>llR{BdEZN}QN@TMlm_ZY3=W#H5jderLbJaI1MX?OObror1IocN=LFU?ggKvqa7M5o6eonKA7vjuS2XX!@C`LkO3Y#7`tNB%I(OAh%fIfBhmX?m$gN@!D6>{Bt zMTfRwU|a1hnarye1D4hEwb1|-9z-_ffH``lyYjxrZe$c^M?PhYp^24yNL;@!{ChK_ z){AEZ?C`#N>qsc&v3d@)#6x^wcG!p7v~9$Ff87)Az6%sRw>BpSHEYD%c8|r$ko~c> z86-=7s{oUHQcoGyFC2xZ*pb33{`B*inM9dBUa7nL9NrW)>%WYkT~Ir`s_QA<&chOq zGyj_6kM1Lg#cvHXyZ>?V{@n58)2g9(k^fLH*=lz487sJIf>oPlr?XW&#Yrm)+^^lugw}6SXEmM$lfgRE6=1cF5OF{em0-z~i)n zqH_Exw1U?N7=~FLyIZy-h5m<$Z@c;Ey6bT<-!z1nJkunp^IgRa4jvryOMV43q9C%V zjaJS4mW)or*R%7dYC7H~Lh3wp3yRi=z(eXsVy22<22JWBExhGKBu_lpIdqD;H|gdQ zL5}qdKn7Ej#VLA0Wbxci2|3zIuL4e`JPXh{MhA*s~CNJ0V;1neiNlsju<;hM6+7-ndX| zy>XWGXJe}15#64;?bVl7{?eCRQZ4A^!77ePkw0sr0n?)CROR)ek9Ktr736k16TJ3X zwz_HPOTkQi1&2Lp;JW~`Y-Ke9rtx4UJl32viyT2)`yZ7idw*A^);5Zx+PX-IE%T7i z`qRj{!qjZ~v!&#EgYs)dU4U@&+28}ybV*1tmo_f&koFHUhxx1j(7wr=q@TUsQ-(Pp$7#-hIh}Dx zS=P2p9N3^B*KE$C!C6Pt9+|g==$o)6Ki|TP;=@?e}vo+oEryC0DZ;XXn z3&QTkOU8Hr=1bvz<*2X~RBfgtUwT-JPmU?o=IcU5XIq#a=XwL58qybA@5{voYoO{8 zU&QCFEkbwEuGn3|&bQ8@%chCMH*yQ^WcWtm@3d3M(a*!{k~VS7aT((Sm>#RvE6tmF z(-?CliEp`^u1dTkUA`L*maX@3f)&LBr?dAuR_}ah=OY z!Qrqkd2`}69(%zExlYs;U0Z*{GrdAM=DM5_1Oevi5F=$|Q$MPNhc?Egt8_0=5_b)^ z;yP)ULl-bOqF^?}p^rKAK^?2$^Q4FCo=3gBgT!Hx!RX}H!(;V*R(~ zr2Vu=j`5Y>vQoNqbX~k|QZ`F1#yo+)Pp zjxn$Brp_MtZ_H3S;-VKCl;cdAEw98KCLKp-Ha4Ndj}+iZKgV*+H5o$zGojOdm6t`e zIIdbj>UvK^{&y0HU*HTeGyEm5-}ofNf+--BAL?XGzWZl9>2^5&R6UYLWFge}s|V3r zn1a(L_@i5ko6{*ZpXihZ4QU88l?{@2=o^6PKIwAq#vf}%pGOMf`!yOV<1$EE>AXC4 zH%t}5YSLOW>$x18B_0dT{=fxyKy>~A`VFIW(U0i^BzFC4n1H-YjOf#`U8JW^J9Eql zIU^_m%%bUmc7KfZRc~O2?mu-Kst294vOHbI)`qDfN*qO8==_<#X$#tbY16Ckm|2A9 zeKDtNMYS+`x-pIVr7OAqroy3?z3I;3R?^Fol_I;F^>Ri~2^gdK#}vK1CJL4n3Nl4; zB5zM@ELk+Ay+U{B3mEAJEeY)?G+Msp!%tYNRYK)QeyaZT*Eg~F{vKiQJBPfgq0#j4 z(mukyW)`%0-)wqjQFFvF`{j(_6=2@g|4?{KcZ7p46=Y-GUsV4if#`S~nEm}RR^6c}y8;eCYW6LCSp3S~m)T zy<;(Y?z;lFiSQEczRwo*GO~n_$9E-RRgG9tC}U>HTHFS}-1P3D%o{fWZPZYb^b=2% zec}(00u2x3;CmN(pALiiP6Weq(BF3O#-96c;6}|#-Z(bw+YxC(%w$}tl_qqyiWCo) zyJG9hdnMJ)5;3K(DZiU?IU{Ixq^ZXE8`jGDom)|9OC|Yv>WY-yH-L1uw-&0Ff@N!s z59p&*yq%}z+Nrpt@sjM|4;jJB-=ApU$4Y$cPN|^i9Vz;pe1qE=o}>@&e-%5tPZZeN zoRMQ_eZZ8iXsXmWcL0G(%xsx@ScrnJQiR* zP~M$F(8M_diA}RlLW>*F#RYPQ)0WRs-rrMVMAZw9SuA5Z0>-Js9)-JAEE?QFNlvUu zrv@=?$rocEg)%Y z!o0((%+;q*3{sNkr5cpH?SY&)HqKI#kkMMA z+Sf?kI(s3q6X9<3TzH?2S@9#BH?uFUx^axJ4KrxkWok{jxP*}Ctfi>vxfcCB*M}Ge znv(ZBPKj&YKtmtA0$b%%bpn_&53Rf>E(a0ug0E*IgbZ0O>NU#(kX^rcm>Rnuiji_D zBE0*O|ID*ks4fHzB#TCGB6HNUP-&zAUD0F-nYgG239o%7PN@jum|*!--4QU~KfG4W z*4u_Yo>db4dyeSwyim3G`yf$wi|sSwj`*u6ZtjSh#sm} za7-;!abay10Os;1dpi=Sk8mr2tf54MLbxttdwAnXb z=>OfAhTSxguFf-&mc6i|H(IxrF7FF!u-#z=wGd!QufRJDCwq`u(efx z%rF`9XKe>ydUxBS>^-rq=;J1k!1ML!z4tkFx2MDTJZZDHKXGo)Jie#Z&U?eVhFoTq z;R+a)STs=^SM1s=9nw!Hp<|bGjigw2QZ~Q0+fdxE{M~7 z1Y*0bAFAkoT#dR_3b_j}f(I1%sh7sea)l~5g(}L$F<~%30EXD=I9cH4RVGrC#17QL zdXn_|sfN_^iv~V6VWhNgt}TCP)8%k56fk{eA5<3nXhBzo3&gzhAVGKeK6UfP{;1^2 zMeP3J1=fuR2bgBy$lLl6Ha3xP-4$pVSu_g=_-NqXS~aw?*<@U^{}{a$qNdr!ap;c6 zF53Hx7r&d~a&Q|Bm?sZ?m2djl& z!LMtW!k_?;5Ob`*A_`e*gwojE?_rDeL6?aKwXW)qI+Z3O*M7|iTN`uO(;ys70?fZB z+m%gL&!da;1yU|3sOjrj>J{C*#lo}Kd2^DbHo^&YDqMRAMuoJ!17qJoOt$_DatnAN z_>+853hPgPMOcH?o`w3#?T`K^fuJ$_9fbFLNBFAKEQ z?S|dVt3Q7aPYY4wy=_demL5obK8twLCuog_t|9M>68e4MiK64*5kkV>wd4it3T9{O zg)Ztl3KxqqNQZqnMk!-*08?YsMme*)FMU}kkfh1^Qi8UjFLq}!_Wbd5aG<)`VQd!)Svg7VRs}x-9I|b)9 z-p11=$u$DwOAm0`5F0#3BDDTiB%<5)k^T#HNP%w}@;vcQe6sZ&E;aDv7=PFW;BKA+ zrf<|wmB0I7`sSoSS~$%W-P`+UE?!H9szp3a!Ct zPvKGWJg|qDI}>I|Lk|?wNiT1x#{Y-$*$bWbw*#?Fb4)dn6Po!0+UHEJ;U=z8Xlwir z@zl0lY}ww5V}{6U^A#|Gv4U#Xi+Hi@pg^w7%Rv$DX+-t0B#&X(*lN4QXQB7D4kvU; z<#)s8NoT4O@R{{f=(HMhl(s`Dv8yO~Jz5spo@U2&ma^kIN`D{6qV{sA-Ut|-TjT6v z4QSr%P=PFs%SAd1FOZg5Y08ApFZs9-)||u=k3L(#l<5p;r#t@Ot-Y!7L+Gi%<_PI^ zlGv4Tp(6^)wV(yUOIqMtLK)_$9IER?!xyBK8iG@pKz8PJ!&%xVNb`(=0vp2Z zc|RQ|5H+U5Kk!lnD-$g^3hMyz!CjpW)F}F-aPVw_XdH2yrZi0vdfYdrEf>_&R@tQj z!~E~?-T*MQMmow)-A)QEq6PA|zcbE#3(ZMSq6LFwP~&nq7FS8A|(SO!-`xYXBT zCibh%s}YSqw-N4Yqz&uN7$P*9t^EBQ{@t(HN@wAOm_^D?Z)*M^SF+XExpwkPivCYZ0LUZR9 z^jp~xJms+lUUsS{{qY=P3&7~h!L0>g#sqFs=6tb3`&9xtGkGGdI~ztyd=4PH;!^N` ziUutq<)?$5MSgga!)-47XNgDc)N@kX=x#VMWSOw}Sc<4G*kX&!7-??v4`Rm!oj68E zKD-|YnB0m3$_0CtqbF4YIe)tYeg6pNNgwDg7<9P?ejEY+H7BX_W@Fac%Lmp%zd((K zrPTFc0sbX^7ZyfM6bG&;!PTWrq*fWvVUmo**Tzdeytf0)%XAlIl+#|+zE&W(F&$+; zT0!cSeNciO%#$9s;=kr3ouQUE;&3|G;<~`3k{iBiVMH5q5?J;|7+ahz-mL3G#&-8Y z<=a$Zvzpr+b3w+81dNU55Tz?Rg4TW($QREd>XF!&=&CmJdD366jlc#!<>n;joWz=w zSPacDMc^B4F@FJ>LNrm5zgl##*+_!EMB`r*Q^dG_y8NLb`Jqh$%%``F3aj^t=tXNp z{>2B=x;eS{vULzLEMHqUYa%!?ZlxgYCe zk;z0vVxFC*7r$t!XXXYY-EUF&s-+VT)mbT`I;<0Bg%#EV#Z(b_6UhWoT?yMqle||8> z?1w!KV(2Y^$**0fN;339hm#TUTYO&V7#OG?o^uqrB&33nES}#D6Ui3#+k?NmLenMq zb+U#_Bhj4rx1B^zc62~5ezd3WZ;c}G{;|B1^30i!>5up;zPJM_IJCMAV+IC@8x8U@cpsgEV>G66zB zyKKDtPX%{?vCEJ%0=B39nAivzKsH`ttc6bR>kf00%khJ^ZAptkCiII|S5&t>2Gz-- zdN^Q=X)|T$rcB}IFickKx5tgw)#|~Y#-ZAgH?Z~7PrOFJ(x`^Sa_->I5)Zc794T;< zjufny)^#rt^d=k75a%wE!N)Grv-jO-v^~s_1Wb21hK>PD`>46frKyjUiE}WSyhH~- znRr?4w#$?|C$SoVX80xk3b5%4%jq>Sdc2kmpM1fZlh`Roi3T(uLvxb; zTgtnJGHaso;<=*2QKnd0J6P^~8fLBc_!GV=ka*Y7w3aRP-cxg>9Y<{r2RAe=W zMwK{8Q`9Xb^W(oz@$0G5gfV6!yPNiMjUW#&!i7`HkSZ-YFdUNs8SlkT=|O7aGF_C} z|01rP1|RAhL0Grw4v5UbzThIo(LHWq=A1P8aBKXhLpgn91}D4Px9GyZH|f^eboAzW z8r^qzIlr4ra@1J>7*D4d<(1^Y6wLQX^MG_}@j5`Qch4AEj|3aAH|2Qg>-D&#{u=ga zyvJR89cnJ)Y99+6WgG{NBr#x`^$hP+bwLBaZ>C-*PH4uE*(m>W1IIj<@1__qKHI~T zcRS6ckFR5Lebr)mZ17_Bs5#U5JZa|-xACXkk=WoR46WUJ6CUC%yu~dSj}85f++mLB z*9)zw#^WBuB}@n3+f7At?FYgQqYyl=$7I4D+7B610hm9o8dn4}gwqOmL6 zsr-u;DdyVoFG&4&gRZZM{O@ELkx|DH$7JngRAj)YTLs? z6%`&bv`DK ztiRD8byfJUqZRj3H3$GN)jgJAl%d8pr_y);)tG$~d*?L6?e=QZ#kDag#yf%x4{k+v zqO)j6L%g_5rvd*<4&s<>IOTx5(L4%Wsw0b3_ZKgrUqAqHYjGm&-^HGo+AgGgG%_6C zuUIr5PgCCFT|>+SXw}{_oHWAWoF)6kE^So=kM78Qw0;#%MnN6e^a%?yrdDIauA1B{>-u0&P+(3B`l^b9ZNx$Hbf zf_4i+{bHC7lNrx79?Ut(bo+joEnSRbq-We^BL+9!cn6w;)MaHvBJ$(dRzj|uxropwRtDUY0CkVWVchP zZtjcPLOJtAR#$OC&TcaBH$slJIe1ga7MLIl0?U;TaZs)eR6s6p=OiXzj=il*P0jSl zs&OZU$@>yT1i`N7xqZqZSMQ7Z>Qs(7CLedZ0cO3`24(KIa8z3Yn@wd1J#=RRiJz^5 z+^543hh{z zBxFHdffQibTuk&=a~;8unt{AIiSLh%hs#E$MaKl zHY?)7dw6Kf2P(CkC+q?Cy-3!u!^Ct>Ao{Mz6RY-ykaY)4N%iw!arM!?9Fr)=&{2T- zqI6eHUL1)$rxEg$?x&-h3{}@WJc}CakKs*CJh@Jq9T2m5(wb`%c;gr=MSKpjBDuTw zkeUx$(64MQs=st6q4Ukjz4f`Gjr{?R=_$AKBml;7L8Pi^v_C4@2X`}guW+N#SKYK% z23l2p5(lL6F-x9zUxkO-hC9C zP50#(3BEV*yGa9#t(TLk-MD$E%MC)>+vFgFH^r0}K4@cXvF&#gr56J)n+Nb?>>9v-w95WAgXuxCxMjeuAyS%dn zviwWPwKs3jzYCe_V(2eR^;F?$cK1NFDwiTwP07M#bs|5!XW82HJ=$ct(+eChvn4v^ zZ%&WI|HKxw9oc@!h{n(F&M{6hMhzIPBbO9&!^?!GR`$f}r!hY0N7bu7Ek=EI!#wFj zwb)Z3cMavV%`sX zCb>v^E;~sb?`;!$*Ba1+y<17uaD8{zr|o8(|T0hZ#jjDYQF%+e^~Mm%n`J%OG&MoH_Ie^6Hc_$HcNUL>Wb zh$zde47CYK$LwwrWXw~*+!>Ru9DglTT)N+$#H@!ITDB>mlTH#0x~j0*udle!?li79 zD#don8g6OiGV1|%QSA1!6E<>nke` z8^Am-%vGu%eHZ&i+7nI38RGNV;p$24vW1Fo7r}4vHFkLxhNGQ|F>_AJb`o)8&27Bn zvkUIr-V_hJ`kwB${Dp>yno`cY2ej|4+o;{3T6zQb=XaAUhlBNi>6v{&Ib=p}I`e`( zdEDd(ZIO0B{k@ff&yzM@TZ!BGdGeMK>#h&@5C=!2d|W)<8b948p-Qt1y14}m7hX74 z(04mR&E2=4t=5kPqv?=1!reH?!R;TwL>xV>oIs~j)opw7@z*&z;NEKW*kCOo)$$4` z(Tef&Ws`A9vYOA6PMv-eJD$3PH5O^&cYmg!0id<%9^R7_%(B9T`?}FLevQJ$r+aW% zo6&?};^d4#>sV8b0})Zmu9cf;_d5ix*smIeau_3V(*FMhWLmZL`m^Rww^3%ag2t!zNQo*#z;=jFp z(R$ASatTh`y#l%;jeg6;TbqC2HMfH~W~2Pji~-}i^r>QP!yc+GvnS8}$4L?PR z)g(J|!Z=1HzXIlf33Y9k+b?xDZFk?EbX+-1dLDWU=X@VUS=%)`hYtN@hE3a3oQa`t z9R@wKIUYLAexhL)|B1?(Y3M;}6satPdEc&aXw@CHXtDhtZv7#IV-Wmq;DxpVjE3DA z)rh8R>9VW#WYV)t`n`4->7d@krz8_h7ef?e@FoRixVd#Mz(-`xl_ z>em6{^jV**9he4QLl4EgUUk^{?rx58mJ^TRfLXS!O`iA8@pR}pdy-ikL??T0B6&I8 zDeJRg%}Fzst;6dwO0iFX+?-_h_X+;FdItXd6w!6}Ly+qgZ_@u^bJBX$aU|BXp^i}E z3l$e}%m_JDcL2=z_hxym6T4B*BzqD)ECgNt8A8%KjN^$1lVeZYAA)y2g9BoycyJv7 zh-9n!`e5x%gK3M(m8dv;3Mt5YhTYwdp^3N&_1!JvmtbARUg%45elr0u-Y0*nt{-_K zE|0J$CwCo0%iEkF3ucVu80#)jBRHQ7%}KR9jba%6d!KR1^k`f%$dR`4vP6r{ca_*B zz79k^-sw`yXkE!N+E8lqDJOqwNSM{Tp4Un%648svobSDb^0tNOQYCG zakDjU=S61oj7 z-*}w(owm+nI%$>>FrBn%&?_8r5!~Y8O=I(<8#bSZ=CGzTBn=DCw7;p&-(5mC2Y*$X z-8QFR%}&swD;P1%TN$$nFvaOc%2rUnn-^DY^;dbn|tByDb<2i&@aDOmPf^ zc}$VddIzT!zrt(;(!;D*;$z$5+*_tMlqY9s(+_kFeloQRMQq3PT=TIU;~<}>?F5X; zSJ-SyjM13$_N3|awkWtm99c8+QC@z>N-)Pr%Cx}2Mpr`9~JhIKIk4P{Z&oD-4mRIZ>K#(^SdkYQiZ>i z-|CzA{l#OxHbY>ChR7xiFyV@=O0DqCXv$-I^3+=;?O72(a=srGY9l~GQtpdWee&?C zI}fo^OLk6Lr41nm9NrK8SWTzrKEbx1E(-BaBgOMy-{L2FM``a)kHue*6tcD1BOiAk z15EZYXQkuN5H$azJ(-s{NGvvXCf}@5g_8T{@sNnc*x6jgF>8#w;+T`EyaA@e`%Aco zDgw=M8Avw&s1}6mI5GFpFp__)7QKCNL|i;PgJb?T9XlB?4h_c2P7WZY`ejdUw9cX@ zB3l!eUkNBW?F3HJ!mvJ|)JdyIm)?5Fp^Hka?6jRk zfs>DmYluh`J^9+`$<0aWfHCmAs)*^3jM|$xkdU$?wB3pEIH)tsEPfe{Sw;|j?;`Jh za2sBZ%*rDEYfkF0^9x?qBAASNJptWtj~A=A2b0Y9jkwLjd1An~#T>I=mMi1}#(QP7 zZRhY4Xz@@7GVfsvDSwBfRCF+bmm)@P5%_U8dj;M+{KZuftgym*2ft10Mtm1UkR2(z zk?MA$=-N93h6lAL*vDUd6yVP>W8_!hDqt#G1*x9AJ%&Q2I*_cg5IUgFL_MtHI0_7c z=A_^yTv^P7F+=`Zf_KU>o)NHJU`p)(64W=C1WewEngl-(^(uVHtvg+b`@lqTdbGOz3OdmSkLz5pjLghN_P$IA({8c@LO> z4=inCIyOVqT}P1koNsvP&uZr49t&)<|I~%V3@F`1$?+8!?03Bdcz;QvsVHh zW>zO$Ze>AZ*XQ85dU|BzAYn^##|*Pv-l25?v#H)!>032cycRNo zBtJ{e`*HiMx*@q0j7Apmw2WW88Z~WY8IEauh4aCSlbv-MmmI<^@-*@G*_)-G4h!&@ zcPEk8tAWyE(_g6e2OMmDH;@=cl*7SxfZ1{~Sb3;_vDhSW1hG!sj>_N0sq3Q%${hf| zei*`Caxe;xxbNeTJ>4I5hxahfS$t~WWL%wODr9?Ba*UMjbM_0b-L)`>xU=OV;Y@Kj7)_~E7o~ta5aiwnXQ%hR9lqx@t zRy%y&D+Z2`os){k4dfHba&Hyj?9F#@t!XxPYkZ2Ls(uQ-gP|p%*(l=seFd(1tRrr( zJ}dOMPsVx*7mi7W?+sv-fElpEMA^ETH{I}g1et52M{#HB74f_MlpZrMZeo~jfZB8?4|nDOpVp=U!f$o$D-Ad7^Jfyny4fLa?2emgI^=X zx#qud(8dss*&+AYI0NQ&>o=-a_3qTQegr8oxIy78mmG&MoXJXADPpX8FgMR)-QCPu zzyADf9CWQC{x+d26{2HNtCitIy}vCPR(%@fYF!kc&-jeb&GF}$-muxg+AIZ(!xrmr|PTja%fh8VSC(Of{dBxZ>F9ow+btd+k=Q9dF^HR`jtwNFe zx&YF`QV&LoCZYZ|KSa&F71(0dDvntpC+zD0GqH%|-Ae06^-D$&zX9>WpRRk!`Sy-n zu2A(i1sl)shp}!?xLkpiB2r(};H$qk;T@s<={$=-WYlvBiT?8$H|ur`4SW4ZOo}hS z&mWEEnEwfwJpiL_?4H;CS%dhdU<8SEb4O46#Sqt24US<(nwpNsF&pc~R1pl*c=iL% zEe-=|se(>@JRT{q75Tao#sbG4MlXN-5{2F;aiVu8vdcdTCCQ<>4`AZ5N>nqh9T0E8 zF0e5EHcI($mXJPfT(01={S0?ebpG~{XKM^ocj+5mC#2xb6Q%Z%q|z95YKf$J=?B zT!BgD8K&XgH}2GDY+*&ey?!AyZ~KypVoV%i^jL#I-!P+>ucfq+v3FPyuSRuCz zv^F4DaBc@PZ$PeKwLG0S^+o)7&4<+0Kl>qG4pl45ga&19yeYMK+8^I`4MD*Mjx@$) z1Y#H!>;iyE1x&LAeU+cITA@vk;h|Yq;R)MfNt&&`l1-0eKDR9KU~&a^2wB*n44ZX? z^a_scLPNY!>y89RINnu;DRM;hfus0+dNb_NS(_$Zwda_6IUKwIm;w)^Jn{gcls6-Y z_MbyEPCJwgSa29=mX+d)_0haWzGpg3o<_Q(#$dfKONrO6YQF*k!m!<;1?^GKCOJ*SvP|5we9cMY*{u-gp-OrAvHSKjN{7`$kX~ z6~iT4nR1d_iW%M_g<>c59q85hdm?1)!$D7aVC9yJ;_z0%9Al+QahoaTRK1w*k{*VR zC5^$teK+Ca<4H2IOs4gllTdonpVtW3^y<;5Nz~>o@qZaX$bW-ySf|~%q~}7EwONZe zEm@B*rkUU$Z;Qk>#(^ATpvnkZ#nK+Ak=gkpc5g>&4P&sU(=YVVCs>{{@X@{;*wsPRnscg;h5cwM|!Bgt0T7T+zf5| zX3G|p%TR)?1m^Bkgn>@1Fbva#WaA3#^^7`|1&;k&;Jk|jl9a!MV~!@IA&hEA@9jVz zqaH*fxHB>rR^gbd?s;Ytzjh`P0m>~pJ7Ouh9qB7A`RXc+ z{L_{+9KBE4zPe9h&a4uMTYq4fO8TVH9omLs7Gy;#DqOWi`+P^de}yjUF(_RQed|D* zljsLv{7-)Tz)BG;BVZj}Ow!29{TO_(EJmGO_DE-qPNKI*s1A(hXsJ-qfcA=4(TkOt z9FtEoX^O!V<8Bk>8VgmP8caySqeG$8^m@3^3ZzZWOZbIF9x=Cx?1Nlt@Rn+N9F|%Uh72&$t zWLcvlKKIpDF=g!m+4jXqR7%aa^QbBxGpzlz;ud(dspI1cYNjO+`g028&e4X=h4)DH z;OVgML<&(@O5~X`1!YfwrgI6c4wqQ=G|&HtiEEUn9q)bK`WhAT-rOh>mT z9Ydd2YGU@^#H%p#DW;wO0mb`Y^GJ!I6F$})LL#H)$kWd&M5`?7_1)_hJgQT`b0a!K zFkRK06mD>tYpEKIZH-oGd=+TQ}C66wspr2yI@r-KIp(Ya0~xEfx!X zeyzc4AErTiT7vM%JS4x_y9S2-q4I5XHSJV$(q0tvv%QI8xxANT_Hx28@195&XL?C1 z-)nGNH`bgK8l??POO@HWnYXFs?l0MF`ZS9zz&MZsD&s-HlC-Hzd;)DC#8ejw5sq7>i0ZGk&^g>lS9RbeH7V&)7T zn}6@vR-$d}gk5jEA=bWsAtJ?qup?D=-2MN@6{Z`ca^=Wuf9SZ z)#b3KBXK4N{tC$@{Umn%R_}$DdK;0_^dIzUA`CN86{;6d%q_P#`|?RQ6gS^F;@vtH z(8VLr_C8 zTbH;h%>7!TWgVUH$D%BB&oKcH+E*sn0nG?{T!!Y`bha?#A(oh2`D<6n|mzZ!&B;C^}<`KoD)dncS*IJ{mJ)N-g zL@Od5jK;&L3#i9Ym6qzK*ehJmX4m-rP}jDMX9NsWJThM@dRdEFG>%jbGjS02XSam> zo)@H@0kL9`F?}@XYAjVP@l6!-Z~YNP`)>cC%<)dR8C=oX8eeQTXRTn=UZthVl6oCyg+F_TEd&Lfu{WvB-l@WBOm<6{zN1CP6i8;v$2UY$cilj>Ew{H-4 zkF)MI`F|OK?)i40^D&yw5d@`Y!n;oWaJQ2Yc*#b8f7224x!wtnD4a|NKCzJ(eThNM|Kg!grn~cnOxodH2RS|%rYo3l zVI8mFA87+cpcf)BWXEp7F?h#97c=6a7CEhe2(&LsFYmUL#;4r*&!rFz&hl*Ug!NCbrWd zd#a}4^HYuS=E$dF)-r#NVFgKwv7;D8VAp)hesgIA>5P;6rXyRc6S98PI#j2T%|{oR z04>uRs%wshPx{m*na0p|ndwkE)(|((HN&Yy!L3OWa+-wbdOSsxu6ep{|;|SE^d)Bb}Ge3Snyf$O_-Qg4A)$HMGk14%&1j3D|13slGR>C`R%9jN(O2h}itn8T%%x zDM#NtE4xjI7NTA9!9n*Uc#J#;?~bH{EU9KqGDo|*=Sk5t~bnB!6R1n1sHcL}1^qx#= zy1C#vuP=#*AFPzqO+V$=nG}Nd_;MZ&M%&AT5vf zS|$uxnSo~4P8E;GV{|)w4?fgb3ta;`p>A1|#qdMFp^aBC$Bb0{H)kkj&%-u~z0Lu| zqO%K5UOGxr%(*WZYdaJ7zI9M~Boo%{)&bT7#WW!`TT-29-5l8BB%{KG^ewy)g>v#E z@JQ#@*x>9=bZT0>IJ`j7|SjqKl*qpT5!vZ*3_X7>J`X=UWI*D8s9L70abn);LC+M8?5iw!A z2LAgbgkwtR>q#+6in)5HPkz9>RYd2zGj>RfBg+$P@RnkKUW#B2%;_PcsdQcuw?<}h zT697=Z%*ob){?v_K8C*EIEV+L4!E%3Bx*hSikN)v2MiZ|IVPQMHWX7tF)JFc=QsPg zlKOgQ95rAsSrf7W7yDS##G{e-a*S!Y1`Kvr^2CEpMMRZ9fb;XFLd?9;Nj;1BR{;5|8v@XQ7hjWAB_w{el>~s(UnY&VHp8yPTJJ{CC><0e#1n7nl4Afo`Wei(Uu;6 zQR5h<(M3N5?|7H5MjLTelpFso)nDUBvhX4O0?Z{q#G446>K#QbnB#;9~2X{uhKqk)m)*9 zVoL6&3Wp&U_dTF4`mLl+ac0?|H@tv1CpFJeX{jdld;`r(vO$Y#O1F5Agt~pV#bFyp zkxjm$V$gq@WJB~(vhcPQVwh{Hj6f}3y~VUy!xT#vRtrNfI^*4GU(tX0r?C4#Yi{(+ zJXT7bWiF?y{a-R9AUf-L|0yp;?7RL?)Y$OZeoRd-QOELzctha}*WJ~?=%Xch<~5yT z=F`oFuBIKusK@yz)~)V|D(KhKbL!KB6+K7kV@Mn)D~{mzaMGaZI@?xHX`d&zn~(LN`x9->RJP z-OU@&uNeohPIo}z9yg&mAc`A3v#+O{@n#+iFn0y^ksfLjBBe}O3d`pV62!GB$_F~T z;7q_~X;bb;(MMZ{V{B9yV~QDk(n}FW8^(GyIOBDrjitzLfw*>YgWz5#f{DW(er(5D z;=6ww%a2r<_bO}W$#_VJOZF?6GWd)zX{?4AtNj%`rIn=4=Zk1|K1tyJjVkdlrYIo=;T09LBI%n z-}8phzuj`tzzyL87h1#oHYK7)=_`&Iu1Y+tDaNWzC&iHkbOiK^GY&g>o@}JHlY6tm zkx{^Ds7gn)JB6BT(9ZiG!Eca`aV%9KyUP=gGY=1e@9VXA!>P8YyPucXDP}irH6<5z z&PW&Ad#Ro@Lsi8CQOqXqEc>EcN$7M37wqemM5bp9hWgbJXxpn}+{D4;+(mw*I^`fFDY7 znkOFW7lN&{4Dg8)8DdG>K#n=9sz$j}%+<38@>lJPL9WOJ8(9RBw2IzxRZs{D8h;%6 z>eDh&pL7VB@_;KRne0_{bg|ySChx&`fqgJOd&3j8yObkN&)b8ibvMS>Qm%^nzau$D zROL5wDMsw4%y~2`GEUzZtM0bDFj@vU4U-^4}mEsx#uVInl$Ty zYQKIkE*R&9`%j;Oj3@pQORg`%6&by;ljd7--n@exlS;pyG$U9_F)1(7^Uq&igHD`q z!B2IJP*7Zi{4gYv+PcvxuOd1tO;^M0-tE>L;##WAMwDS*8Jgg)3XIQso1%`p+mkI5 z?Qr7Ho_J1cT{4)a%fLfe?4n}GsHo}#~O2tuj;04 zqZqXPrCrb%HMID*3;wP94K}sTk<)&-B9Gq%V19^h{D!oj^BL7sr$T?99O!TK^<)Fg z>ytl$$EIkwH{r7|X?Z)My`q&gmtOVKFp}ld2SsRvp+Txsj=dC96Z_0wV{4Eg{Bn_v zLUf_#T!9?Y-5%MUDuGW!s6h}-qu6SgtsBb-Tu;;OlNKZwJXt0!c;X@XPlyn<9O*%5 z|Blo&r?X_MWlMdqL608SMec(KC&L2L3L&Re?F<}{kw)(;iFJ^&2UME5kh zLm#D>2TlhSD-XMf&#$`3ooEM9#n20K|M~6Fwgf7sJ@Y%vwxN}Enys1CQgIWS5%ix& zd)RHGpt#}%YO!*%wCyYHPFFlqGlq>)Vm#kfvArug-$ zOsvatku9GbLz+n^o+n{TscvF_)(MR`UO*^IncQPce^L#40|S8<5K}E^-=qFAVPyBHQ?Q z@>0aM`H%UyLQ>FeZm_{-JkoYuftSn2L%`DesQ;X+TPHZOoX<0s2D}`YX{O|my0}nkS;3gyGuUi(jU3ksg#pKXH4Xhtybw&lS3>9 zQhyoFm~{oG4?B>3`BY;1y(88g{T$T}m`@hIwn0gP2CUyrD7X!plj4KNp1TV5Lp4y% z^$4X&{yX@wC75FxRX44QVj4!7C_FCjCEez@$del_B%Atyq`Mw=UF7X$Bc(roGoj_%n_}tgTAp~+Qp4@p{|fj3GdqWNugeA9E+0|K z=`ykNo@CV4=r~T?*%7C?9!B>A%Ebb=7FZ)JjALw6n3ojuZuji`($?$AIKf38Vx&nl zHqyGXdA=C!N8c41b!uH31O-EGfy10L&~&d6f?8gO51PFo;(2%SBa^DU+>gZZD|K;s zc?Pn)pD$i@{0zNP132cT>b?0yFXdqZ6p7bJnXCet6P<`1;t6l1c*F@^H{5i?>ijJ}>5!id|g{rFk?A%e+$6-L|27c5#lf$(36u&eqhBzlahvt3!LzysdD?y<%{F z>W@;a+LC7-kHDCi59DF=VHB*2p>-)HDaA@@`ZZ8oW#l3|TJ%JlJuhH4MJ2}st)wly z^s|;S`YZo$7=}$nEd6yJ;zUa_{M{fFnP4uli(GO;;eR`mhh-h4hh=RghRIRw&_)y! zalNxrcx$C3S}t<%QYUmK{~T8TRVJ|i#{IvGeBLvv;S0}i*niW!>LYJ}QTm&Zv$wK^ zoxQIScKMpu3O6RTCQ~=}mQLwA<}*y5Du(V$F+Lx~eA~JK!ke$oa_6l9WSe>%HrQP! zum*o-gyy~|4=Q5bLSyR-@K<;OYx=(C-SSe`Pa4y8OGbAE#pU$^Y7^BBE>|}aFAkbDJFA@ zTK<7ZT{J;-mO~cLMjfr=afY-=v%|bo{*=$7(CY+eS=0Xp>C+_)Umli% zDi+W)8fs6)FnZ_d08`Z-F!wCyA;-4hT)1^UUaGj#4=hukDN-jM6i-wNFuZ+;WYF`w zm>EOor0Hrx>7GUdC^w36{-ADWd}=jv*z7E)4Gou`&EJcy54S+>-Sc4fpncqFDf86> zFdRRN_d~Op!cUp`@S=sfbj6zXNT=-(o`_*$_SH&Qlafmow|^zB$vr7B%uN+$I>q?a z_s!4gbO062ah7j2`JkMxOR<)d6RL7 z-WS7$=fb~bhs0Tj24WlQQgqgWh-SVoIVOD{U(G^_85ES5-~QflR5gbFHx}o~ZZAWu z`!gMFTXzDcPIm`nxhKiNio5bZ{=U4a|F>k&ay{Ys2H=A=9{h4kn4s}IIU&F1E_-F2i#qO z`4Q9v(`m`ixv($b5AAq7i2Hm(Xw%R=;=Eb=aOT<%uz%TqqRB*0j>%KqG;fOWKl~#< zEF%fMxaB1GZPBbq-qc%q^q>mO?tc)*Bw`+QR_uPro0BpR#c&LJ(i$%rW3Boqd`R&h zT3T8rE-DMbI#Uer(l5ir{%#Q*vx@_hAs zNN;NxRJ~jVUUM$+7R`M-&Kqls?#S@EE*TQC4)?t?2v2N(MfA8A$uWW|#SNzzhvKpM zQ-5qj`ZpZq^^>2Y-&$dEa+(%cH6>92Mmjt2H;vA%HNb4!y;O*n4!_dQ6c(x**!9J0 z$Be;ernsZkX%9Z)Y%CkS)gqeM6Z&Xf(5jI+o_9bBvKC zeOKz)sd_DMgL7>66P%u%g6yI;XvXUv#5<(|DsuGk7PtOnSK>%?b>mT*_wYR}onm_I z9HdwloFXjE93!iRcZ3G}D{_L_Up`sf^zJ*D?8xMp($|&XHH(fgQcUxg%TV8Pw^ZM9 zhvYr(rqFes3E8npN7@vmBi$_;PTD57;g}ApP(6=g;wJ4#KCo_)DpB!I}q%Ih1`W`^O6_pY-ct z(-tb{{#1tWg_XdRlgg56(Dvthq^a%_8b3x9uB}DV{BxgC^9KnX=}YwoDCP;>p=rob zMlrKYE-2cc&JZU&8ZD=9e2E%6#mim>g-EXjb@sbXr9Moeft_-&0cMl&v~g@*IRqK` zL!W0RaQk;Rsb{w}Vo&EOl4)BFX{}*1GV4B8YByPn-!v0d)LBb0ccQZt(MPq&otV+` z481kPy*gM<-S-4#uBA!&9cooQYcB*ntpp?2YA!&_%(ilLX2IN^tsu5lH4)<%L-CJf z(q&r#ZB&Xw2MdBo)Sw`~n*R&c8!6`Yk8_H-y==((@uTHY5B$U#7yaew_o}IqMIP9x zKZK{9=kXpWyT+S9E|>6GT&A3Kc})b0x)DZd-q7Zy}QQU73MF# z4b8{XVP@n{RD?eZU!PWrl@o^H-hqRl@P39kddzvjw8JsjFlG+NoKa;2-zdg(|8_-2 z+bv}3V+YykLu={IR89GX?i>_8><0K%Q{${XI$Q*ZxhrUozDs4p&%>D>H_^fRbN1nD zPY8YkH{#;V3!UYQ0#i|N0LuD$P3P_mJ9>` zkW4*ozAa^5U=`NnPR~_Xzcsmao_V-`%bV(c!d)_9qMC z2Ws$)fOQSAA=#!2m*Dn^*XXOeQZ!$ZggP9K!+Gnv;PK0X(c0X6agXCOD0p;$V|3|z zLouBx=1Pu@a?N#b^3vQv&cCou`eoD-msz$!%sq}t>(AWWgRAzkj6i!G?YG%@mAfmH z52cD$4^E-TkQ3O;yc^#7GXr_NPZTH8Q2lSS>ZZlf&4yxnQcO_S!^#)kXA$!j4syJ{ zy)?&Y9G+-$n@622BbfAe6m1)=g`ko|aPWKzR&f=e{Nf0Ulmm&q-C<<1B?50&8sb60 zX{h(^JEFXfK-jdUd^M4(`i&{YEXcf~tg|0Ru2+we@4fCwcHP{I$Gn_}SQB{y{T~*; zU(MsR`7IM6eB?7|ihTeN7HkCN*WP5)j|k-b#uv8;Zja5pPoTsjtw^8O@o+N`IA)M4 zBe0?vm$*vhbzcpleR`Dq-hQ;WFFG1unh?%0tXF-u7y{wz-hg|nM2KDa4Cbr7fJ+(? zFd7dag*Ub!^+0$0eDX&sQ5A|tXZ;Z;5B7n6H}yDXp$em*nEbxw%7m{8;@FL&4$a5 zw#`NoyOc%IXshZ&;6yPU+$7~<&m!f-QKRHZ{>zbnLONc*jy7GiujiA+Y=;h5`2*JU zIm`1KBlS=G9NJ)pB}rQLOi-))PS|yLzaE-j*^0dT{gk}3tRxK6R`ns6L^1U(6P4?7 z-zhfgjgogQEJx2PPvI>iW2oB51K!TVO5aSfm060LRMAe==k$Pu2E6rZJxF@W0HLAp zjy!9(E99v(QyBJFhd6z%CA0h86d0yh^&yx|F-G@dmD6=k3KoyBoHbw>EJ}^XUmWvL zP*2*_r9u-b>O9x8%2C1)517<{vJmmK6KQ1{0m<4_V*E{aGU1O4#}v`k&^T=k#VDn<%E=8j z=;>T6oAC&t>IxsbL zqL32*Kuldf03Ixfk%lgzTB=4m9HXrY2e(knBbQOilNF25owiv1oNbS09Nvq^>1A-i z4EN?h-l)tHkKg)B;9J%eh?;a4SPZ?iL08INei`caCI}zv&xpb9SHbE_IeEYMg=lo{ zGXHOSt1x~PGk?T1<#V?H%HP5*dw&CwhG)xO3vg2*;2X=VKq6_|MlhDFveJNqIq zMdjHWsZE8(DAZweckKGQSjZ^J6-Qe3!Q$s^wATNsnB-p1F;i4&R4~OKl7&e z@xyGqbiY67!$$GmMKgZWKB$7*D2h2aZIn`DbOH*t1=*%uII`$l0dEhz<{80L>k(Ww zhhbVcG@zP(C+I0h6=YH)t}U0pgO&OL9ND@rifWxEYK8>h3mrc|XYY;Tn~|$IW|yi) z5Kl2(=5|qTG)P2o6-e%Una)Dnbd#zMX@TpPV3^uw6unUyuxal@!1+(nryIv0^IIj4 z)7n(_z$2_8@%|?>(X&0pqON=hQy+F*wa8LjI6i`7vgp=HpR^Q;iHNVy|IalJ{auOV zF@+ytSI-}k$yIGI=^hGS+?I1!d3JKkyztn#0$U9eXxbGp5G#itpmWko(U^@dL^L`G z|GY66j~wJB+6Eoxn3J?7O)(cKrs|Jt{*pamDC4If2Yv1g33tZHLH1o>_LO5hBVaK! zQyh~Qx7LCfLzUT38^H&eBmVpR_m zp_s*f#BTYB9q9XZK}M5%z_z3VvOqmM%ySaKF60~!)tSwXpRO;I#-;MagN5peLT~(a zH^x8DPDEo@wkLfwC*n(6t#JCR=c4|VAikPus&<}Yig|96XCHK995PTBq)P>4P4g+gTeQ%5p@nr)iP+$-QyQp5}Ow zK^Jm7Y8A&s)6zG+X%!T+#J8_vuy<$lD^ekEi0uG-gD=Vj9Sk8lHy=`7G(u)zIxvjK z2|AfiqfVBvGus1u`6p!kjfL$InyAYqaGwj9fE0#xwd3)Xk&k02ISq7yo?QC9x}J zVY%?pwkIjjZ!H~nXe~_+98L_xjvO;W)tvO4V!F1DQRJR{q{zK$FAEdypqcN8yxyZN zdmtRJm+zJ5R@lpX8(X9HIp<{mJ+yKBX&#g~w#0mgrUPX?Up}Iy zb*hZO!6gRvC4WXXwn370t&^bsUmDdN9wYq?Zbo+uve2WY*&OqK6^~|$NxphTaei2` zI8EPPZW2-y<@e*|)nC-XYjg&%G|HTAIxHhV{~qwhu}sa|ptm6q=1m#_Ip(I4Q?3>9 zY&B21Fte@H=GtF$_ro;l{q6nsY&GobNdu@>r_@`d+7u{^E!D}9JUjXLrvt>?CrDn{ z+zFcKWOrRz6ExQDgBpiwV3J09_X@zhbrC$(mmW|AoUZ6UkkHB7|PRMWcCOwBtN3+`xL<_t9<`_Fw)M-dD zeqP5E)|%6a+s~15`d>A2xO$d6&@>f=YtqX4%}QA4X9v6duk(z+GwL>!hGoIb59*NN zHVCzz*OxqWFvWA-+e5PaNSt-;hOn)6C)B&RVs_KgR2UPAIiNL9vF4i>X_Y-v-i@uK znVIe6l^Ib;?Q98{4=;vENA#&tfXw~Yn7m=$+6ypg>|LZR9VlF%g@s?jYW(GNA{<%a zCp=nam**5iJ*6&g<`{JqW)Q_hA3bMpyvmoPdW@9!&Dtwnav3K5Y+QsIeQ)!jrG@WW zg6l)V#TpYtdNy5o0eq(2Kn319VuPtW`rb$d(vSax$lBg0WnPvzBJdU**c`wym8wU; zhGJelDb7Fo)R*+?I8w%u$0Wnr-XKiwkNj5GK=i?Eh&NIPgUTzsMo=`m5mL5Y21D~E z{w%F-pMewN3E; zq;xcAe5fdmFN7C)K72JRR6S6x6mxECnKEWF?Rh$6D?jQpLo$2rfbaBfhnQCc3!n_A zkEAQ82B#CJd8nRHbqC(e$MEDLeP6tfqHb@F;pO4I@sG3&tpo=8oFc8wk!qd`9e z^u3u%F;9N}Q|?`1OA_YV%GaWerEz_HvCqyuX!fakE&?=lI-U8T9|ER!OLAYOR_016y?th!aYk3@v*2xpX?!)V>(imR zHI)h9_ZjR~o(6_l+V~FYGLxWP@))AM$Q}*oX(qAj_-fayHw6KT7F0-q#C`7eG zdr{2jZY@Opzv|+Nv=Q>o*}-Va-3)y1^>xHL?<-0&d0T=<^>-+^n#3`7$3F47wev=_ zD6FrIrrBvr>@pi@hFruBWNzVKdNmP-`KoFk-9a(4+CNoBM`bBGY#t#;f0WR{nlpI) zz?1wDC=I;C<1|;_&%C3HWoz@(-|-K@#MD8=eexDzeo$X!_>a5fsa1-w*H4q&p7xt4 zzh?^!!_p{vcppG9Tld!~|7J!AGK`Rqo(M+WCd6Vc_pxymW;x(mI-<~Gytf^0}hB_{i=U`rXoSzFYkyD1LN_vF8j9d*}N>&K_ z9ZZNDHR7;1-v-LQ_9J84&fu75G+U#wKs3diNLg*iwmt6vwv9Lst#^Wk&x{qe8-zfq|2n>30s)7-0kw%rfS`!`(f zo1ch&>Tks!BIRpOCDF;m=@D>nv2qMql6%f&CJpxa9aVR@GtM6Zp7NIxg; zf~E8NA%tpb0(p0aS|C-zCr1(D+J%FD>j~55jjN~_M zx@t8A6fI{VVrPG>un)p6*6UGj)MGKZC>R@sTH_0-^H` z%HwRTz}+VaJm^WFLj-;MX$)PJyaSqsr-7eX2__boU_p6zZ1Dx**Yg*mcERdo;jSsT zXoWTY=NK;9{S4%oJE{TZFBD_*OGlxvJ{rXoTgjsj7=iVZcsV}EoE|o&gNJ1a$FNca z+Xa}rLh0-(ewgAluRT6ru7z)AO+nhb+mLQM`r&qogK$;ID{+y_a*laGl`QBk@RwpD zLZ>L!Zf%Q_CtJxbUp3+V*30tUE(0LiMG1P{sBsW27BkHAO_%uqb0et&3pzfZnEMV| z?u&-`A9PWxq+aCXf>+T0PcPi@`AhNOdux>0Djsd5tD#$`)@k~rIfN>H42ls6`fCY{4-pD!~jrin-r8OVJufD9E~@^2S@&QHCJN(SK+fMKSHY)G!mEWl7<; z{~mBm0d2ap@JWZ_A|w@GvX=TSTrX&k)g^DH<&ksry1phEWlTOyE#cykiK^$eJH-^u zx~GUa(MzoEFjQXpFImjYPmvoYwuhA0d2lbZC2nq{&gC>C$m>T}L<=iwH8fPGh5S$3 z?jp@@L6Y*I2DHAYi=Oz6lqMB?Ky?9Ekwup)98;_6Ans2w+dOL(+m*TEu!}?F7bmNc zJ$(dnzjT8XfqprSsjb`Kqwpz;c0Z`!hY%mCH8kx8O!x4CalNeI#St@UPKl3DvJ9jg zjTX|j6|d2B)@)>_Il4kiXaMUz^I%PAIn?#K!RH8A z)VcVVF<6dGM33hr5j%Y~?DirUjlMUHd^+odYN%wWGPna~|II)ZW(>P&11=~gX3Zg& zw^_=A<628o=Z%+F9?s^@7oV0sJEVJ1+_+TJ@AH(PEZlPxXfpbsFab^9(2otQ@3 z;7Z|>-E}_l8*u$91f0$VhxWDLN;|%Pw5>wV27wUtDO@Nk-hwkmUxE|uGK2*u3zcJ! zT!B<`ACB=+{WmiyW@3jV`_G2H$&gTLrvp z=u+=`U|mDEM^~chcONPvjMgEfh{7>5G;l9XbM)+VuK4p@IX%b>$YX4LT{`$aUvw6E96W ziMD)9!1H$Wz#f$c(68_^QK-5Gmz(x*%srI|&?<`gzAZudt9Tum(%VA5l^r7`>8Rlw zIkQptBr0RrIUOFA_X58!-c?ZO8>PN1o z9Yjm4_Th__hIq4D9Ga#1QrxA#1&n`LaEy;ivNeceR{Sv*(GhimXAhR+vW}8NxkvE1 z7q?I}rlZ%)k6^(;&_43+f0&?B>MnolFt|GmAx$ehQRP!Q0imynd!bMyl)o3HkybEm zeoHKCpGFH*l17mf6FJsIEYvzFp6fDLe(^6%820!Kw!CnIuZGRA*L^rmv$pS$8K$Zc z6nK3AZK~oIerF^J!^TLfrK!ZO67&DipuHbN{fPz=yBKDS3KL5)N0xLIZQ7S8XH^c8 z$Cmn`4nI@yT+J$uY5bK56?3TzbIH&D)d*N~(k@Ht>+!>$to|(u0mthIyHb0!L!M)P zivybPkO6ukVVJ3^55XCV+4xmk3~BvPF)VVB?02*t=>^gvmS;InJW@VpgWB^9@a*!1 z*9cg1QuLeGz#3q-wC+ku?o1VK-nvKS^5`hmZb9gAUz6lrxpT3^-vzAFQ z+gG+0cP)t)swWSU(_V>C|LFu4vcI5kw+CQuNc{=vXRXxpE%zzZOQ5rBot|>clhL`N zL1Q=J{@=D}yJs+Y*sDZwdQ=Ot=H+-Yu8SWjj1cgoL3#G7E#Qx1uv9IB}34%GXv$Ik*!5X??d=a6KzkRHG*(Is$WCJOwg%D z2zj%Qdq}cbTo!dEzetzvE$#xNV~Ox2T8|_xw*c4j7|G1zzId&qJ;y9jg@d;#=4!87 zO1GBt&_Abv^3bPxXjANNZ0PwBZOhD~2Pgi(JiXXQx-fbs6RKim}~)OWCfYA6oF$T-KPMj{GycaJ&3( zD9w;`_f=XC- z%&F&?|7*K`N-?cl6ewN$MxfLfbGcpRMs#6(4?H2e4Q#u20=VBAT@CAj>Z{uxtokK` z=JiToHG&B=R4mk5kKc@_5*D7iCo0-Z#`|xq095TMqR+r@+ELYN-Z4yYhO+ob45}Mu zE{~d=4dSXIIAGlt{LY8M#Z@*u@nAhrXG~ro*3QF%TUH~8UZH`9^f-uzwdjS0s*7UK zAwL|~{TaN=HWhbw@l!o%s^jh-6ysmGUl|w{ivlj0$*J0A(03VjL85P_cxh%Z4t+vxDGap5b{a=G##$As zt0mIShBzpX^gW8=Y|Uh!He(@9zm@!FMt5rI8V0Q%t%Syj8N7aT(WMI?U}mdf;#r^9 z4#rb0f^h7qIjH~l-{S6vf%t{mU>s#NP;?p^$1x?U7`h$BU{g8Y?$Ul_kzp#Iu$>0K zou|o*x|>4uZkjnKg!1EVmfy5EI2P)bB=Cv{JG{5qZ-(D1SK{E(S?Hg2v#7IfBMyIN zgWpUzCAvCBag2uwV?Z&Z?Ck8$9bAbLO-$u0!zaOn>xX268AHJ@H<^D3Ql_cq2zJH! z!i25ocqxKmI*&8P!G`wu^4e*r^pFN=xH=whYaEV)I^Gx8Hy`Af8FcHUp}H}}{7tX0 zfAMZ4+7>-PKAdht`)U&87TyEFstfJuoKwoTPL@WMQX6Du7h=()h99OJzpIOD)LP+= z&ErvzWgUqBWn)}VeJ$c=wkCFmS8z-S{oYWFImKK<4vJ@cS|YjU0QsGkDJ*<)StjEK z(K9saMnb1oOJAq+Q+3u4ozh=5B+Ih3E3?1C_g@h(;ldykB6lY1-5FvOubzvXvTi%i@rf|W-cg#g!bV!@ zwo5pg(~E3qol17lD^|`%XGhS}UAh`0)eh}KG06S8!lK?)bSvv8XL>#*ixf%nz-?W4 zjo@d0HSAYTcj@<34VKmjjHqWZd!UzQgu({BCn)yeAxU|ogS0hro3wD;7-`1}HJFs` zE$w)mOBklF>JZYMVph$#q1d#wOx&`npFA~ni(su0EoYCX343xT*pVOL)iHt_q%+&< zGNs5fg2j1jz^mF8`uPu(>^fdR!wy+UiG4drVSRs~frI);H5!_HHS1NFxfFAGg{0_O z*@=Yx>ns1WT1<)-g~;6|4&u3I-MrU)j=)Br?qidyq1n5D7F=Z5yB&k!t*#)LHHy9GvWH>u-N2{ez*p&Fi@VDP6Dba87OacD5WBj7g5p0ZcY0MOrp4_gZ82_=p3cZ?z#NMW_+(y?_(y+IYOVblkb1`jsyHf!^!T_*) zSw!ut3xL%Kf|g`L=)#w1rMn?I^yjO%Yv&~V_R9(goD(9R%(x>gUlaiimlku(3l(M? z#k{j@t0;T6nN&RQBcD}YElrwQEFFDv5(RnPfFN2#`JmO7hwALTF-fLfLyI#&x8+S# zSUpzwGqzkfCk5j9uc@m4`b5F`UjJ0d22*et6H6VS~P9K+5}v;E6Elu=REu!G8$!ms|D>s zT14rl1C7pfzbC?AMIHzN{p{E%LFT0{i8J}XL0FwBM4zJ452 zu6ojrQcQtHv9j&TWu)}AiR^2!SDJCZ2R^@h5^Cy26Li`&w57?ETZ*%&lhp_+dQgA7 zVFRH{mqFyutZ+2+&q=(0Tp#@8XBsNl86r-PPKI7-YdNMw6{;st%#9Cf; zLw!rPf=A8^et4fWh&GdFH^RGlelTRNHCayeJHF2G!@WocY?K#=-c4&1_wHK;t?CAF zjEl-$;S$A6l)H)Rj=d25EKKC;>=(-GLC5jT>I#lw6%VE_z+^#LDdI03US>nGQ7?}{ z(;x-e_+&X6@oW+fb^8c+gc!7~+f8xZwRdD4{2_X?&Y(9GLxWqHVs?$t7q`yYCGLFN zTQ;6M0&UoQ4yW|3;TTrG(WbJ+rAL19#G_`(b2^Ce2?`FRf$TSy9C|tc^?KP)VprON zRj7Z{FR@~gzErWOqr@;n=}n`UQi>VANL%b#uAvM((_8MH?}h&LOU4iS-QgL5T6h-S zWHR8>f@bJ>Eg3TB(~1Y}8e)yg`#lxp((EMR+tilg>~m&P`|IC@ozBL@@uiuB8%-4q zvqOccqL{13f0b6DgM=8LWBR#J@MQ zJ9i|0|0WA<@L$36-&Ha~*eZ0}u1!`=m58p9Jz|((l~+VP#Z);pDNBdt3Qv0WmeYRf zp+#3?@ykBVDCHteare*~0WE!JYQBZp(iy1O*vKCN_E|G9PZK9g=g^<1*67%a0CI6A zz*eWzDCpi860cmvF*d5zyrdY7^S6{5emdw)iLre8TNMqG_6hN%Lm-xPE2zst(}WlPchUdD1% z*A`-JuZ?)r)K943WEK?G@8-cRJ5s%v>c*$=bONivfqJf-nz@m5N&F1y|K13e!6jmn z+dnwqyC=-=;X9S=ng}r3wB?P^Ey#U+)eT)+76QR}K zxnR{Ho7M*E;s5b;-f=y>?;o$El8}&wQQ47^5qY2cx{;Nckr5$TA!H}CBu#}R3L!~@ zBC7Wpm4=K$NRo=8j7V12@4oNz`+oj7e?K4hd7t+=*LYp8YuE4Y5Lz_utn1j!Rp` zvvR`mpDqhgbow*C_+<$Gec24#zqz6uI4Fu?YUO2Hg9+xn(Wk7^E}>}MkM2_cbpzp1 z#Zbw4ycu|(ih!ow-ozSIj-ji#-rzUs4BLN0=cH|(nB#xRKKNttGUWSNRWR#*0N;)t zhRr4q@=eZ#_#IO%n46DP~pbzQlCCkzX@spMG~7E4YTshOTTEdh z^3hWqAR!UXEW%4ZE<$5MG=*is>+qshR+#%5!IumSWSEXJW<0@c z*Yh4b&vZ7juj(e5#0-Ymu2Isk04qpUNd&#~Sqwu{+#1gSi1WY7`Zv^Ws`9J>zSPtg zYYv)&zDBkcdY(tvros{r-G6~UG}41%X3Kxi=>(HdsITa+(+xQ->n7Rh8pF=)6e+80 z025iXEFk;4Nb#OxXosCn7E`S{UAbqR&>A0bdk&7Thocuex(JE&?eSTk{`jcZN50iy zGJQ(^H-<9Co?!0o+Nv1O=WxZZjiqJ12E(+KnNqO(AShCifUZVn!{r1M&?$$7gS6v8 zi}%|{d5hbv{lzZnjhxR`Q=!+-I^iX`y6$Y|Ta(0J@$dp_E7xq66HL{rctwj-2TpyH zv2;DEClt@ml|J?uNYtr$(C51frjy0=H2ICCOwN;VOHK-JaNETjoU2$%+N=2u#KFSs zsgP~?R8W0J7H%x@1B$VdGXfWaiF{wG=(n^;`L30*bgOG;gr28Mdp~stx?{!ki5jNu zRhkjd9sw1=P&1SA15q&K<1sYSC0=~Dw4Q5YaGLkZo+>6*mZ2k34%!)*$uRfj0`WG2 zd2#)T;!$V}zv#S?B*g1*+{rj8&RQSBkEesX)nBp%Et>fYGz=k;4mCLyi(saSFRbFs zVN1ar(Qf)F{)f$Y@!y&rqSu)pXne#Nas89e96e2UIe^+nFb**_iUm#o_%ql@vY*{e zc-cQdQvci^%z6`9ukL3k+U5@}Wskvo?-R&(&jxBnUomO{G<_ciL!W7hgX`wPJ`^jI z7gPxg67Qn(EBpklEuQQ&|G$CRpI|g%YZQ|YSqSMxhSI6{!@}pGfl~R`ArStISb&kF zu=K@RR=Ev#BffSP)QBz}&e-<>->a{X=HxPA1nIcz?A(d^91Rit%MYO=mM77al-8J@ z2FX!pIKgyCE>^S-m?s=wYA9`8yjDi;Hwf^@Y z>X*ba0{3HNc-j9N`$+3~CBf|ABD8Yp7DaxD73yphhFg#N3*Lt{(bO6Hcn?$o{kr)x zjD!57T_G5$n|G$)aZf?O29nD3WYOzp570B($6^6$Z%9M+9dipHVtg_a_*?s3htV%T zqx-85@g2`aq3eTBWBWFSxLj{7+O3|)Ys5T)8JiC<%y_v+kV!BX=5A6>NZ%?fs_H6D zTb3aPmw$jLi>*j){xhIsrSbE6vHlHJchiz8wVNubG=|GIYC?7Q6Uc7GS^W7Gae-SL zjWl+p@ejvjLALoWhOr=T0g|oVA{YzxN6KG`iv^94u9AuWVewQUhX;`HHo9Gb2DgXJ zComb@zT>j;KDM+Nn$Z+^-8fk2uO5b`r9|PlyM6K3n~5l3WD>uu!$}xtW6v;=18>Ld73_soT_V zLXY5Zyu|1gaw2s}H@}+u)84qNE@bYt@QTh$c z3uR0Iu|E!ZbP0yUaDsYoE3{L4ph&M=bvubJ| z-qWWuztu@!Dt_7r1;kv&4GTXp40W}lWxLejWR&M?9HbZ5vdLm9?Trn$6Qc5KxxmzS z0=?EYk(q)M@A>468X-C3kw7v3zr6k%!AveO)kFcy4_)E8f#J zqKkK=!T;nu0h+Z?Y4Cwn)ejgB5z_m3atk6?aF(m@3H$!Uaf8}^=g)Y&75=qXM-&r6 zUY#WIP`OAvh&LMXCVHNn>%%UR=Z&@Kvri=U-1-JJ*;T+|yPIqflgfGMc7?tx$N)1D z_*40)Z_68g-_#jg^{7W&`JMejr%AbrFZDn8EVErg{~q%grmZ|DtxYg3Gu!jyd|z?1 z-MdJa19l?K6H&PP4Q-$%Ky=YFRSi)&4;}W)nOg}nSI7eYMa$#SfEXKC*nbrl0v5v8 z;Rj%M-7jRC(Ls1V!=7PY$-@_&2?j)UzHfvXy4SOdwCJiE|8dR{oVZgPa^8{8*RmKk zBugiYqs|61OCxG#;!c)w+K#&={+f6Ty{+}+Uivlj?T0m?2fMC|*_xdtjoX%}N5&XzY-9*#g{NVjj~$a* z#onlZc{jVTjDQMYXh!h%^l_+YrY$2&<}MG}htLxz<_L#S~*0=}_`_bIS*G-{}I-P@QU^JQjU} z(vN|-SE2?AYo+8T+}eawhF*o*@U_ad2evUxl`Kx0L@@e;^Of_YlgQMdlVtaH91Jfd zJ2~c?10DH&y-CW@!nez80JqP5C3Ie?~6a)@lYLS z1P@dm3O&j&Bjw*_Ho?>e9#`5M97kUR^`!38=Ry|~rTC$82+;+EfbYW9ER&}B4b?zd zzl~v-rkoq_$-*4RYKG!D^T(k20~*4dRss0HgWmYq{MO2`p{E(9(Nk5 zJa8ibZEWl)eIakxy{|A6NoSqv%FVy2N2PSl|~sJ@DJ{ zvyh!rBfoXee%w*tl57QB%7^ccU>G|Y<4iDib8yyC(=F)6w2o4Fq&FO0>MP|9oDOsm zT2vuP(n&*-PONNey$;;RB{Fdm#l&Uy!U4@Q@ZaTg(Bvm-LQIAOPAVLM&Gf^0lhL6J zqbAGXTnVO5d)L?l^T(mvNxD)^(Q;U47%k1%J_XFaCbQkE;h$4jRo%}b4B~EFW1%|D z2%agr;PX)i_*>~rRM}5cC>}HnKX4t2hsE9E$49Mam~G@`LvGqGg3(=NqBw8d7X3EX zmDXOdhJgcbNE7!@B_&m2G_$mdrBQT9md-}e;ysO_sq%i%Y!&?AwGw7s9*Vq5b%d=8 z)bPNseXyf?3qRu8NQOBj&vjHjNae;Q@0&jYKt;#y^R8 zJe8$UbZ^w)Tetq3Sn{X5<&_UhSefJL8HBNzUT#7cI}*`K5`tSlGTQ`=YGNB=m-|s zSa)~^$@)+X9p<0TbFOd>P4*TB1H4XjlzhL))NkZN!T8uk}KL%(ax1Zd{STr^6NA#5sWgI7Ju zMvKXcE0x{$2xZiuITyQPdea)@=~aPX)mHGS^Y!C+Rwi4U65l_JV z`!z6V)M3uB^esS(_j<`U0SC2$3)7VROr02{lO2b5eC&@~4tOK~zY^b)a*gP4-R0BB z4|E;DEH|uIPRMc=809$LJoqa@pwn!}tW z{RG!z$I-Lv7qB#ODE<|A5p@(!^JN30VbCuphKZ2p2tE-^f`u9XX5Spaz)o9AxpzW5 z@p~Hn)Aj_S?mR3b*g09=DnI-JX|&YBzTXewQ`7=*=8#aL8-j9gpTbwa4Z&A`UqZ|_IEK-d8!IgYQx`g(uRT3Th*#B?wqKhnj$Q79Q%nlwI<#*xjF{;LEnn+c zMi5?D3#-jvf>B=|7;HaMINLh_%^4DiSH0|wPt1=-W0scinnfI0^lZd1hveK-J-(I7 z(@nGa(hq<6K1pq)Wr;_Hvsx$cLCrrhrW2XLnRgiGi&g8x(N47z{=CXpRVaJzcMDi|++eqGh>$%TWari7& z1*#gN*;-~@9E3;z0GdY8P~H7;BdFa>0h4vpg-N#NNH4XQNUt9M9MRlEszTC~?qZUI zp-3@ha&T)vFwR>h^Q#*Zm1JXv^yT&*lzcEA_ueC)#^_rbvzVZA9y;|+mG@LNL`y?% zD;(23L^MFX4Hb5V2+dm}hkIpkWkL|oS5bJe}jr>x-PO7u% z7WYuJ9Q}=ZY8b_JTQx%Xtu_kHFt{haI?>24@SMpoMY017CYa8yW_)SbU^FIHQ;P0o zk9@-da4+AE;F3gporhV}=``jQxL0~I|1?^>f7mSxQu>67&lj$R6)2BuZ=oryjNJ!6 zRkw+A$^^b-Ss#WuBKz6c5{y%3XTIm%1xRa@rZjh2EE;RP2}jv$K+f4z@{;ia?a9}f z{RcGx`sORJSzMYCs5*oTT@F@)%i3%%M7xsz(f1v=dbAOq9(~Mn%M00WGg-#WBbaWj zboju4eJJaJhBP*$7~R^o2ImB{hp5CjDAiidW;|$|wt4bEPzy+9AqSQ7w0%^MoDGNI zsX{ha?emJC^?DS(H`xT{-n+rKTBpiRV;#r>C`W?P{{2UJW<)R=xJ*N8zqLEO4EzIo z=99V4&&Q$n<_WChK_w$5dg{>hgS>D^BcF!qi=Y|;`y9Zl+E#E6Ce`srPtV7lmwChS z+0ML6=6r@}AHXnc31-am7s~5%k0HZXt)&H#PVj7s3)EDbLd}&>C_Rl>ic2xNUtY11 zUn=mYGaeNq^l-`;GP>#4Uv3%1Fu&yd#*JWlJd0O;e|H4! zp4D1#GM84eceR<_?F&rNrob zzt?|J=fYZ3mJ!g?P)U5=Obh&aqA%v_7NO-En)&QNAN(_72)@gA#W1VoP~DGU zgm*WxmK*IvTMg8uk+JU3;oM3oUu_bkJ|cPLs%SPxKnuhkhwVWxl)T?axtls%s&?&* zqc<(VJ&r6wK1E;o--RwXIo%4c_;P_a3OUR$QF3s5m|(Q@zF4>YI}K^>Y$a8OJ3vf_ z2&qfUEC?8#08u*R-9;>oLcGb#Kky*ig;zI(ES@3aq&K1=e(`$%-kLZUwf0dH9_Ee5 z1E-C|`;I*0ySBg!StS{sjymQh{~$er0kjzVA&=?+F3Ob=!UX{pN|=a z4#pTgJ_oLfo6I?hc0Bwev~b~_T3E4l3_AR`jnH>qCmbVviOALFlVb6on`8syOVAnP zEsiyBgREW}2_J^v5;Py(5+1cO5H9UdSjV6!P&u{BegUObgp8)d`94XyA)(p#hD2RD@p zKxcDVH_CfkG#ty=f*wA(DmGYKa_{`x2?3Mr#8Hc~QI=~q8hz{gLvh!3)0(TK+>pmXuU!OH_apNB45cmWTLa7Yu%9EJ=hWF52XjY z!K-fT#3`YX!i~pE#a`FV#3Q3x(5#*d#MOPvczT*ya-4RTU?w%aQXJi`CY+qBB2AgE zBfP3PB;`G_1?x9N1RF&@XM=*FW$aV7){SNa8pH>GUW+4S&L0FW6ZAwweN!0b|5Ipt z>YdPJd=FJez7%ebo5oHPDhIbu2xi%<=Zfr}Lxj?hf8vBE=Y)fA10~N#i@=*W^QJzn z1NBGS;o%%IicN+ujBb;)Zn2s0`}Gje`TG@p-(DpcuPcI+6NhjWt7C*Z)j%YqKH*f4 zl8-q#%}E(kMKGhm4XxQNWf7 zQvuB8dFt@JIRGu{zd;!6p^sB;D^ZH(Ai=Sq7wY!S3#!S&JBn$MZ(0Mvczr*ixNo*o zSQ+_8thhQ|TpVK}LC?>qA@3HX?!6BSxA%o_S$XV%rptt>U+3u3Qq)rRh5PH>j`uHe z#G5uA0ez*a;@ii0+{dj~;m3P7h6$4~%>Zd zy9-TOIk0wndnV_JFi3~;@8t~BKkqi0>mQ&{DK;f83&FVar7z$)u7!(OF^E53Pymk? zdozry97F#l7~`*wSqm2W3I8&FiFrmjV!EXlI#8H~0ydX|EeXrZ$o{VT&bOdteF{)t zb-Ef^MXL_Y{p-Q&d-37-D%(Od9eCCXc*;YJ@UUu}y_5Wyb8ciS3>MRH#hlJc_q^VCtqJ1U-yK_mVE) z19!}Ea`-7W6u67STD#(Ll_&q3#oe}X8G8%R=~b%bpgW751J}bV zy9q+AW)PbH_z3>xVvdWZkzBL-A^)nCD{KlH&M>#-jz?dD89?fWx#LZRm+3#m`s1C2 z{ZoUnhUUlrG6L&{1H=NX0ci1_j{MG?`WiwG1(QC&P(eHzfW$Npye7pE=joh6`>cz3 zb7M>5?yto#Epo?WD8Xbcn#2z|T+OSt{UK)Gci>$r&S35Jf0)3ZYM>fwPm#R@O>7pI zVlusnAy7RjcqLB}c3z%>4%&7W>GiBI2$fx~=MN7u5b32Ib{dV8i}%(9;~g=c_dm6f zU$gqVnD$g1wf~cZTldodH!`k}vnmx_qLN|emhV7+8;YsX`phiCoqNp|=6r62e)MWB z(yL?(G2GgsDyVv?i>kw01d2H*V{9nq=osGVNqSbt+;3u2HZi3ieGX3#ZThcxPu<|$ zrZz)J2HC(&G6MZhA0c60CTONu2;;OoIi=1U#o>pq1-mvy+>-=N;o-(s;z0FT9K*=P z`eE-e!rYo+jO55>1Hqip z@5*=BGZr~keGxyKe}Ny&El%nW`X7EiQ<$$ zr->s^0(Z3i72YlE5}bQyC=M;J;Kv(&W4}$AjM+gjfAsYD=RKX!gKl5Msb$8CJ3j&8;J@Y1BuH z*I(s7{QJT%CuEE#!ECB(!#mIQLCtfU#8(|pqo~f-_?NB$Dc+xfqfRr~`dwOww#n%V z-_|6vT4%Z&4-tmvVBdzdIQ?cZ*9t%8x9g0?eTQj-$18vS&pJzX)27Op0D=kE_^13+ z6O2Bt|13UtK8}jrpTU+j-9fGO5g5@tmhJjxMw;QDkgfJPmJ!f2D&b!X3~v*JOZT@$ z2XsV!PV*+*X2W%;v~u7doZrSU$K>IQqXe_-+g)Wsayaqf{v?jMwF`=5Uq01%I(r!-Eii%2>kNgXtcbbkna20> zF#sReC(8kr+MYP+46{O(TE!F0<3Zh(EoZ%u-LDT~m$7~z z+D(#H&l&^Pd?Z-T3;a)+qV6<;tq!AU6kS+bP|+W2Dt6e`l<6_7LRf z{Z5?M+68WQkC7h#oB~nC#A9gREf%WN#Dl8sT&7=Rp*rn*{=Tb=GmW}nw=Of$dfZz0 zba6Pg|1k`IZPpNe1+HP3!j0^=$tRfoyQV899B$%5RyK&eBn3?FbVE`)PazWC3^pN2 z#Yr?&55JTIG0jRAL+2d20UaD#z{dGHEXeGGOqX^LI)tcW{Tcmmc~BSO{In4aQz2tY z2qxvvafRa}vbKFjy{H#G0F-xlsdK<|Na&x-#!Ahyub}*BA}F*B(L2>>)I>B;(~6yb-UbCS@I+d0CoXH3m{o$#R}KHfc=MNB0rL zt|#lnh(1k?^xdp_TtQ>IM~VIKc7@`i!Kf-{qnPqn+s~iDfL%{ z+_GTlw;#zpiNN3T<9l!?1;?DqQc_oY1fw?PLh51>uIWt%mtj50?AlL3H=J0Nxoj1F zJh&yiaZE#pMk$2iTKT5kmm?ds1Y$7}^HO2yW-DC6uf^q0bH&Glyrg#mKu*aG;x$|a zy~QO&L{0i1iUX zw$_NtQXR$Pz3N28yEn|8#|0IFw4^gBIOc*7lgV~^(H;S{%^7Op%$XdD;Y@e$!)=L{ z?R}^RcP!mlk+CWd9(~)-Fd6c1V?r>kxf5eYRrw3id#c4)ha9o@b$1T(Ccy&bJ4P2(XRB788EPZLl6p5%cZK`@v7cx80TUZH>LOL1BE z9Py2f4!*qjh-`RHWC_dt`ZGnBZE!rx2wc|ZgC`7t)Q$s$4(}pR#GY8Zq{SS!KOKj{ zw;tzx?PR|qe^SBf_iVnjGF4GUVwm^F*_z7#kdXA4F# z&sZIr`gNv$e+cSB7J&Vg2}1vYhmcC+30&S|5T2@$goIb8dE3kYXdX6^VXDbHjhto* z!IZ>V@E)oPA=AE6oS-pNboTegljav7mt92EKQRSLwYRfPveX2K8fns5-1g1h;67on zaK6YNxdr><<_1$-HYyqoob-qv{dpnrBI>~~i85vm!F;vjc(wQKh2IG;L>=#|!nn*x z%&q##j5IBur+}VU7>PPRGOr_uCwX3l?9NquFg%;40i6kIfE8Puxm)>pflI zd}TFk9&iHnB{z+{I+qa4z8K(RZrX3jgWHV1h;+Gb%9+=T&t8>fq1HcBEO{vW++=#gN~Lq`2Q^RkL|d zy~!u}1EW`=zhAC#9WE{v++L@mE$Teyxw@Os@7@Sfoj-vtk-sPTZF~vlcajM|f5$7X zZdtkb8pomyVaKu8oK7%ak65s{#IdN8`gLm99A~q*_UFpk^y<<)EeLpK&h46kxj5bK zLc4AExGRJ2h{h+CylRv=!@QLPs1SnbdD4)NuI-7c&OQ^{^MlaOO+nbvyDbzY=Ye_H z5jMRVP*x3QTEv`T;X@Xx(;?YWX%V79!*sYi*q0kSwVt>Ax)R2!`G}K-B=Ec1bZ3|n zS*spNFqW6v@jCmaqNyci;{MHt(bOIri8-bQ>*7+`wUKo?3psS6ma@g0)R%*X>V4W| z2#L2I!u;*Wxj(H__}6JKVf&oA5qs~}@*>z8YuY0)(S#>BA&557G z?w%WP?g|Y^)s2IBE1cM5G0h0B#14VVtJhg9;P#BnQ{T-*r3(k(sI1#uU%di;V2`2L z>|JZPo)yRcQq(fcBzdefkzfM4d{?Su`k_gqpNclQ>Y(vU6`!;03Ut}ltv}=cE8a`@ zHJ~B=5)0Mo13kC>eGq4Q;Q>M=myue+SF6s&y&E<`w;6NzIL}$^rk$2=S~|hhJ}+11 zFAYUbGoOfk+6{)A!;V3~Gy~GqAi5u*agR=?d^U=ODJO>B)-s z*YamFwH*!BuOu}hx+s8RXo1*yju|dj9K|6SlaRThnvb#x#E1Xs<7cXZa^0I~hDniw z+aiLgR7_BoO*@EYwJH_ceGLWZXejk7u>ftWW8fUUn}zB$>MVS21T|02vNtph)$Ka> z!^89au$1F~N}km5c&Er#*L$Q&c9SZkvkC+H*_tU`$m%yC7WaeiR`zacXPGvG%P^ucLIHQgy z?P!L{!{?&o{y+H<$c*?pSm55IytKN_Y=$XtVVEX@IaU;^2von$HA1oI_-`Z>z)h*@ z+H?pf_J&SmI}B9~QQI7&EjO7mB`1Ka5g}5meil!l&vFmA(@GCr)afWRcgzqFxk68O z60Bw!qo$}Z^p{}BJMA~Y_;wH#DuWsoMT72(@820iF`p|%sn3SRDfwW{{b3&higDa^ z5A1#Ax&T!|`g!aT{XBMwl{J^R*CV?K8PXHsu=^7M*WThsm8b#5IFOr0FdCOzshEYm zQGAO1t8^HAPrOyy8fnBTr8D-nK)3wX=BP3`4^5+rjGnSOG|fFL)lb77Gh=bj>;$pf zSaZ&#N>%W3N1=`5Mad*; z3{Zc8sC$2z+qEnIoCq(=WY2qIq}g;g04m0*LzmJO;;92Sg)w_Kh%>k8iyGd=sCnQj z@ylWhfu5#p9Sb>(2*z&u7e)75+QJC?J7R9#OJVez5XrpPI3|e?aBTvk++c9I_Y|}j zl(JBLUvVD1-t7#FUYNo76I$ZSW4f?Bu${PK_fz5F=XA9HiK^IeN5M|hmE1HE+4Lru z#>Ohet0*hs>eM3fOxwM}tS6z8UC&v>1Sk!{$JN1zy>jv1t>PZ5+1yuAl3mgx;ncuJ z6nFTM(EU&j+*?qVb?nYzL9uQViu82k9vmUc333{cR3A0rD;Kyn`!MR$0jS*cGa~}i<-kS=<53PO0wrx*}3-4E>s8z&UC?yv>Ewy3C1=0YkN{5_MveobE zWhgW)Mg^;;E7boPqj5`uv9{s|EZN)|#ke;q^$Ut%&rdIgX_jx=bb|RxOzgDuf`x*u z`QneIylDThCvtr)BDZPeg-<$#g&j5FVH`;YBgyd6=Sr}QxC$y(^=QHSY5c&t5adUM z&F_~Qd_C{OFhw%Po?!kS3sm}X{=$fZd14zcL0tFp0n7W_SRiSBZ6w*C^9=EBrz`E{7(5{%vd~yj7^CNaJ zjINAXPB0s?rDX?gdAAgO+S@?=D@``$rN! zsndpG=s31n7Fkqp@D&C-#57lG zwqclgdSGL(k*hm&jr|(!Zg5aj63gwbrLYvea7N z-Toa5)r}_)7WU3`;apyBDu4-_WNBM)zem{>7MY ziltX1vGLzC<*P+RmJ~!9E1BhFu~r6)I-TO*{kPN0ulyCm=&OC_tB3dCT(#7=J*ORo z4W|}zuK8_*16L*sgDs0ViuoWX9&rS7=1x2QRj;$$g>RymQT+m`ZivBuqB|35NEuMC zA?k3c-M@}KX;gXtt)zktVw&!YK)3cyg5ZN8ipB;lp?BUE`23*+L2?4`XWj!*j3j3S zR|v)=QH6I8S4D;cMKShLB|4FQ3@@lLAm$7AVX@yCX06YZ_hDhIcuyD8(5Q1)Wv*x# z?SmHV@>8^a^?<(+bs1%yz9}xL4dx%~c4e4KQhp$n+f0HP)Y7O72^x&9E*8W?4t3Cj zKY(B45Xs160bFJVG37mt(?%$FK*C&Ec~6xoCrsvv5j#R*Q=7i(oF#exWSSo{vWQ@nV-_+fkC|HtcwaI9c3ChTdOxv)_h>>YgiY z!EF!`{S&j&RRiFY#|3HSyP`W1MB5yL|TGLiXG2mNEAU#(jOh zvUcen)Rd|eXZNm0wPsUrE8}jEU~(3=xzA^zI>n4A=?43T5kp$iBcS>XR?gIp*$koA5eZQidp%+-?)~rV+?AcOAPUMSM#b}|8xtaVl-L1Hy`X;zpc<_5{ zoET=QoUPRmOy3zhmFo|LqLkE3F>~oAI21ITyRd#F$p{X^YfH=|@ibH~+g*t)cb;Y# zs zLu}nkIP;k(i5xC4MVC3c2DM{Nu-~>l_}PzD$hEwbpE&*??(aJi@6W!&i+Ldo<06OZ zDv7OB4uz+VeP+BIjqiU$oOj+oj*>79N%+L-Z_?tEt7~RbQK(JTE?vPsWU9a z#E$HWjd#w%DTQ-U$9c8<^^Y6z;Plb>^G|IdfBgZ5iIPKgZGt&hh86kqEm6Ra>!KRW z0E?Itl4q-_kooBfGu3X&CDrupRpg%^#H{uIw`^+%G11gJZ;U@U%tJ}3A9(NYHn?@G z5!hm^h0y<}1H*KXPt%!T@=gUSa$o=AnyapfvzHRjIx$Tu$eBQj_n9z0y$sBUkPg&E zvWAze6d$}_B-IbHq=u-5rj4zKpqzY|Z#EP)J<|{Z4(MauBLi^A{eD8y$e9ciBx8CI zOc$ptMb8#LuKj~F(W0#ZY`&B!c`PRysKum&I{q_z1SrO7S~kqgEnwTRsXNd5Eq>zq zZHL4Rtvb#9>p-Bht%R%`UW zRFaIxSVO>s0!SV9j|na*##a3SS;SSuFf@&-S2~FG%6X!5!x^sYY~m?dmnnSNmML8P zJrKF&YyygzC)aE&3C6`sll%K98Qw4*6$zm_{ZNlq~0n*xawxku24s#Y%gYVz<5Vf#` zDesM@+yNJq2`X>;f_hXc8dsVo^jz`^Vlp0Z6Wgp5^h)}m*i8da)`EWwLx=rH0JWH4 z(hKSpn(ej-=YA)NHoaaFCz$z?StKc@RPzv3@EFeMjAsroEt(kxpMfXNougd}LKUvI%I(`3T*cEmU)xO!oZTP9r9be^)`<{z}f5KU= z`Qr_RyRpa<}5KmoGNy?lZNP)U)v=TV2w6_ zE(??$nIpZbvXVkKVN#P>8i5ZllDCkmKKxj-f>wOtJige0QGb zcicUToMxZK3*CF-7c*SY{iq85+Q%|*yzav=+T`m=ej9IsDLC(|RQu*Hlq^pWM_;}# zo{#$qZp2S5_7;)w-cE)7l|5NTkgh9d1abX|oTtth`r4}t6)q=H$CqKTn!m z4)OfCd%1Av_g03vC_m6a1Y>r;M%m~4E+OpnCDD9(n3%bE0zT^I$##0hVlwi(3`5P= z5@yXp%}ny&-GMVNrb3^sgM>4eLQ&$OlNfpo$D=-8LbZORxM)NR#5D03;p)Pc*Hf2xD!Wd;_7u8h?FPH`Lxt143i)yg=YxHdA$X1w{d__v@l*w@=+149Xf{X zJw7mT5|zZ4M+A|Xs9NT5Nf$b4U#o_Qb;rQ5pQSKMa}C-XuomA)GsN4jM4^z$cllXE zmqN!Gf7t&(Wq!L! z@|#9*>y*U&Y}9_fg`&aP5MO32e0Dj*Io>ScAN)Bbn0`p*f`fI1$~#wuBhCIiJ@K2-fu~c;@R-lyv}KJ;n77aZtbCVLcfN;{9D!Q9L4M)uTGNRJR}(JpW1x>vm4x- zK^H`E!~^u@K{W0@vJ-jXKZF_~fnnxEkX>Frr`cOzUrae9*a)Cr`T;fV@PeVoHz@mt zrtw{E4nxU@&nWzEZ+`ryj)-FJ%TZ?q!Ib9xR+f&@L9NnZ56l*x9HpWZk}-<&hW2pPt`~*u6)HzGd6^vwL5# z(;Spz=sJQis(G)x^xF!B1fLVDyo=$&@twH$rvXr&mkvc|4}kmF8%zf0?B@!}$MRSa zlE%;xMml2m5YpS(=fT-~?&6<12=MKBzHlkyFyFc2Hp3XmRrOC4lT)c|*J>G>R}d@O zSN%a@A?|qjNi8sHeF>VUu4O~AbP%&FA6TuEF57yTqJ$f_hM|EI4DjcX(cHHENBNL* zJ@K%6r_nd99KK7+RfeG-0utP|5X_#pMaqP$o~YHQvtqw7O<)>thL06>1#8z+&^yEi z=&&EfoVnf!=B!Hr+iQ=Z!7~fgn$CdAa#tLt`;seu63BnInuRYPoCl2$!uX1T{n&5w zQO2kzk%WDHx^hQ+07C7~im%>ZfHAQJFzv7@*g*d%9#B6H4IPum`(}{uPIX88 zb8fwI`MQ$~vrTTS7!XX>gil$fi~Ny-j}hNJ_lG<7Wn!;BL!n%81g?Ev3Dzs*sB=St zE+pS2UP5FXTRT1tj&wK1%YO!7n*noC?Uq;k$^l_GseBNAIyQ~>PCmgfW8^2zj9^s# zPFS~{z5^Zgix$81^MkC&DN=2P0*uO{!6`Tp9$F-^?Q!QnC}8yq;s{3;*4A}QgRB8v zahvE(SXXr&YW3hP|75KnPJ3mAe}}Xao)^nEt+R|7L@<|68!CQuvO_&=PKj63JYmg= zL(+qn)1gK?9@JJ{gv{HCP{dU;eHzu-Py^bg327koYKKcYkHacG7NRxB{_>f7*J1~A zEBu%&|ZGmk?0LLMyJm4oHxYcNy!9p+ZH#kWT~AkzEh14}uqj)vl*(L;q*u~rO2wH)Mu z#st%G&2`1d=cSzD(+Sb$YPS;bBIdJv}Ou`uaOMQ|3rsZfD!H{>FEy0|8Qbpwa9QV2`Qrz%b z6Dns((&#`tvS71-EZ1matHbDN=0xT(*)_$`jG%qaIgnA-I`;w?mJG@Qrn5<%m2Q_}Eqqw>G0`VoTlsDO zS*a;!EQ!Z%fO+C4&<;8Qv`0Wg_3>c^;1qwKS?l{;X%BB)TZy4jj@-%u2l4pkOTy26 z$5Dr?cH-6(uI#tjAv?gh5lq$?EpGYFK|-g`N5x5BvxS1qAyUq#nPkS}I=B%RURs3g zdzSnqFWrTj8AW7HDi@|qvx7;yzoS0EDMG}HEs#4TTPXkQE*#o95=~iuL0Eb)jGbnN ztnT(87#ph=MdHIng5QH9qPSgMyfe{PQn8x~ZjD4Z=JuTQK9|F4$6{8zZ#jD(iga(n zu4Sgsv8NZZ&{!e(R{R0Ww<}OslZG(&XBpR&e+&(8*1`0qIS?fzi8}oV=J%U2#r*O6 z1(V0&qS@VF;>r>`X=tz(Xj^21^^+2q{a_@xm==Jgk3>8oACl?SWVo{R8|vSoiSy~` zz@KyW7y9RRC{&^&o1j1nzDb@K=|F;id@?zvm&k)c=^GBrcEBRNsoXCa1&c7Ht$= z+*uiX@)69&o($tGpC*c6I=^ThTi5NV5clq|xWf0AxGSt&F#UNK6)h>2XK~3EtfuKa z=t*g;kso7xna$!JH?C4Hcl1FEYmea>kK5s(&lAz8eKGv7x)jQMi>yb`K#~lTOj7hBbJDbOYumjFgdhoyo*MwZO$I`Y%29+O&fw3NEb&~E3&^nM zB!9!C5c&?>$S`ln%Z6ZX5=^&Q-<7kvxC^^sw>G*5z5Pg{n$BPSj? z1T*lA5x@S+T*1LUSiE>*ir8zoAHLP2jJq!w>Oc};j#@r>C^^*tioviu_fyaVGC16}T@+hM+t@%SV6BBr-UFOQ_{=*S%vVRWjwIC_h@c%bbZw1i;DtFww= zR)+QB8+F(6V+RI`j(4UY_a#^Grf40YRdqT_;u3iS+(SPzoejk}H8p_S?QAgI07CjP zkt>j%3G`adcSDZrbcHQX-;?XPKrx(*X&{({IR^Z`K+miMp8#=2+bd{u_j7pK9!*jR zCX)CrSzs+?kXTLLi%TDYoQbc&+~F1o2}XkE--X^n~}Hu7h!nPA4<*5?cEjp5EeJ|yPtHACZzVsP7oogrX3@wMB;LlYSuqy3wlPo$7f z9%#L&3i2Vyf!M3n{IlmC$Zn7=?=dZtA6k7|Q3a}k=J<8Wc9}gnim8!5Ykvu*)=rC0 z8J)}h&^{!lw@yWwV`K2~t7cF>i@XJX$1@E5dNy=B4GEi{u^o~$@ffw?A1YAuhu+I3 z@`q-usGDyncFb%G zHG28bG%o_miCaHyeK(~BKuphv;F|TA8O``doDfef>keP_7}%wuruPcz{qnW*Q%va)4np$UBWhHr)v3M{|L4 z!eD1qz1L5SkMTz1Ho0TXm@Y70=MwZjvEsjsz~d|;+FRnSN-)}8m9V}d7#-Qz6JO3b z$(`vokq__O7nhEzKo4A&@FNz!VHhiULb5Nxyi7l%RBZ4@or4dE9=;YZYLX$IIoW_^ z1nRqi>1>$S&~QDl?sAzKp3|8^ZqykNLR|5BsfG(#zK`EpxEL44`oKp!YyN!gU_>8* zaq?+~5{%;x59NO2AQXGdSDd!DFL?aTgp%jIq2=KbC_Ouz>1=2bQsrF}LS@7y{tdCx zBi1YvmehlhDJgNM8ls@pv3#HXf%tKH3q7!8I46z5OAF>eNUxeAgNFr0J2I$DvPqJe&{38@tX$@4e%A zeZ6CN+2rmxZnZxjPG+X)X|m-f&4yr9w%S;KesU0PA?Ax-JBZT$!FRD={t$3K8UfDD zt03oBBDCzN25PPEa^@VdZ7qZ3uBkwLL-D5A16V(7B^u?B$1B$!!KKl|@snlU|Tyn9b%sii0!8le)t@r5|VA;bBIwN}~k#tX)Sx zb;nc)qNhOHqZ-Cd^x~fP?hh*XX(G^DaDU`rdSl*va(L8JG1AV1zHj0{9S3z~UccvY zjE;Jaz#TE8PMuLqZ{M9HP1+$DSUA96yF}H)w!L>qId|hZEtTNgrUD10_hUpflj&~XZ zmg}%9nDQBF!_zs&B=kDZ2sRIW%vXm!8L>=y@@}!@y}LpvXr;q;jeW)L;imwM+2oc_ z1sStNT~+r%%;`P4!kSs}$`N*3B!zPl`ENK=*@-szOhbiG?JqujQBZBrE`sx)l**+H8N2F;mpZ1R=$%$IZS2nl{?(X~$tqR(PP2Sp%0qQoFVJFM419Q!PEM{HFU_6Ro_N*Y zRnB?!md#sph%9lvL-y@D$1%s%rJ+c~+~3z#FlnR7^fNX{6Qb(Gb^nr7)>8&U{VeSI zp>0k{cq}*1GPrY(i<9IYL3Lk02(8tGZ*_HSq|iigKeAL>vOAIGyb2;q_RW*RCywLa z%?NzoU;veXn6%7J!nU~sS=708QnS2ctUxzJmAhpEFW%>Mt$~QyySQq|CbO6~R?-gbZUs)MU{{zAEoXXTFcXulf<#4x0yA%DYhXrx0EVx48pMaJ?BQ%YBIH>w!#I`U^a) zO^MC5k7AhqN#R!8<;1v38 z{>R_VJC?ZkZ1yWKM=?-;-_vgQ_VfxCz?=rAYWZ)_AhkiSfdSE-~W`{qDt zYzpxs_n~3p1<-2S90Ep5yw=Gb{I8#d7naT8+sfl&MPvd=cS)p!%gw0w;l1Si{%p}v zs)EH6d^u*fx=mDpn4YR&<@;tKESD{jCJ2R6k*Oxl{+mzM7nOm{&2yl&qB~gS6mlyt zIq~Qnj&;u1zVPy<4m&Y(Khd;Lq|dt#q)GFRll>2miQ_-rhH=swj=65=x1*D#!7P9( z8(;8oh5GsDz}DCkb*{auK;-9~36D{opjr5dAorm05s3=6Sl zM4k9w{(R|8^Exs3;c428wcr?8XH&2}mG6zx(>u+lzLV`=^O}wQqX|r~t`;ok_Lk(2 z#rcI~=`}sp@}0HR60O1BcCaID)K6#~#AKQG6g!XJB95LjPx^Xn9vQeGi*{+H4OxA# z(u89pa`ArstWS`Zk^yZ{d#mmK7M!Fj5CHb9>*+k9zfTiM{uoAgC0~ZNWVaV+O1Bq$ zW*nn_LhB>OYKFczHs)^r+wOCvLy?Ec@ByiG+2RHw50_hx%EzU(N{rQTksz+5knc1< ze9ql2zXm!LT5MWUjIiPix{$&o7UStJTt>V7>(d-qrE(?51gM|TJ>-jaUSB*s%1$_b zXSU>&(u9mmO`@t&ZE%k*<3GQr^WLB-$f_zGiCy0ONil7}j6E z3w$vRE(yGv6fTu5><-(tCyM*@8E4eiQYCYgqFmmvVdV&=X|LUo~blVg_})sa*VKG5HPCB$Jm-$ri62)Td)d zs3<=HFAlqLsg*n=Yxsroj6g2ixegaW8JI}Y9`vOB9(oDamsyF2^DXGm$#rD)n%3f9 zn#D2Q)%lGpVup%Gl+UyL$mHcyq(hn`VD)%Insiwg8ipN$j(-O89)Ya0(XiCnN|42rZ5z}J<1(a+{AmtAYc{~*&9N1$9bsyT3%O6gQ z;V!{+YR|vmp=>4IQ2KGqKy`4t6ftfOKIA`|6-qujPL!H0nh$q+8cN+doA51IW($Xa ztW}q5oo^ogB8(p4CDpt!S#ZXr4YiF5qjT+DNcp<6;=9HuDhl1{a7^8c{SI=B{IJ10 zZ7pJ)dhd2vuMQ+G}1&byDezT zax{$xx2x>7WMPEzH04TXwtx!_TcE|=@laCW^0HV-+-?b~JTpxfxP zFuz3GfFnO7W^?u@G{1xU}7% z8}tc1uUgT=2|TQ@4S}+2uQsR9hPs9qAp^wg@K+O++t~3)^3H+{Cl5f&7N$h^t~Oh6 zv>ol#swds`ra!xq_yYHT_aOrjgQcNl#B5#ITu9LBD>PghCOJ&5A=eWxss8>R1wl=2 zLUQ#7o)pR$`}*r(6Mu(eWZ~GmM~kI*3U^8MyS@IMO3)KtnnWuXSAf*%SO^g_Mb*?&D{we^1FHM~;8PJYM$QQITHJv$2ejD76nCI| z7ipk-8)?t6O~Sq>hU`;!Bgt&iFyZc1dlDEq6XerSwKypUF;~y^6wW<~5g+v=lF5b? z#bTDODjRN%b!Zj1+I&OB{aJns$Qc257G z{t37*zXvX^*STx2(+7VT-{CVkapxI}+7y_-#&eTYToJ++&DuulMy!^uZnGfrY4)h~ z0!4@^ZrxoNcYh%J;pHH$D&NIQJwsLN5=Nt8Ccd2CW1D;GZb-QH5KO#_xshgXxC%P| zX28=;CB!o=fwc~Hhw(mNSm#;8SnktKr0b_r_Bv@VKg}L>oK}h$RnJaBF3=7Z5P#Z}^zrP$Vne=y)~Z%y z_T>bzB3CKwEuT!X+G|nyG;&=4!@;MBv5wUe)`a=7^Fj8~zYU!v>g=ZaZ}L~-wcs+; zZn*>Pj@$lkMj)@>jeC>^gZxCaJ?=M>l{LKv3uKLYI7R0 z)PXe2zb4*o`WdwU?&X*p>fp8!F?AOG9h>XKvIoDcr6srWr1%~R2ApZD-``niL&j#&7L)l-8-Q=HfBqj4~ z=-wemhzGvj;@jfDMu$lpV~0-x#26sP{icQ(@N*ukYv?Ok)_6!K7X{GSYaS4jIXH!H zpAF4stbr1ZMy&lIP<#QmsxsOD95J<}>aS?n?- z37k@fvhP<7NMC|RfVEwz@0eXA{QXZ+?7bWAPpRWSPc!vJvqH?V(FJaaqks#savB38Df@2lP_zb_yr~LCviRs zx5L;Zd;k;MO!&(%w>kI*(tHbH*ohwOK#?eP{ZPx~&$`y_Nz4Z=Hor|XX?~kuOvbFo zkOSX0PKZeu)K-k$I91tuUvDY6tvBh^?gX`*_>=FG_Sm50!EMRuw|rDyz6E5dm3!$8 zn4$YjoV7Yiu+AOEij(cw`xP^Uhjm@q;ePr|+_Z;dvebpHafq3Cwyn4^qKjbe*h^Zr z{4)`7#e_0I2lO0Jf%2U}gb}W+L^+TA^OSFBUW8nC9hTJN6W=9C@$c<3ap|>j;?AjG z6n<^=S@?{(f_=(EQ9g~HI`No}m@WUBh&D;*1nmo^(w4Ae#K-0cZCk3vGXg){K$6!> z$-_ap>D7CAIoGNOyt@i9xea7Zj6W>s^j6d`=pz;!^MU&VACsdKHVcsl_i;=-KGQI= zS%4Tv&o4^-wXMl?6BFr&e=$tj6;3~C{X!379J%t0``?Vf$tMzHxDtLt=Y1=Hg8d1S z`M3uD1)dB{`Jd1$bd<=t86wd|l$K1~yKaO;7XyVI(adtVMAs{?vSJIj1Y zUB_K?fT1n#5yf0Z>9(}=sxlH_W@ zL-i4{{dkW+7Lm)!`^_asxkOR6%`u650)0w%(TLzq#PoEW7*w=}w!QlmObfI{jSapW zBQHh8(?lR9*Z)%fn#^$Wv13FW>(G7Mu*t1TeyTL^4yZ-b#m1{c6&w*F2M(vrZa z5+6dC5!BV`(5V6YX_FC?$n8nT#S^%ScW-WYy1i_fXdacoF|YA=gP3^4T)xa4Vm<_u z5fAjGCG~r7r`H{6s)rS%ZH$19TGKEr#78EE>Z1>I&Wh{YPFB?VV#erVt-Ch)F@rkH;p8oxwh2l1E2LG}!?C(nhGh77YeH zY@ynu_ybN4a969yI08Vf!$}i0V1yUVVFM+VG9A_{T0)_b8mjJ(7xxHE^%jmXrJ`VAgs)?-6L* zJ>h!_@4jh9vquBnb8{`3|MRW5DRmPS2MKh%aVwT)y@z9tVsMM6$wN%rG?n81$^PU` zd|PP)`lWj}98!6rF0FnA?u)|3n=(c&4OtmRa-Un*LR>6}0+@zRwdoVvh@#`CIe4kOSrMFkO2 z55Pnh^P8v_P_Pc|+ECzcb@K^W`DDV1UHS0y`U!|0L`m@1wrr=JAT0eUmhXa@T?^749*MieI9 zzQZvI9nXQ{_(Dn1dZBc$^Iu`dhfb^!eluPC=s5IapR7*`GG?YaR4+%2^AkOx&e88; z*xFVSIqXHe=Sixe71rQUc>^NmednzRjzOJ`tIb_7L0yzQ74gv4QhI3HLn`TfSjhg< zlYP-S&Ga9hX024+*z6fsIOc}>wN{Ooel?~-+~?)u&4QNFn!MMfxazcO_?AIfhrR?s z{l0Uxo#ww9Fv>3l%@;+Wmxi+H_#~LBwU%TDPM2PJ8Y)P!E<0ZPlD*$Ik>*Mr!FX zkWbSS11Nm0)gdPId2gZJ(Q0w{&*swb#mAX@zvHSy`2)Dar58@z72Qta!{zeMVp*Id zD&Q8c-z;Nc1T*ptmQwCSv575~5#R7YX#=|Wa*R40{EnD4dS*h$B2)IY zb2I7Uu@7v>uxM34OM5=9Q2o3HJd%S@oK(TbvE}^6E93^Q5m^S?*VT|asflc5L}v(# zu$9JtcVgNNX2f}YFKK)6D1Mp?Sbo3&O5-d()B552VZmgk_|Zgi&eD=B(t=eEcY)_O zMQuSv(=%xHez7WND)30aeYbiFK3QC`?lQjx z+~=WweOg;c5B@Fmy5J|8r&`dmB^@E%=V89-*;c~cZRW6W!UQT`w43;Z#?y2}Ow8cXLKM3%v=FS!msaUizMkxSq<8+WgNx(}}6NxtRR(YI9b zKL4PwYVA~N{&@$SPWd9xzqgcMvTs3o*-nm0S7VG2Q;>36L3Cr71M17JxAK$vRYXdo zaiLSgw_D(*QbE{_Z^RYX>NHfKlTzz)D2qM;<<=GC$sj*v=hEe*Q*9vq<5>%)mnrev zctw0W_cP4xxR+z(mo%QnLjG=&zB-OM8q1D0d}R~2-;>Ul|3?A~vWcF{J@CNHEc4lC zVlpESv_sL<l0?S}YDo`U^Mr2XV|3 zb$(-mnAY#o@(-m)Fspu_+4b~G($M|&a4TL#G|NzpiskOn7jz---X+i+oXIzot@pVA zhIfo%_Q4zC%j`tbd+TA^FRd@_y*HNhYrG;(eESZ%IQwu+TQx?3m`;NOm7NL#*x6I> zS^HB_lKF`dv`TT5i<9K()djl-LW`$2_@*U~%ay1pEP&L|39#mnG0XiJNLnq5qQ1!k z=+`@k$n@=%;(ulj!Qt|Jjo!&i5u^XAnrm*S+Ye<$OpAOfZYs&21)tnWZg6i_@83_V zcd?Vs#x^5X`18bP+G51${?ryj)*KZpr02{%-H4o?bdJ6r+)jNO>=8H(%YpAUXlYcG z$uF9R?Q33Dhd5w=w$}*}-?~WhM`#UXLQy9+H=wUHcWrNuQQ{4am^FyG+OnDW#r2BP zuxAx(lcYg@UCE%vS&g_)8fVyPK90kQTs34=e-74vt3*GQ8gRC{1z%h1urbp_L0KBc zyt)OmH|ghvuIX0H$6x|$_OXJ=rx}d}V#I7kOnw&)(Z%$&;@6r=W;p2%v%8s0+XS=( zdGkd?kqDX{7+UAy+Y<->=Y>~-N6W|1JGK~XbxXvkK~_TLH|$4G+9i&EI!8DeV#-|G zgbLHTP2-qPYK$LZ#Q1vU>|V*jk!6pV@3XUH;p?L`^N}vNjJOAGM>D}8Q{?nGmFJ9L9>*Bqh^CeQW|OD*eGmi`9+jZ6RUO~4Mxl?qZ;K9 zmu94CzcMz)!ILD$p?WT?4bBl1p-A~KWMwOP@jm+YL2zQY4HI1yUPb9 zlE1n9qR9^a$MpP#{uNDW?)P}by8t4#3)iOe0>_iEJqHwFP^pkHx@y19G{nq(5T@Lh z>PxB=#jG%+Gt5woq04)tN_BA}U%y+Si}4!H5sY5ghueaN8sQxnmr^!alljp9=;E|!^w{)G299&8Et^E#1J==l{ zngM-P-~vwcxs}JUH>z5IywgioKgcE3zgCsd`j#IRf;*B`)#t^vPyDIl=yJGttVEd| zJd4Pf{pyYfLrm)2?fI#vB2oQ(g>8yF58wW{k+{9x(XSIHi_6WSq5ce?UX?Qf*=tCa zjChRAg!L&+Xb;m+>Uwq}30ht)dftkmbN+OpgA-ROf8u@v88cp;-&{wG^PUNgo%e>5 zUbiK7;O08m?vNz;zUa;82&PUS$>TIxc|T;MF31`veN?Nsp&B2ywW4}s_s|%x9c1>1 z&tlq}!&K9MFm2y-h8Tu!rZVP#bT%c3(a&~P3~9ZGTYZTN=oAx`ns!-wC*W+hYU$b-OwW9RH+_U2E6;T{> zU#+vLL`;X^ql&AyR*@+SbJ(s;TR@}b7S*@ILwH7z*DV^>uf*UM&9g>0Ed}kdIFg0B z&ba1j(70WLhBS_$E8g!S{#GAE4P8IFy*1F>SDI|z{x z#;Rd3^-+xK`YZ*SXPt+*J7;;vLmvFkXdcSv2;_AkGG?m%bLbq?nYxF0k>w4|*@atk z=!j-RXy4{-*oZB@95Yaj`Ggpte-&<>b;y^>bk^CS3q%B+Rn783VFhLcI9<;#n%uu} z|D4KIL-JPn*^*`F%xE$RHP?bw5bi#R4kjcGtksC7HR zb=NUr=bMu(E2NqjufC{)b`D?yH?YI;0t{}Z^EOfR$O4`b$e4y}r{HG&2I=OnRg&3S zEpjc~fCZWBNPqETHlQ7QIHxBu`SeNHuCCcM%R)O{&u)U_(UXd(ekrWwtGy(Dk)&E_ zXb!Tky4%Lj+|o$C1-y^olC1)ab`ay&BLlX40cpz@dnv{EykIi9D;u=DkU8EcWZp6T z*`kFf1sU^1-TH2Wn3E^Xg%dmU#oJm(nQHzS^4U8>HTpy4hiGR$v!=+Pr9n`8a`3P3t&l32*{hReQVQ^~pLlSvGM{3q) zAdK`4CZmq8X6yX>lAVDU$xknoXCY>YIvg}X%($YyLPYEK%xhIVi>(h)rvEykT9iE) z_u}S5gnu>E4vvCXi_yo%;SM(RufyiN2k`asCfHzJLHuu|vJ-SUsVdzdwfe5hhBj+Q z{GKe8^6l^O@20z2XVVWc7y6nDM{6kiofXRluBc+h{ex65QZPAxtpr&$WY*c6_Xq+^ z)H}U2EpG7LtJBBrBmd^iXMHY2LA7Z|!JG^H<+asv)2rn2Ik;%?mVC)#3YEiX!SsebU5PcGM@EIh2OBn|XAcQZ zn{DKnOf|*@G08*TDi-~YWbGe@vi7q2~b>{Y|!r~@~MbC z&ol7m!*!y$ua%fp-=FmQy^$)`oP$eK4arxdy<%}#BV5c1<``3a5nx6z6){(aMJw`7 z9%PpO`&gC3d8wtd9lLpa1F6o$m$A!5csA6-bPfPmsQUu4WQRg@F5M%rBvE%&T(X4}KAbY@KCDW^C!8B|Z z@oIdimh)t4LEbU+ynTgE)?Q^eN|FoP%bLTOveRNo%^9+0WgMOI*O!q5t%c)VqTt2`o$7yTn6sWy;9nylcK!4Li2wi&zwtseqf1Qk&_Ka{6 z@i~yb=w?no9E~BRKTnEY`cJ?EFFr)hrJIR-dEOPbxV^UcW2vSXtWVHMrzu^V7(41hSUnSmQYM;!(ArZ81oa zKZ;h4#L4r!xVn{-v^tVVGR8=)8j3^A?R|O5t*O?c^{g#y=FU0fivI=rW%@Ck@xW<2 zyrJVluHZr%Y(KQVz;!lGb85jP^*S^QHD*QQ^M#R*e=zw|G@wxk4SON_Sbt$Y<<(5a z98l*s#}K2Ha!9$;cckLltqpAJ^Q+`V*OPSQoDyOa`iOTtT#T>rl4?X*E@%&b2=nl9 znzpV8J5-(6aCS#wfA3D6Ckhgxb^S0fC7}ebqI%e}0~DVoFnZ6E}e! zYkNQ#3KvM+s&|5S;9J2q#f)QA`18c?<|1O+?+sM?|9vm?a#+c7!+psgx8w9i#yg_j z1!rz{97ER;G-E*1x#|k^Pr*sAP@^)a7B9m$jk8kjAq`elIFxnmI!0Kzc%3+>@RW46 zha_lkIV;Mi$yZ061&GNoo1$E4VnG%}EoC<|P(fUMfEw97C9*iFp*$4y>Y%e%xRz$mF)!7aV#LH> zu~h2BOeHms7qGa6y|9P2gFdJ$A+nQ&ZOSIxu)rW_Q8|q8T#pF|-g)SpB+n5TKQm_C z9^ZkVcSee_f}hf7%M%zr_?Png)XLmVTK-D;Gz{N2nBSBk=Fh#h%A{f56+ zG<5Nz8~fiQ_5IS|*r2iCq{`#kL0Oz6N1d{W-1W*u=#$wB#!R=O-GeQJ4>8v z+75)1>84`%$7n&u%v7gQ&k)mPacI78ll`Q0{tRZ~u1zx58quRj<#4&KfxnmQt@(ev-w8)y>}i|7Y!0Uw%HOHb3l!$ zMU3ymsJwPtW68d>$*g_O5U{b1gxHJEh~>UmC>_;}FA9+RH#!+jQ4|{sZU>%1?UXYx ztj%kf)-;eVZ#k4C?O7z2uZX654tJn-oBN7~72zC1)feq6Vlo$Ocl0qlNM^f@Wq*4Y zkhp#zJzeyQG!(=@=}}AWd2flEWG9vDLdCL!sQ9je+C`_JX=oeT=SnDj^Kl)yTXjHm zXc0%#(=6%5UVh@5RtX&QOx=z8i^w#J4C`IZAe%0JHl|X=189rFBcmka@qv zd+`fthUozMI(_??z5MWOa9__YJges{t4L zlkl%~4wxUGC6D#uR;!w$^&;zZKPy;R6hzX+@m<8c3mV#&T`!s19v zcB0ch(zBaNbtCd2S3ksUc*RviGN$MqRyREEfLCe_57kB8xss?mTN;pkSJ3LH&*JrT zq<(94q!j<&?DyQJ98;vmI3Ol0>4_qGfq8z_+1{+h@<=k|SdMC%R}MZp?}FR6I==Zr zzGwx@9)okcVvygSa{tD@PKWKgyjJ>XFh_WaJ5~;K?I@kv<}5fUdN6};YX$i<M)o4m${;A!uT+VpKz4a%|FjVg934@`Fo;$ z+@Ez`w}@o@jFMLW#*K`KnXeAjXCh{Qnt@#6`JOi)tnoZ;8bueXj80pb$347S{HmT|`Rq}N2&Z_?FNEVKAmM$GM z;HT+`#S{!~-4W9-;kRP`TUYigK%ag0Sj1p)fNJ-LPo#G06>xR9$9J!KB;5pgDnf3o z%o|z=Ng2*iXy1=~QQ(^QS7~r{x-I*ne^b;u9V~o(QZ1%CU*ni#>XF}7h*3=aqu3v@ zgV~vPU=N)}<;Q64Pz8THMYJDZ2d@L@W;xawG(9iz4P}2@6hnqbK3trq525KH!dB^v zLK3>s4I7()-l5z1FV<-)2G8pVvCH~U`JydQV>Tn^zqt2`56Abj))(3`x5PDUS=)iC z8r-?!_4l@Vb=c$X;8v0Y>(5-`nY5n9S=c(~CDDi~P^#8G5#}e4pq?)lK!f39VVsAl zXuPxnT19ws%vd$X2QgaxOB4fL53x~3It(7(Wv!l^k(iAG|J^t^pbKn{CYJ6p!0Lb! ztlTh5=$sCdLW)SYak1j0vK8d*&TX{m;2Y4z5nBnWY6bN`ZA>zy|&tySST)v;|#jd1NBiH(_1|%ABmXkW4#oi^A9rD@y%I%@mk3e zTSLVi`wH^Br@WqOt91vMUY!M-{m%0x4)P4Ua)B%6er%?%rSuwi1!_cJ)G!3S(%F{8_md}`lpZ~|2y?9 zhl8y36`*Y$aIRg8m9s;n>RJ%Z(=(>=&e6p4O}ZHPUWZz}{EuUb)M->IVm#l+<=Yr; zWdjN|nCEXNX-J|MeI^KkOFfE{5Hq6ZQZ${t&L_RB9^pi5=^ZpVSq+B^o3r!1V#rdm zjhcTkq)VEIk;E|%MUU~nKhC^@q6>J$#EN)1_3<{ENi%{V%wPg`oRb~nk%EfM?WKL)$5 zrX2HDjZq@T#dNaLO{WVBU-?^{bYd;bXm^UveOD-W1ma}zfNaovcbwOuNuW9-$m@U; z5{J^DIlefig_)7!C!MM4;diKfFom4GS1)F7&4HRuJtcBa5_;lygTZYfVrKQ7u59ki zL>KlG$H+uMcyykkxf6-lUx6h$93#czy*%=}d3?_QOFRZ$g7b6~b9a3xIIgmmlQ(^$rE^Ln-2xY%YaRL2FXwa z*3a6pcDbdB)l)Lr^EzGO>ZNhQ>ZBIzLcf!W{h`rJzGx=+6hO=i#0;9-NtrVvOi1kd zQT#UbDw#a|Bz?2BFOjDrvaoQHXK7*Zj6S8-=VB@5GF2p5)fpWSZ{bLgYE=1{*X4 z?o|kyt;@hb`xu`ol&k8pI4Rs9U3!)QtV@(D`&P6|*!=5{7#4(ewg4HJA-4E;;KrFY&5fRbNSB1{86{( zkZX3;V%t|KispH~^jl~P;(jL^vj1)YO9OS{vFp$V=-mTbtk}Yn7oknM|3O^(>?X`V zY%TuzaYXsC#bX$6mZwmRZ7n8grYYsqnC;>i9mGuP7?OX!sXs9_s1jGNYe`;q|BpH> zHz!#dr(o9|7gXJ0f9+cZ%rSPtO700RiEsFN0sL7v$U0|5!^&q0dSr|^u)Q6PHXRP1 zK7pu_o-D{1h59u5h`DWNn6Gd-K*BXD#4SH?^l(^5>O5=*Njq{FM#P!&aqO(OPheG0 z7nmM;h>I*Ls=%lZv(Xu9}71&;0h(%E%fV%>(K6LSFvK}L?UD2a49NYv>u2_ z@^;BvfVG#Dk@rQngBM7*15xndLjYO-D+;D2cjU{2<#Fsc(Ji5DOB65Or#;LLidWk{|-=xa6MWyeYx0LH-uw$sTbB-B4*6B-40`l<4K43n_|wm)`EMY zLRzvYjJUUmf>Lu+aJ#Cu1??Ez5nP@`b1N{p-2LBPV_MKUl16{rMlzGr#AsC%-Fc!H zomqH7>?I{~On`ddnk`~Job2J4(KU*k-hD+}*zYpQpRKQY(lUxP42y@2D_wZ;zRdGE zEI;Z1?jI9)UBI>S1e~63LJc1T(ZRlZNsqZq+&VUd+Ur}za^I`MEt%xb81bo^ya8ee6I6B7@R!aFG{=|})^$Dg3n`wM(3LKgUY zU+1>eK$Ao=?0k;O>{uc$bi!vD#s#uIO~%O6s|h`CaEv=9g-`uT;nDK3 z($^sdB=w*X)0<}~?M*k7+BNUM>=NdYPOePwQfCB95%b8wS7=Q8ph96cmveR@oUFc8A=Q9s^yniMm97y2?sjG8Z~6-IX{^7^UGAZ_VOVn-q*mO^&8wQe-8UM=ng*_-C+k`;WxBAe`C1N zgX~wemfCMF$Tw1GvypCfZ0YuOBqF;BDP2AYWXv%2+jAFUv^QN+ysD`dt&WC^N775g zYim!aZqDCLM{%7Eoh~qxHD*sur~-t8DUJUX30uQGN}D^}{$ zF^<*fZy;lIqNOTv50f$N)K&FR#AL24RE*K?%^r9Mi<8F1llLx3s-ZVd63yQ#Zl^1o zHAY0?n-pg}5dq?^DNV(b=L1zg4#km@PnW?->mFnmu7V)@V#v|LVm?mf%flCI zag@GwX9MEBf1NrzQLH;VnfMGN{Kv7&F^TO9LS9YZH0=Kjy;ip`6C*o?{k zVleI;zCYDZb@8V&dJ0~LtiLyat|Xv;{}MbcxXy0@vN;#t^zIBh{R4y$(+&!2qn`A| zMm-oc>4l?f`&h+zWiK%9HGs+&EkvD0okmQ=vKNYjC&Jm&Q#(cGJWi?o*m)An zdIvA|@8*~l>eJ*PrcLs5g?{*9*5b=Hu_aEjwmEfFnwb?Z*gV6Pl&h4mHtQFO+pkVM zOf2s6aco+7m9&VMAr4DhNlI?+pgVrtf~}2{i9T-f8Pcea+FQ&B@HG1B??#1~#of~s zeP$)G?|0XVOTTTGR(5Gg+R|f6%`zPAMdu_s^eb^0m;u_l>cm6d6|pv{oaE@u7Hit1 zlC#FTH}oZqMa1eQi;i?N2c*#hSn zI`hvcrCe2)FIs&=FxcEL0ce0wT7BgXtwb=0ZHl=q@AZh9%AE`}6=pRbNG? ze=i|$J7&^&3plAST0LTZPPvi4-r0b?nK4V8)@d?JIDVSC+#evw!xyd#v-v6)*@jxv z9Nqa4lZNWZw56wDerQj&90rk`6>aDd~{j4ZX16AxKxmF$uO@pH}b;aEPYoc z3i2}H_4tdITM_a;0y*)JyHT5$z6NcK$5g#_n2XbSVZrrU_9kixdpajwXw4eMjlAapENV$;>YA80|B#6Y+?|oA)jbU%W=uuQ`0@mI)7_=n8|1+^g!1n3Bj%PGz%3_i0xld2xu?NoSPS z)i1Biw?AnfuMo5P>5F@fV=20}VrfWj55+-=0~Wm2Vm-h-f)~1E z$1!vF2%x%op5HkcZA6vb5`1o=* zd9%w_95DPKOFJJ(|Gth9v)77PBZB%T&qDRKNL z=v_VqS7yxSiHF;)$FRNWXee<#$rBHGZ`6|g6+}Ov8&$=05bEoei{Ygv^vSSJFfZeW zGGfXVLB@-fND_8ZBw>ovTU1zeJeY*BYlIa=`6FC1h?f zz`?S3t{Rf3SIq*W!O46c{i*d*_+vL$begz^F6qqRqt96JqKgBOF@Mw-Z8~BiZp?7( zvoevy_wFuso6(Et%JQ=3v3M@(DW~ zwU>B}ih!widT=jQd3D&FeXTgAB=;GwLq7@aMu%NEK*zbG$}T=uJdDMyaYs$*xNQf; zGtKvLjDSB+{BArD)3L`e$6pbLNcS@>#4w8`q}UDZ4V`w9tX{Fu(Q*Vg0dhJ0478eA zftOi4SEhJ*o`nB4_M%@m2h)3ofn-i6rRXzrKRsq`MN@a26^#zYbIeY4$73U6CaJ6) z=VyeF`)9r@FV5X1csvhWkVAE+&6l90Zy|r*$QNy8(F;f~lOSfS z32FYrnAw@)`kgDS=oP2-%+zlUNo-Lq*s7bw@rYS=nu(@@2v^B&4iU(<>C0F|n2x+ihP*vrNBJs9lG1lN}6YE_N4 z1t)Iti?$T)!K}V_l&q+Z6tiH7pzCkOdRRVZOYk#3&5m_>oGHksiB-QnGZC}*LA)aT zWDjwd-dN?o`B`K`Lb__sUPt2oUm@RF?4pMXJ8XIdRaWzhCU@B7ZKa2G6y$ocy|ia~ zfa1`%W~}k5uJkr&F){S)%(9Nga7?uNwU&pNas6`?58;xS*~41tGLDf+8K+fe{%$7~ zHrU|W_L6s_L!yL@yAqiR!0ywEV9cUU1{47aH*A-??YTC zS^#=m9)Udd{jc%@Dg7P7`aOIsXnSp!a!;>deeGwG!N<`WX~t3h-SkzLyKf_A^}wr& z1(QZIZTp+~6}=oe@`7kEmc-=Q*njWZX z?2#-up)X2M?_2P5 zEb;XY~^ufk9W6VmCa_3IjKHP zo&4RL6%{SN#<7?w`uSUGr;9ocjZ%2c62as>Zo9x*=Uu1YWS-d>w4@f{FYZ#4cSX>h zMPz-a9isg=O8zZfPXnIkLOgROj)9@#fJ<%Z!Nvm|W2pXaz9Z(`rXz~u+DUBe%;>zi zEBZ>ItwLF!kkMkp(NZvYbpfd5TT-I^|2iJBGiuls!L>m6zuDwm5yh)sRazh5$qZ2`Ezjve?Ud59Mbp_%b3lqAG#Hha; zb$+9b7}vJO3XOIL*w{ni4o)+Qq|nAbRMR9CJ06elCz%PUwtaEsj`+VBf$R)hdB+mM z0{@BnT~kQ5(>{82S7#bL=QvrmBwIXc(UrcH0y!oRA2xWJj)>_ud$;4zrGCuTY`MdN1Bu+yE`@ z1deG?pT+_)Zfh^)dHyhGQ=1US#edA1V3bN71_UT%FV&)$EbvQCV!!0r!WgO|4=G0UAK`Ex_j zhwMw#VK$8l$>#GA$rUlD)uFlqF^Ppk^7^irA}$Zv=GbIwA7UJTftrpLc>l(-%S9~R z72>n37SrAfJdM(ie2ewxLdfdbpM{;s5`IUwmE=!eXtB`Jqy@_y_?%__C}uLIL0uYh zMoc@CCXUY{h@+1X=ji31CA?UEoI36t#6^9zkMlrotjH6RX%2Z@(IxAl<^1M3mgmAW z3l(cRX0vr|HJS3`D4}?{22-$>V)xouj_HLzPpqd+LX1o5J%_Q?^Mrr1t~)xk-bhwV zPNiL4Nqg8t~j~2v{3BSj{uC%_)ulR@}*ft34J(>cU5+mensuJakW`l0m7}+dF%wQH?RVyZ@5bWHs_nS6d=rZ~7snO8ouH!)=*%3_)%yV=bHB$cZp+lm2v z`8Oru_*Y$&6?79AJsKw5`mM)P%xyWwmtaoCMM^$?JOx&mNVqpnE`s)D7i8627nuA^ zg$u05GjTZ`wNigH7%n+P^45}w)Q5;K@`mn*m)zzd_ts0i!-&noku9r{lWjU2X>2N3 z&oKoQ6D-FZCz#C>LM0=Nl7Pp=rCc+P04_fm$R znodK<;pC|!THHPwPf2`*A5!=`5cIiwRCqlo6g3X$j+V|lEI2OlVwmglM<9w|20NdS zxc4~=_OCn2b?@C>axYK~AAWKc8gbs+ zEnw4467(E8o^7D0&u#W@Q~38!EE~15yO#-Ts?1UKq7z6kIR@SYB?>lq;b=h8P}F8y zCDg1*XPEVJVN4dm*jJfKoX&)UecQ9RUzII__CZJ4jhCUIxO)nd`A{!a>S~p3y?`98 zra|X<#Jf}bJiPwb0vW3KqP*$;U~0%4;ZKJza_4N3*UHbrb%ivBsUZ6_@^@1}Fuk|v zOWd7&fNf|Qck0Ml{+)J!ta(lVC?oz);dLkB5|s;();DEc{%}QnE(~jFVXX-DLxa#L zyaZ{z^8l|Ws^FgEmZ88AW@ugSKZ4Miz%UBroklR2U@Ec}NSu7;fsbL2xsPMkfIaRB zGNm``0Ck3Sd!5ZNw11P|Cl$VND`xc#?RbRD)IwAKvqanfxB*W+bsXtB95u}Bk0u=X zA)E<~XPB+>qOg)+)Kt$(cJl*(-LH?_v2-6`IH5q6;B^F;oGOKCij^>Rom`Pm-)S_V zj1DK+O*{|X8-BpX$YwYdj|Gi^I@q=LKRBVXCmLa+jRVvUFpRkzQ%f*c6T2jSYi0ao zJ0Z3Xp&64s`fNJncwa2(8v;9DN8=weK=a*n>=1X0}5t`?y~0eEOcZ zjkd%QoSm3UuDe49;zjon;2Xa2E%Fb+6M{K^-kuwismg1f>BXP8Q3(c_mdUDIXEWOz zXTOiE<3TZwhyGW1Od%x|S>Yt7(c&a0Ytg4qJpbx|8Ls}KAijR4AR10Ez%|-`$Uwk1 zezW{T@P=SUy7+NNx89QOYSra$eKP>%4i{y^Zkd4=9dc%q^_fjVQqj_;=9f@2x`I7v z%yDdDUogmVsW>j+IOi!UV^zJuV&%mZ;GVq^PJ{Xk^N8#^$@k_9UCo?C?(Vx(!AQ%1 zf0ir*d0Kh0p97|ntva!rB45fjSjgfK+Xpo>Q*C;lW;Z_#zB_gcoXb!Y>*rht_cirE z;>Pl5`q&S!#=&#QowmL7no;Ct3nJK^- z=EQvdM-2NAIPWC;w%(;o>GdWq1P+fZ1t&Gm+D^f-VRr*Gvb z=CwRsLAj`#!b0sE+*1n)evxI(n`p&>0bAl^)>GU-IEfUeIfah4zVMmfeVAWS3#Yi1 z6G>w=oOEs#tgLVcX2Uk(rWuRiIWOW1xzYkRj?@R;E1zRu!=r39TBMOr_Gy{~qj~;5 zm+))@t}h(Hhb`U+t{(}O<%JgVwO`6vK>C-Pt`ICH1tOW~qMtRBIWibDXe7KF(#1zT z`yhNR{|pzb9t>Wu2^9v3t9ZZ1TR_Ot9*C|6$T9s0#wYD1*XbLKZCvd5qQDM*p5`jq zT%|CcjwsrUsf4a+*3j3r1g@yM0ck49umy#%V4e~T$Zp`~zSHA>TALyb-%mire=(mu zH>1R`p%^O0Z)TVvImU!wHZOj~!QdF&{r718%$oDUiNEHu<}wGqt^FQLk9+*BJ8b)S z34S6bi^bpXLmTpD@JXuxFZ~A#!zNmQ1|>I?xH1m9&D8<^7s+}*_C%%^!x?6h9Air` z_ntO#S$k738atL>&@oJmtJ4-UPoEbWVI2$GTGiePiZd>dF#BsT&gmfxDawM)t;L{P z8Yoj;Y3j9;TeM{0*kaa+$`1o+7Ol}l15F}9 z$499!B;Epf77xNVZR+@8Y&5vtxB^|@u8OX-od)$C zEy5971+*vGiDAs;#}6wAW-qu_Y+Xkb+}-T?ghRWqRoWSJkgpeLBn9o?cq&G-EWAVI zatxI&uJ{xK?VefT{^Vmm@wYAV3H=D~H3WeBonHmx1~O!RdjP`}kT*1W1U3+iiNv@> zvx$trwT$7fjLMX59eo+CkLk%URFPkHjfA5TFIB3)p|J-vq^|m6KI{vIV`Y=x;I8dx zkzSHjj^K}m3J%{fK@8t9QQVWK4A#lt(4GYIn@cZVHR+^Kc5*adxo$YvHM9iz|16Z! z)ihosT`z+!7lz`@l5Bp|2V;?5in_hPb7Li}7}8r* z)KX!XA9BnAf>A2H<*@nPTIm4)(fpeJ1)y=}1!T4>jZJiIa=ZpZ`V)x{N%o_S6)MN3 z8usvk6>ztO7QP*&$B*{8ir@MU#M`}2@ZDx~$BhYQc**=|Ojom2{)P@9n1vpn9Ma+j z@Kc+|@!I#S!1TxIC}3_FPba!&BuQBrMGKEB8;RcI9I*s7dk)7E6-(El2f~Sgt0m^j z6Y)k_6gTHXH-1jyE8%$KRK8h}%H+ormLIuaN1 z#cK@reT37=FS<;Fw4n1jclOO2J7*^Q^K&2wmHX?-w?RYdFa1>*6 z7Qw|SlZBaIk|k=U+n`bOKrzFwR#I{LX$ie)YVsMV9D;HB{YrAFVFxgbgM6rtHXe98 z5QR!3uL>@a3N* zXQG@hG?^)k$x-4d=B0c!R|%$iMQ<+Z=5eqwV+pig^r!_g#jyh!E~l3pcrlWYRU+v zvP+3;?2`bh)TZ-lWlj9M6W!3lO|wDcg?Jb_jmWZzhCQ|D36xd$U>Xkxx2G)jpuDsI zzPq&xHGb?1E+IeR+KB+<`spM5sO~RVU3OuZE_p?8hhS9gTP5>iiJ{rddHg;z9o)Or z629Dim|!Dd+F=8h@=K*8uC~7bEj*~(b%-nnM$1%CujrHLbpK`G^on31dTA6=ncEM2 zni3)y?BCBYr^p+cJOcFu9SZ*D;F6B>oPTJI%=ZVQ zr+Go(S&u5=A~6#D-fo3_9~B9yz2X^0nVhGQ)wB@|T&g!d<4+KeAZr;g+~=Dw0~pfXMrBOZ6V$=UchgoBG%pHj;e2%qJ=8= zgsIAMjJ~`T@tt7)2`h_&@2&%f@J>Fntp})`5G_+(u?H+M%7czNX$(W_n;9N4(B#<_ zV*l|1I_^FX`?U5&2E!dt;O4bJy-y!3{N~WrNJI1@>5DMwL@Zm4hJ4iOFTq%J?CT=Uvata+%9SFPFr zR!`OfGIG<%J57gRERy?hD^s`envX;HsO`0R&pULKy9CT6twAUbvS6A{9ldfCw(@M1P ziv01S#k)RW{Zv~#N_!1YS2J9GY-d3*v!;e|immR#se`BZZ7vf*^pJd6w3{9XDJM2Y zM6se&Pg3MaLlXBPVYU6rn2iBVUGzFt2z0XsiHjAirC^i-Zhra?7i`J^)~7G#za5vvDApqQW9>0SViR zpB2ql=f{Hy9r3c$)0YDWF9CMdH$j8zp|E9F9jiTc8pvvhp-ElXUYLI`0n}}c!1|h{ z;BEJbB2RR0i8hnL_Qa9m>vw(GY97h=X_E-1@Pxpv+312b-pBEV|K4D`pkP_ZMqM_a z*4XU<9G$oowzpNnq_k=hTzeBvd3Xah_nZm0s!Rjug%RFWpAEmC$riS)P{2K!rM!aX z7U@&VTMV;PzUy=%m=6mpIc}#99^n$tA9y>DcOT^^6K1a9+sJulKG|VfsQ_rV4?{JZ zN~R_XsVin0_N|Kkyh_k$sb2FSgjNiKh0lMLOr3U|b0d>>b|;4+def}rduUgJ2^@Zp z%R6-n@A(kVznxLUZT~!6<{C4brv|ib!DZ0uo*wkxOOnbANkQ0E1K$wC8M;;fwYyN7 z>m}ohYG)!-dtdneNCW?v-za3hZG*?Ek1~vwd^K(a6E*J!r!XZEJE$k}MqyV=qK_1a zMn83g;>q4!lXe)aMKj43Gtx28l3+cs|i)4UI(W$ATL{q8F8 zHU5k+dwPHL@84;LX_5anTL`8Hi03RClko+UB>qM5Ofgd<1l%cVXB`jfoFp6d1^7yc zHwO`y(+w1j3!%w=>0{!Aub;BO<|`-A*dskr@cS5|kH`>Q9+@Mh$V7%YD}U0w2qvy` z7q{g~9QGcZ#9s_8#@)U@gHI|9FrBlZs&Dj03nm>V8(X6KrWJt>2}k3aRbW!|Wx-E! z8RW;2aIXG3sBdWs801$f#C$MC!#6}R4D}i!duShmS-;(iOZN}MlROjoMLM6w80X2z z?j6LmB2d!Jh4u;d&~1XqoRiAxh&eE6gmGvzT%f0mPhCm{lg$HB)hJzLc_$gPXSNG7 zHuOauAN?7|k-RzyCWK&C-b$AIy|ot~T9(MyF7J*zmL5Pr`9FcGzT3%YePrHxxMJIF zXrOe7S%FPas%36)wtC9=0r3dL{8pXQ!i*kw!pJc$yYVrcjYZLii^gh4|~O`LLp ze4tx+;`-7-M(0m~{iVwIePcW9IyahOp30Lik_hI3nCcMzOCKNWjN`AmZ4`FaTtr<{ zrZEf+;okHigUPX%49jB}=bAT=cGyFIo8q+SIUxC(3d%Wh8+vZp3%W~Gaq%KUu{gs_ zT)Vh0aF-jOF2f4zWwl3GgWh~odPZ)o8`2gm5N9X(ZdCi)wL zfu+L8^$I1f?f@^FqQXy`TuyALdw{UG^}NfofdXC43;Eb}4Z##9>T>4p3ZVL1JU>3S zC-5*&LzW*uOC9zQb4I@$A}YJVG=*i8Qdwh#DprcUFr4!IHE1;72m8z$fg@Dja+iH3 zV547G#I(z0+yrmpI!`dS$VZy&(;5jzwos3&`!xz=#U${X$K~KhVTnlQY(+lOWQcr! z3_0m2gAUyv!5I^evkp5QwW8v3NteHPHCqdo_Pro{4bJBNRa!%{#PwpFa-78Turo(7 ztL3}SR|Mm(!gJNr-9Tkn5`QKyMRfEIL5%4ZWC>qr8* z$!eU5bDz0!DsKK>3Xcy8mu4nhlLl&3!^qCzqz;`U{7J7Zp%{*Qq{(VN5ll;|Hg~5_ z02s3}i9dXPDOm8v6RAvc;vE)e!(BHQGYxxJWdrQYv4_K6X0g*jDka(Rt`-!P5eJK5 zJNWk5^M%+!!_mw&y3qd1BB62N6`o>F$WPTf3Fg4-Uy`|+F<|@9WL~G*74u#eXkUme zXo*jTbqj_==g~#1zM-n`VONrvWvdM+fD;QMA^5i*B?c>lx^F&0^DuAZe!3L;Xxj?u z3jv^*BKb{Ix<*p4N}46phNOahRjIso?~?+5lxzbn*8`h)60i|!z>@v)TZvSD;t#NC zXEal+(8kJdStpDiABvX#m6hM}emNDh zjt}TPF-`E)k3t)~2BWnTj|h$VCm6<&{CN_LKEZef|8q#uO9b}cGWpr2Lxi7aRAm9K z-XLUoG*sR*jioCrnf@GVy|HD&e|kVny@uB2S)x*v6XTTT@E-245Ct?naM#IH!2%asr)P7 z)o{l2OjbtaZzM4lQ!UYpVf)dU^8Mhs>K~G!vloTiTcIAg=|Z?dBEyKpvX!jHhG0@= z6^uXlZx>i(Qou`yT38x%LKbGU52z7If|7ka!_fXs$o5c3L%3-fMSBE!>4r#nJPUab z+ySl+%QFQEdIB;PicpG<(*I%;}e1DxL+dg>_ zps@!u0*OY7)5Cjes{P3s!~EGV7^c66I&zxQ52eIS0JGwC@z8ez(Su96X#OiDTv>XQ zVJ^tcfdRp^Tb+>D#`FTCdyD+??YZE*P$)}`-45b9%3-ZzEfbehna`((*O{HJlJ5&x z`!5Tgi+=;ht}cd^Pyg}Rb=J7Wr3oH;ql_dz-ErgySMcn>05C`Hb32V-&aLdhx&2Gx z?*^3fSM%-wvqG6{RWDaiOI)q;AH8Ae*fe#K9^TW5E{gdSo(&DJJBjqFyIRWgLoKkz z)*<2r-y!0RfL&*zrTmI;d5_xMM*dI7KK zOj*(F4Z!id0IBewo(s?r?vUlrU|hb8O{wbp#KT8>8^MG6_xM+xJJhhc3-;{0hW*ZF zfCKZs5udMINLQmPpH=rDn6WWZuE4VoPTpI~J1idzMxRTS-Ttx`=;TOYNG;jLJcuM6 zLZTxi({_!|O4-QBCOZ=TPXW&j><9K z6k~puv!5~rTXsC;D{k!IcJ4SSOFB3kv_+LdXPbx6tZEANaJN2v@vHW~(umkMsD^-)2P}_uJVMPkQ=@|2%sO zQ40IZzTMc#(`maUAMZe|f3ujB#Pb8uMKxAIyXykHT5Jw`OuE8%Ulk}E&gqFx6g&VP zB-&NI(}-6c^&7Yj?T6@1`$cL`vg-^Zn0xBaxG7_fSMn`1nD73@4)qmB!*ury{^gqA(vKZY zaIN7!hOw8QL&p%zW79`mlvgZ1WYown`E?vm`ut==OxUTtBX)nq#Pq(O)9~B8ihIc zmr3|UTq8f9xGEpE?TPILHB66GX^4Y@>=P?Is4XZRwQ`((5vFXp2?mY}7B+Vz0b4N? zCB!SE^A^EC_duo~+hU9=%Muu7EBW4#o0d&5{ho$$RTc3VzG>ncq_1(0z3I@xv^S>d z3RLyo*`Na32jxMk@u0`u4grPGHS!m@yE|1-izozs#V668ty*Zle>wpYdQJ|kBq@F^i>1){_a)e9 zPejer%V5evbEx0%n-H9P0sL+aK_3?BqMC(?pjx3t=u_Dr5j!%5`Aasp1S2Du;bFCs zTO*F(itSCjrY6xhuiAiKsVU*&H&2KYPY#^B*cBEZCW57!T((tTG43Ax61NB%-{_0W zt&%{S?>@ABl_r|ooC4C4e+$Pgdm)X99t`6n$5au_+~)=oB^6hk^1G4Oo)Cfm5N}7v zA5VnZ8Bf@DQ0a>wOr1uyhDo{5U>$L{B+f}$m;7ORVlSNkE)480b3$v!D(zKn77-X&Kq7WKs6P-l&*#ij%_W1zE1C0lnY%A?Re-cz6!5wu)*JlSprMl zaU#7&`SW1=a0BdhVWQ}D8Hp6LT>k2OM=*;{zjnBdrVEikhnQ0K`<<_vqI%m}0BMSQzcC#F}l*$cj=-4g#W`$n!em|`mB z6+t_}SbvU|fEneIZIzFCYpcgVJvakJt^ddd$7m`ERjim0St)h9ruB`5>TA|m>HSq5 zpHch5rM(QpYg(&>ta2aTvDFwi)hgpfUp6z$M|nl?n_$A*QY0@exA3dyHS(LBe8G2k z9$i!mvx$>0X{^xtX6mvO zakqU67_%-@_*&XEzR#!{keYZx+|YawYU z7nNajw^Hh2i!2!C3gWOQO&DfEoRt@*2+|nDTocdNDhUH@KV&BSY6f&!7?} z^YIxy71rLr2o1;!$D5>?qyE!@&wX7~*4vox@Y*O$zdrz7UXc$%;-(5&gM)aA8ApzW z$gXo3!JHn@jZ3YJ0M92p`33*YMS~l)fSL)J=;~$9%z>#?UbUegJG`gqalX}s zWQc47oZq$pxpm0+mHWJeNu?Xnoc}Ul_Pv3EV(TbCG4tdYdxFuQ_D%BVcrti!;03Qd z&z`Td`v4!8&j(e((QwxrI?+|YJi40w{$qs)&0Dj{&4a^pnxNnG05n$B4wO~<2wH7n zC}D9obnopU!O?mX!#t6fQH})D7GET>8Jz|WR=?(hHTnx$c>}R|+!;`nLkbUqsU4UH ziw8V~Bj)`BEt#jG(`wQ+T$}^N8eLTIBNCne>`Eh#v`I$EYWpgqE0nPE4 z;U2-}(`bF8WJxwkHkV+&sob@9dY1`ONL`FR8*K+t+a7pY_k}3l&;*T~StQt>jbfO1 zc`ITQ!8G4jb~t4`4~&ob$=gn}1j+G9vK1AJL03GH$~Wb*!h>lFcbtV5)x?JFf9AmL zQMxE4#{xA6ID^1y9enYI71}tsAL^S%R>sMHoBv^U5zNrF`jV4524H9UZ(cchGa!+5 zvd=MVLDnV_)|%dCg$H#Uiwnd|j!oM{)av+d>2G-NdK0vNWdw$eFvUW|C+O$b6YVMP zfj8=Tu+^ND-?T#nvs)sS{9G#XO9m=}1N-g)p%%-Y{9FfYh=rlaY+`gy8u=8{(eeoT z?!Uu^`e<)$YPXHzR0mhF%)60)8#V^NIy_FiLawui`r)>;8NfGWC@_$}I)eyibc!)I z+(nhI3F-z8ym$tj8e}q?b2C8I(A%(h%4cYolMmTVb9}|@bm?lSc~-?oE3u+;kl0sx zj8``vi1$165QE8eDS0gR(ktgFW-)nnlJm51f?4&=gUidPk_OK14#GPWfKI<$*}Y?Z zfX$I|xa9R0*uJ9>`p$h0y?(x7Dm?nzEZmb11DCD=%iC6ny0;%m-rrHdr!Uxx&qoJ> z{GFq5gw0uwVlI+*8o?wG%z(3}x$((oh3lC;z>BfP@bbu9na{yNz&jPgB^9mA;gTl% z(Z&k(Porm@E#Jv$)W(lMt58L3n%@u3)jb5dzxs}EJk19%@C6tpBZgZ96HDF#1d~B9 z{>EwCuB$4z0IGtO&usX^UgcrP7e#6X=8z|{o^;pW5V+R82`FyM z$4lPz$3Na578OP$<4j3B2%ofDe45#v-LyUO!~07F^DeiTn}2;g9`Ld!=zDBAKfGsz zEavraHqq7ohK%p5Jp%O=$hRl#0jt*Ra__K-F0k7VjFxW0zuqo|e!XtuVIMfG+cXw@ zd6b6FOWa~#Jy4**W zv578f%AodM#w=S;#i@dEqgsR(uXdO?BLIweaZNBSjOH~;&VwndRS>;t8^~A!*>#o^ zOmK4*_b($5+q?7vfxU>YbG(a8ZT&<(ZXJ2jPz4OyLSlnriCR+W2BcDw;@5@H)~Xv6 zLh`xdT~9eJ4-534i#|MTzk%o1UXf_q%b@m;jSO>NJ_A)vFaz)0;v!6<@Rzn;;O(-T zxb|az+3}jG9F>*k6DbK5UrZsb?f_E^9gaU>Ifds3-T~W#=L+sB=AdDLJDQb|3Ek}a z1MS9RLigdSC~DschLOo{+GBzVal69#`6l9oq3Xc7Ax&)Rv=E!_b;nEG>)8P@?Rac@ zlm*+*7qP;_?fFIM@vRi7W*iqZ*GGVv`;Vc>`G4Vr)xIEAdQJ$uI{>*|j%Sz(GOJE* zS_{FTJ|W!7ISF|79(ADMeFvWc-q0^viFG`(JoDhC--^(=J%{D3d9QDP`d*Q9j z=xdztZ`TztsOS_bovn#BXvc$Z^Q(lQCR5Y`<(O1?|K|qP_}Blb=Gh$+@t2Xbjs6G)CnzO!b~u5V*#`Dh(ri`PnYu-)xD-?0o_~ z{_XA4-4(>O;3-b>51RIjB@y=o%3a!v)7}{8AKSJgP zOx}_`fILHz79KRPHe&G*{8Z5vc;t)~>6ITp9T?2-k5QIHL|J3SL3v}r6nV4Qh+u37 zsYoh@_z186sDjtGMuBy^t|9L)YlZxlCnWlicn}jgw%WNi_M}Z2`UIvv`OFNO*8S1P z-y56x*lcv|03MLw01&>WAP16QC$H0ef>mBuq_b3nJcMk7`VYd^~^@~iUbT!B2QWB0}G)}2< zmBKCFR<9@6T{{W1rDvg&+6Dp(NGDccEhH>3>lc}UB2QXCTOIREanu%|&b<|!-!c(& z$OdDma+mwQ%M1Q&{0M$Uj^LJjzsyn08~J?N6oPSq67EYuf3RDpClEEBf;H>Uq63X3 zCDh@Pj*QTvkeV`V>JiIcoz#?}&8GzJU2<7mIXIIaSEP(3_V%1hk_C8<&x`kb-KA&! zZ!*kV`P9%{g1OzthC6a$CYWuZ29}RL4TB?2pzc%0lZmcU7^hFVgj-6X#hH3Yr6k4E zO4;8{oJleCTRUC6q~r_p_c{slZA`D_dgm7U3llNRrgn=;&e4Ar;JW3g^@HFToOP%}g*HBdw=%uG1h z(!s)u0p!iRErBoX3J^|u#4=2@e4=YD!Pwjw#Qk$S0mA?E1Pcl$;d?<_kymXwM{^2C zw@-p5Hl)8s8Y`}^2SewQb8PydaYYf_kUkDd3n!qX=Yo013xUEg=|U79cZhU%*9kvd zl>q&1+~k;T1d}KHlMM7r1R7t|z_Qm$(vX!OVd*CeP$;*uW4J(f>U(G}IEtUv*`eC*-q6_RxC?rdz@T z$#;cx;1Z_}ywo<~*r|D7p;rKyvGWvEZa08biyJoo39K|}2gUbeSPPG4eUF^0f_APB zM|=IYg4u633-eoJ(8`Fu=+FGALg+z1hB238dUO zhG0m5pkx$ltk4Zq&^%(=_&>)nY6Z5tVKDll8HuJj9tX4jWC(CwBs%SHfr^u&gm~u= zh8alyJjrT~6O60Y0Ey!07~ptE3+&Yo#zyhhGV9JmV9ESgSdg|7y8XP!qFm@iS6stc zb}m4LG5K!RNcB$;dfGhzJaVcR#!L-BPbXU=)8Qus-@RcB(Oin? zwJy+--s5_p1F~%q2}Dhl4&4lov+xso+%47H2iwMw*gaCMsdZg|sySw;=H+^1xM(}j zDDQ;}KCeTAkC>y1MH#}gVWAA8F2|%0%-M$X4pVejgW^g0;6ooH;P56^rW3Rcv=I}g zO)=*gCP2FxI**KnVYOGG=g()btm*=M@>3uEbsK~9rmO*`S?c)u@bM_&=0G&(Os$X* z5X3Oi^4c?tU{2c3l&Igb1;$PNz*-YGFlBkJY<}Jb;QOkWo!rt?d0Iv}e<)zb-LzVB zj?RX?e3j7}jlXcn^Wh*b$`HRwQbqR7z0stw?)by_MGWIfcAez6DIl2Ax8;%rM_=<1 zoU4kj0||DYHH!%J`{2~^+dCJ`GI&hx%9Lws?|01=a`D`_A$u6@i? z%v|{!x{_cbFMDv^7JMlAzS9_NU-=Jaoh^{ruO3GX&nuv}T00xKq!O&u##gLOL@`~v z$!O`-nV=|lpO|^G7k?~98Gkz@5tm20fHmDlU}eK}j$-oUqrJ5Rb3P-Mvw(+%21OH~ znw0>$R$P|dh_e78b;Mw1@ki+Un>4wF3KFgT)`=uDrVA zC}HM4MRES|tHAJE5!k%#6r>pH%RxSCPYC8qT^_f*?xQdz(iF@#u*K#x(q-RO8u;)) zqP`;&UEUtato2=cy9tg(L`z5xx~Mtu^{#K=dR{Fa5mAV9j{1t*zh~m|`gHI*-$#5p z#1&J_6Y@?Y`?NO%^ZCk6&ez`tpIBoK49{KxJ5!@&dhh46`i2GwdY=y>aUu6e9=qJ5 z%Uk^}Tzhmg6rQI5i$2l#KaYMeFRzyvq%Z^LKXU>PKXl*)Z>O`>n2}*vg84#!n-LY< z#Z8N_fuAM#nLJ21D+!Tx4SL1Xa7S-4>_RP#I!bP^I7Dg=?6#jAcVFURUiV>O`cx}? z_(~-lxUG~QX8TuIjtlwqvO%EFvo{R0fZQ~K=^~hdZI8KO-H+h2MV6pLb1q*sd#h}j z^-kV|cyiJJ!N=D2F#l8u%vfK++!FA!BAC!k1HN3lh(C_Xr8T36qH+D4;DkrVIb*(@ z({s;+xjkJGy=nieZ?e+rH^RRh_vBZXfJe#4Y8!3?unz8Xz} z`C5O6TWJu7+ZwC@*OTPfxci9hJA(x3+Uwjbj|)k?e*w~+4b3B<=D_dHi(q26C}Ctu z02u$wA7vH3hYtFifh%7itZe9m4k<=4%rdeUAUCZa!Pw@V<_3`#Z)UbNaLnk7Ywgsa zRPzP1)1^L8C$Ibl2AyQQ*Q|i)2tvreP4jO6ua^f4^Jf);{eMp&3DHHrJR1a5pFa>r zeKbLC!SM|9R9@nm5X_rf%emouBk_%LYfx+bAAV}{9d;>d;SeL@a7|hf{S5oVLmP_V zuz&IyD7)(zzO&MVE9XBIRO?EBt8W&`kntPJbc9}*nCj}+h6p;PIogw zLApPx9HoV-T~ooR;x?hSS`#IFJi;&?@}}2Vf=N9;QR3gZ0Z$lj4Y=MP@I2s)Ql~cw z2ANNxGih)wIJzCWueiq|UTGX6wKN*tz77LkHlUVI15bagOV6Bht&p*%W}%{y6#MATjxq9>eI$zc(ug zrU^Mn2G^aC_CuE7u8kk)e3FCGya#f$D5R?IVpAd{({E)q)U>|IpZfuBiY|p?g~6mz zc972>o{h7!QgBIYJnvO#gAd%zzDaKe{5qJ{JpYm#n%9wn9=O!zV@$~?h{DTx8ah%jaMr@@}3A59sIs%=l z%WUA%fqb}^>=xk7IadT262?m+%7xf1s=}hdlVMCjA?P99esFE}G+yxb?faMl$kVv$UFvtx11XOQmu6LG!UZaFb6{F{yc=i>-9DaUHU`5;L}I*$9`rHg(BD_- zypg$&uy5EzM0PB&GulfS^z9B$e;ZDYNh6rRFm29pZyY%7Fa+cdR+skt`VTrS9|mmH z65*~_=1eM2-vZRNm)cEvjc54{TOJo z+b!&CjYPJK&CrJDsX|b20K+_yxA4jcX8EV#k{?R3V@HAgckRLTF%!Vy!&$Nq{2E|lLXwrfip0$# zm&p~V8NFsJX47__WXekxtB#(XQ$-D{Y`|Q<{&?>~HT3wF7Ft*LLa?)SVHhbH?Io*e zBN(O0b0ir@zwu>Z60l@n3OI71NLJvp4dgE=hgq!+Y}6{MfYdZo?y{{qE2BuNyko{& z7&vi}xM{u~NRwFLUnN6DK(6X#D)`9AiNGXh7MLq<GTBBmWH#v`Ce(!KtQKtyKYuj%%jU-L>-&F4=EzQ(-x|jtbjB6mXRu9B2<_-3(Qtn zf{o0|;6nRdyse`#t~v3YAGh`^KgX|`VIt%cT_Xs__hmJAclQCTuyrc(30yD;5LmK>B3{3 zT<4`T@Pp5ML~mM!dA|Z(t5cc~pP-AvRzxw3vV1j81oPGL6lXaz4qtbe4(8Vl#){wn z0cpSslBg&*prtwNjU^;}ljKQP^=M>{W0&4M0%?r_f`3{8_!DvpK_X+E^*I#iXVnY7 z4+bHt2k{I;?F~tN<4Q2gVw|`<^+XaQnhnfs=T9ZF{D#N zbf2a(RAA=7JNkbWew1AUuiu|UcJnpS(voy=^6@Ppd#VA-ni$D2esYb68^Nqy{Y7#F z1>(Z)(?MpdhFIx36RG!g#Iz!CoRbY#`8u!?Hy_Hk>f4r9!N`C1P)oBv_Iz*_H0B1O zuAJUzP(d2dnXG^}uk3|t8+;jt=HimoY$2GP&#=QR*+zUudpfw2tch!tj-WW*7Qs8~ z8Qiom8`eGD0NbwIhi)G7fOJ}T%(C1JKNRZX8R01)%y%1d8Ppvu9~BRlUe?D?KK_E0 zg)14RNv`qmA{g`f$HnhwaQL%q8dzW%g}r*lA)iCH1-FL;L+VVmm7&nh_!&%Ux(KsA zlbVNU3e^UmfH%Gw<4;$8!G47a==juD$i?`91y22O&pq|9^z3kkiIQV{2qr0Sbjjli z6+Fyp8n}`gD@?e45!pN+&M>sGLL-o<_<|0OQB2&2_snSKxS|DqTmt}qo}`wOYwPXl z;Ph@o{4{Qe_%v>e*b%iH1j(f&Aq3NSOTXmp*hHbQ+cXfGcNr|rzk=%8{iGpJp26_M zJhmNFi~huf|1?#;MfEGJH7tQ+@pyb0D}bGg$BOjYZ)^fePU>Lo#sQ*sdLM?lEdSm_ z63mB46Ng2=)1(&@rUE=T4P*_@L8{fyB@XZzbc-O4{p9dI+~WhJ87nj(y=?{=93!oW z6|sZyH5|ele8|Od{cqt1$zgn)z8Q|OE5Zt25vHs8pT;AJVANgoC1JkZ`NXNyfO~}v zUK5p$nlDV}X>U!Zpor8s#3{k{6|B`MVgc!0@HOm872$mFPl$3J#EnkrhU*6Q!ao05 z@WzAt0B|;P0}tU@d0B6bc&56R&)}2CVvN_zB91SETUecoU@`(l`s2x~8HHQ|Agg4t20GA%kf=j8+nluA)RX(M316wBvDW zzAF3?yhMm|FBf7Sn+Y$jrc2rf38HT6D5;;45yRM!5|?Z_qy*!?@3zEfI|Q?*&j1T@ zd1AMn0c#ZpPKJY_KHCef{v$&}PJH`sYvV`wo1mwZLvQ!`-fo(`#pk&zHB zSq+_wR*D_x#|rl4$DLaEVz7Tg|(NBZw1BCaJ86akJGm zn0?_RC~Y5up7u`Xz4+b2AxjP=jT#Jhd^;$}NK^>L7|Ah>1fx);#O?bR2OgEr0zM7h zr6E;n$gX4(F$Ye91zMIcZWZaNk@|+4tOo1N6WR1boZS_;AT}C$)o(**)~SPDuRVmC z?Y_v%@Gi`Dnj`q^n*=DvTK?O-BAD4jen^hho&{=cPT=5mh|BvV!H%;Bf%BTv(9E(Q zbLXi)-3YHryIA2t9|0PEGQ__N?uZIQ16t>T5&bp^2OmeGiax~DM7C78p|)R+kyiwt z2xjY_E0Xv}XThPp^FYvlop|548KN&S2hQ3>Ivz(Yq0*Z?CX6Z1(S%g7Qt$ADS%KA= z8lsp>k?3H45O`8>SQwBJiI#phK~?Lo3EAWJFw7NsMbJqwOZu5h{v^f&6TA7qewC>( z?xViUWdCVkQWXs+Db8h$6>4nu<<5BM@Ggn%(^>}S!pS?WQMp?PQi}@)8fqCrlu0nc zE;h(j>#{JwBYE&xae3YnwaW$_O$0Oylum<=`Es?%(u zI&Tjc_4YhFho=3TubI|pugeZ}J;ww5?dXPW|87PDEG?1ur2;{3^l^q+D;LJ76O0Uf zyvEJg2I^{D!TQ8b-f;J6ndYD{A|=U&ZdX%aoSR&K6F28Hbnqib5M=L0djt{vj8Uqd zBa+!J1U?h{;wVRmW?UPD{v0e9`qlU{%xO7BpJ0wu^moXKkpRv3rNq)}8aTf7ybNF5 z3Tm$tk1i#F*-g^Qj&6lfNMz@?XD0n?{3*Ip`>FYdU?oGfZPNqsX_#zIlu> z8_nRA|75XwUT^8~%{{UHIt#Ju^eymh_yq7wZziM|9r@tcG=fPyl*rvJtQN){SP$l8 zbmxanJSS_NI~&l#Lv6!5*uEg0X$ox&h>?~tW-f}2r=wumNoDA;w3|4gNkf#5J1pLR zU5`65?}DwJ2gJPNRhVMt%Xgj51T&C7$1PSGfNke(1pme6fE@=DWcT%slHOVgbQ?{o z=3`+n%;fj4LaYppi}9O)Y_R?`@fNroiBlH@gIR@o;=ud8 z*lPZ_hh9c7-4hGBxM9=r-k{AO$M=lTkq{_bD%%81YGlwZvX1lWY*ZX*3s?>^eONMzy7eYrrA6v26>eU2iFk(H$;xHoeK`2i}9J zA4;LUTR-S@z7X0S{r`o>yDzPvRXMw4K*@Q2^};C#jqrvmo@Mg&ma2kr)qB`z;>$1| za*Q{@C|TU%Ud@Waoq1cqhSlA%!J>;|<=00g4mI_}^yeBg2c{EU-k#T3jz?o3Qh5BS z1k1_}359j;z{J7_Z6VVUlQ%5@*2)ROhfXc@DLI^Ba^%O|egw0*B9hy(Ar?DUZ3C;e zK+%tESZgYt3!cB^g~z4luYitPQNs*61J&6561-~r2z0q!5ElBS1Ig19XnIu-bT%>+ zl+Jl9tWh;W_x8py%t85+7Dh0m73OhCLn85pG21~F&=NOg*TFck7j8U2Oc=->`f8{q z>v&K(_KH(apqEE6oW-lcK0XaX!;Pz;m)DN&QQns9 z*+Wv+?8%lr?WK}Rn-;QFs6^|Wxg|-KNVcrmMV1h<{jPK7`}_PcfA)Aj&fL??xz2UH zUay82o8qgBN7B`oR-?NUQ)wIjSdwK{C05%%g?M%@yPs9X3w{5Ezd$JoLf8Xo9#fYJLGTD-YaN4nE;HQMBr zA+EZYL0Z+#5TC7l%E#d97p1|V|4V$x8y*9|F!L;C2$)%_q}yjHQI9=c$j!vd_)Nd) zD8QgEJsH?dI$32Zoikg3LgWvD3NYVYql+(jXNcKqt5KutexW+$EIEGApoC$V)iG-p z)8P%+%q|-@hCRj~>_1~KmqPsH&v@#Zpouh^%q4b>IIcvaZnUMI1Fa>`f#w|JD`P4F zQ}A6;{HyQXl9Mp{@mbRbo%?i}Oo4D@_S-ZrID_jSsovKl#fq@vtZFwd$Nl&rpS0-p!ARcBs9 zY~YgVZ&)Lrbv)eK+!x;k87TwT+l$}u5z%Z|3!JrZD(Z*L#SY#J1cqV$&`@~10gO%U zEBh9vt_4{y!yv*vE@wW z-GaqPZEjsO3hB&T9rDQivO|A%9Ng8St z4OYB(8i*!OTZ^7)c?m{t8_BM+tA#%PC$av6u{i2{5yzyO48!!paXvW49_XVb4M@5& zn3$MkfH_Z)=ss3K5}_||_-?n@W^5T>4eR2w>>ZL;l zZtu)<*rR`$a*wXYSeWPB?CmZFeA-7UKWUNYgQkd=&u!zFe{h}#tLY7x zvI+V2-)^O$qP82*MyJK%(PT%-n$AVF%KezFhE3ixVNA^eJzT06gO|j@FnMk^ZWmxi zrdq`iy`#R!vcOl|<*=Xp)aykSM5c+uPX%yHjQpex0L;G=sf80SLC537M%1>OuQJ)fLo+RIbOPdSBIf!-4w&bM(u(>Pg`ms7HltP{OO+1$JyaHWA9DYihSj_KVrF&BlwRq( zH(=d}qu5pnlSFWMKYUO>uD&xJ-lQ^#tA?Y{5j)W0?E{d){WHA<$`M2^_TXy)Mgryg7(R;9Dae}}t*s4c) zUFVjqtc+rA3C@$6@qE7{xZChn=#F}C+U-GaDI2ajH9gw4T{m=Pk2i9bU!87%v3csH z_-Yg&6c+DBodXlmj%SkU!ygwIPN>9{*6*BPL4+MvRwI z&5sM-WEh=t-d>tE&0acI)Prg+xFs;mN%__337D29KNKx?6f4fu_@ZXd8)!!R5|zic z@rWOH5B-AelUd;b86Fef^LH8(UofQ?>Zu{2dEwH%4Z4C&=pgD|yIlCYD*XIu#<8m#qQ>h}&e z`B7f5n_bJpyCXiLfmcUM4#tO-;d*~X|GvYd&Rt$3_e(R-m6P)zkIfscg?~@L>;R0~ z)@@4dn>AwPDL=GE?T%0pcvRKR%mFd`58VVvU5q<~-P=QP2*Q{p&Bc6{^w{x zzdxxieQs_c%~-WVI)FY<+WIxJYThbo94(*>!(N@Roduyv}uk*rV-;+CN<=XS~>G;d&o{zEQHY1rT zYm?E)WaKjh7A6kuMtB`AaQ#?wD10ub2ElzbP0RX&yrQKcH}0S4X1UttPm z<22BGwy4Iw*T5VYIvzDMC*!#~+t7-48|ekNOl*fQD~C;)Kr^3OqGwCu1%fym783|iTDtLmuPH6g^Y0@nv#;pSOZV?c`&bQv3uy#huJ1=vrw zJ8qGFQJ9}yBrcxagY?cDgcl5)BNp5F3QaQ{apwc03A<_2<(qaCFung2DSsUarB?F; z(ZR`s#Bq0RRkJs}6}#T~O4zlF(*-Z_|bkdFDn~TDQYn{fE zPa*!eU}A=#@>UZU_J4=t>U}w8m5j+|zs;Ot<+Q3;TALM!{CvtqkAN6y(d>p|HfqHR z4|1Rx9X&61JeZv>>v#;`cpWWNtP*>#^+1jpy9r6C#cA%7QU0M+@o_&LQnfmYWA@68 zl_J2b-4>`cc^gk3ObJ3`Bma}Un&+T5yGukCDV{qxmp4{e$D?^J*nxrMSL=E<&tXs5 zmm+5TIEKt`MUcrzle~KthF;uyDZZOzLR9{V9Pf|!1B~Iz(aQCcqUp*VK}fxQ zYiZEIYuI(vBav;OqD)TW8`?U!IlK@zuYjBt=SR3GsTjZcsfFjnmWz*T&m#MK`$){a zjwH?|1?}7LLR>z?h%88p;TS)7Lj&eIV9HN_Q{c=X`gV2@3Y$?Qg*G^ll@AbgzYTk{ zPZ>Dd)(%(qDaQ`AS@P!g!ezXu%@7qk=EmWeipV0e1ba$ z-o}ec7UNfLeZV;`3Dxb}Ky?3Tl3GYt@LjJ*mwWxh9>I$_=84>jcm|jyf9@A;em#=j za0xq0L-B~ZVN|>426U!o z9O)7A9>2UCiaM?6N*%x5hEDu2j#&ZrA8^y&1LpUzvBk4)bfk+7gHZ3`DdLy486WA)()pQhS^OyzfH%j2MnhP!Glryr4ACimf4L*YC|pPQ_XJD zQ%!TpIdBJhD7%a_0VcV2Zt;UrS>j29AT(2biLm@e9$Du4T48+eDK~C*Uy_gQ7kuPa zV60keUile2mlfa*+a0LCb!(IyWht@CF1tTU>d=b%#F$Aw=EfW|O|A&kRB&c<=37zs zA9W>18bPQB5p4#2P7}JSj@LKMHz2ScHn+x?KVX)za?TVES9W}WR7{G4NB5^AYtn?J zDIT=r%@Pr3pgmk{~p@?|d};?Qt@Cuu92fKDJH;m?ir$zfP7`%G5+m zy~-+rK|9`yD?@FR6}mT-QQ!ZHb%E#6rq3-=-ltvSpxZeD!)VH%H50%rZTH%~D~QR< zQi4$1v#*fJ?=<2&BfO;4;vRl>{U}UBihP2&aZ(Cq*{iJZ@MZ+%TI~PsFI?6p#fwQ-` z<|pQuvvT2K3z&a5mnm)pdZ0k-V01-0PWm-5ki6G66@BVTxNEOZQ8Cu~bssNETZRt} zE#!?AT2O=+p1MKj^}U6kZdxQPcoQc+`B{hm><^}$o+pX9eL8W>E4lDc0;c7sF^cnV zA)|O)FtR(CjS{ALk#P@VOPo*U@Xf95JXz!M)M+@kY-O2VY@%yH;W4CkWB~CPkSbWe zJt?LJ4I#<9f1k&oRB_ieNNg>fRB>m&60;yk9ViyPGWBYwSjjmKq}6>4&gg zL2sN3|0As9F`;!Qet6F?uOjpD`A6aS{?Sz=5frbM{iDSOzi*5nzp9*(?}JIAT#x>astJ9FuITRfg z2P*!>43M1eI-rojG5AHT3HRt?wxI79cfd@;?tZ(LpF?{(7?a92v7~SFCUkm!fVl5q z3<((3lh`C@iG2+GIVKf$ov?>q1ekwy&Ld{Nk4I)L!jMUcW{Jj0ZPnqU4tzB)B1dDh z;vBr>cP(Z`p>y{n99so`gx#`nuL~9=_GK6uvw074n3N?RHw-0F>#fN5A}Z!B^W~Tc z@>YE{V6diUQG$Ian$~_Vn*XO~iSgdKsyL-Dj9MMW`g9xLs{4F=fNREsJ?M`kTo}U+ z?|n6`Nm0W_;yT3(J=oSLntfSIE?^7ttKEHZtTqH}z)f2P9|Bm-X26)$tS<8Fy9y1T z6poT^x(N;*QL6LabD{76XN06gj$!pp$AJCddY#StHw^RSohi|eA4A-Su0SqMpG1=z zqsSdQGcr&4PMod3g=3z|9$mhG*{MHg#N!qUlr%E}_5aixrA#@d^6p`Xv}_9b%SLM! z^rhi@)7T7dNCS&Fh9zHQ4%R0xJL(a`#{bYyMSD8f(IGA0Z# z8|Jl9tbX1CeP0oY>e4r&R<{aN%C3`n$D?uSEna&v8-s*A@Vyl-aGmsy$2oY7?q8e? z@)D;GdZ=`1SL(l5!ehs3lA@Mf>AYduXyB4@q+cjX)cp{H0BwNAk49y2+F;oO5?ep;0+)2{ct5YOHk5j__+Wz$Jc{^zZ zT&fXW={rTCz%b0}7`E!EfVrI2LfOLelcI826zVlHA1z-isgjgt$o3hSG(tt-)i$4F zyv*x));F7hIu&~k#;;mSx>-MIn#Ta43dVf>*Ke1U<)%nb>qI|vf2(AeF)}6tFl%Rx zR(9ArR{YU%KkB>l4BCTEtLA^yM_T>mQL9=o$6%E-!x(p!_`s!>Q4YTM-(3_PIZ3K^ za1pvZ%Mjz^he`c19--v^3CP{f7c)$<{JqHo%zSC9a$jtX*rjYg3f(ITru&bn=7CLq z!dUR*(0GHZ)zYx8aEEKyces}D!ov%ku6DfB#QmnWkfe#vsHTUHR5;>2HNEv3B}Q(N zG^WK-h6$H8+82`D)(Ed*}+l*q6jBH_jYS zpDm3+>wWtPu8)FMEpI$Bns=%#s;6wctOq+eKVE6wDcqD~ypK{^p+bHqhvp(clTZF?amWs!OJ%VRW z65csxB4IZzPsTh1%+~;_99SDdqp!rEAs$uYqgytrb!s`h>LEqLH!Po3;Cq=8=d+B+w_iwJWsl|7A90@TtQ>2=ZgIu7Na@u ze94*d5AcwG6Org}Ld>3`OYZ2!a7?;ft$hNFqVs;`$VG89e^e~``Olb^J+MM1@in4z zZVch*`f) zNT-A(jxmDo4Qy_k0ke9RoAU6;C|ckcix%wrDdAT4@xV{-#rmg@xcFjVjvlrRF6QEk z*id)_EC7uM6doHpKNUaSDnaG8QAF=X2Qo`P4NWV$Ew(W?BzJXUImStzwrhDF+($=u zQtmhzK(GCcLAB~9=#Qk4B*1PAb#DzLiDCwB(>NR(IG4+wq<<6en(tsH_&Ep@2n zv~>7C2_^@%+LPAtsmS|UOR9vzWBzP^jtP*q9N$1z zwr%D;g4(bQ{PpW1Y_PNXe-#0Xb@T4I1pf={P3@K)L}OFD$ocK+WOi*dlJ<6`Gs#c9 zW#wXyX)9w40rPM2!Jz>m0$q|3gBluO)G8*1^mhHsD+05^Oze3m1lQ&~;uwc_Pq63N zXBb(B;kngTwD|BA6l*@3^zHK;FK88nqRw@pSyS)e9}|Xg%x}3(WCob$jRi%cmuS&X z${4i4?7o=QKZ95-PZ8BM>M)a%__!U$8@s*1zK>60hPi(FJuf^e+K!+Njl768Y zt%Y-*#|GxqputQsm~1V1o!yPv%kQ*)fcdZfTG7#_!(xg-4BC>oR%yLEkA&N+O3bwC zu)99UN8%uheenlgc$mxpp`S)0uI`tQ6U#9DV$u%H2sDt`rMJ}v-E7&GhHuc5!uxjM zm>l_gGZZkd2j~>7S#hbPxGEa8{bh>mCuI?bJr?}8VNwzn_s*mwY*4v$+GFgR{Q(<{ zE5TQ~*-)d}148I%Gn(^8q8sO&5=^bS(8>OHsL%R0B3q4%{2?HK8TPWW@R#-@<*G~3 zD0NRdjaZvXCK~#cuqW-11P<3HptTzF;(vt)i+g97f{R)-XVN`oN43zB=J^At{#rqlZcXEmDCb{rn$$o6Q zo7FdLM3Kc-GgX9x<{j}^Ns4`kmX=EWT~*@9aoTu7^KSIaBtkUamCrF>Wz2NISjHel zYO9v0Ut=_KOWlv+dZd!IEzgUk@poY^4K_@tL_Xjj;Bt@`9!)nMVm6#K#v6@z+px~9B3B9=V3 zcTA|iP>Ee?BRIx5`93xd4dkbTEI^Q9ns)_B_Wj4>?CD9$gMIga(X%@?@bHv=Pd+Sq zSWV}cNO^O+3@}3uYATYuc%b0cF{satGZGepiD`(g$V9TEv^K&?hurb7d%PGF#^?T5 zcvOT(Q|sd((;j6mY|M@or%G?}!h&w}Kh-I*;90Yh{Wh6$8RZ3-iiWTDtCRiFfX*>! zu8Bv<{2ksz?Z-4Rp(~79fyTo@C3if+iiYwW_SKp9`D&(GzClkd29sPS|&55?>7~JQDvL$ETw~Upf_@Y9dExPD(S6+hlmirc&*h;d_U;<0X$m@sk!$9$8IyCVU!{Q9pV@oO?#9}tUPFAW#R&YU65 z9Bsu@Nk%2~;)Mq*3d!`&*gz|WXGpREm?;f?NKSMtDZI87&9x5{E6VqgC2xC@VC}e@aOLMC{2ZEX)wit}NKV*#5tr#O z$n^V(IN|RiGBnVfgpenq=ki?~lO}J~PXR`|D73iyId`gr_OUkfU;GI2b+##K_v^b@l(3m& zmdTg`z+`mjRUGu#2K^YFfIc~oM}(eG*&{P%ez{|gV+jVk(TKz>)W zBO6)|MpG8+(g|zZk|m=%ldi|wQ)|(VV^lJx6fpntUk_g}qCq(60d0t_aj5=ozAC%t zXec~NaW#A?nT-LfZ%XZ}ut~cMyuM+r2(R{P#DC%;{9tNJ)NW}{TKdma>Iv7!zujox zscq3t@E@|254x@bX0D&BVvgoAVeqablybQQIm|t;a-0XM?}t!i9DuX4^=CPT9o{ob zBUTYGZIs8KNs`AsC#iKrhA^OL5Doq^Tv`s7{&aKNwn!8h=Koyc?*PX1?N3FA(VL4s z*BnF{X*FnFSE`EBH$@?imvC;&FW9FtpPMoq+S-7NE?wlmjn|)Zc=*SkboknE$#m#& zVMbrDI@a-*+O?UEcKqu>TXeDJnE(5%Jq1k8#gR${-XNxSNk+b?0Iff8TIDvi2l&-V z5DzAgS}~y?U(w_;3QGP2t-4{eV>tXd-d7Q8;gK>y9xSoc*TzT#0C0;!EB}&KQ5I= zt=uP_!+tMy@ZOvQ!u#qdQ8~+qC>MT3A*(ivYBT;5tfyt+#WUs*cGJw|t-3B?zD+7p ze)il;PtHw6KaZA+(fL-Yl7#8Pv)!_|JavpVcnh4tt%@Z+mcTk5s>)}mZL5(b6)W-u z_u+HM5r-J;_U5hdv$CLMcFrICYFP-!Y?W8j4KOz>&nmUA#!$QYsVMA#K3zS2h_u@< znNL5kA@a4kKT-KCm`Z^m3lA+jDd_-fY(bhd+dIc!(5d zN2=;!V5bYNRwuHyiJC97(Tru0q$uB_JCR3q@nCf_R!0Ysi;SKIMuh9KqU16 zlnp19T4Z30p(FA2=M}hdYbM`AYZ+eSPnuqwFMS9AX`$jNVN8IJZWP zPaOy^PT~*<4sLX)=ONq-qgB^{R|_X_M$>pSfa(f?%UAz69(VxzJX_JGs)Z}0( z9ho11B4qJ}J7BUm_p(p)j1cdwPeFUX#2^RnJknCM5Y{kP7f7XUK>8rh&S4=_IiWed~;l|InwWtXfE?!hTSOSs)i4D*@y4&r0#mX;X=X zA_bYZ^+Q3C$4JeQp1kA1%z;_q;XLXc?|87r%40*A?%G;{7wGh)hiy`XF3#V@BY)4) zmGx1=aC3b+x_1%%5w=WZn6q->u@Nv=%8e9;nw^A&6TupEwvRAzYzi6O=Bx7m7ak15 za@bi#!0MY;UN3no!uX3i{a`97+c}siZ#NF2x6)G}Lej7dR}$HpVeKWQW>beNJA9>%Z0$OKvutngrN2`od>$MOj;JQRmMh*_7z zk+dycSt4SfKblgD_ zwcSy4S#leuQee^!8Y^rAwIn7UYn4^=17cR+n8sg}&i1Fme_b_|717D!$ln%7e}9Qo z2%70J;d?knkPq*p0prn}uV~0rpfz1mk+Nq2jCn+o9S#YC{o%{lsUVbhJXqmTo9c^= zA-0ma!435-f<*JR(!~5NczYZcwq&jm*Fyx{s7+&}ku|B}xp5OX##pvAN(PKxdaz>d z-lfRpT?%ToZYCW%-Iw(L+*L5!pO2@9ug30;#XRM=U(Os%yMp!;dIU^O)TYvgrc^Xx z%jAhd(a?PH<2-e8`trAuCBsgMo+*&C3BS!SS&n@iFlQELDHaV3M9${$y@|J>kiSAk zty^1S)%PTP(i}1Cc$~Aok8c!Ob5|?&7GP!6^|MBJxq^_WVJcyBdAfM^={PcP1(a3( zaiWV^DPPScc{RC!@flwZj8DV`Tp?8c&Zl;CTeB@R*R{IBV)+}%qoK188*aa zTo8GDYd30&z9(is^dlZatjL*UQGC$|Q-^TVj=sUbd#K5807MY)Up5eiB=c^W&Ip zGUfyOZSwW02xm26&|${~@NO&NduTQT z)woHU^zWlao@XhbTdPBFr)ZF6Df%S6tQGyF=D;yX#{2-xEBnEUjPz?l%-&;YV22bm z`)skQI>ZSTgb~y*a zzBcDL=G96$K#)~yOcjwhV6>D-l+u_9k;0B@Yx*Lux3m+kMH9^EBG)|}QzLKH+XLpt z{@%*MIdDp+g4hDlJ8RZ*x>3 zcZMOC_9CvG_z~y+IE|xX?r|we2Iy~2<=w@96H;(mxf))1$6ktCw-M{Kpy-gDsWg3K zBf8M~AsYGLDaW}H-ZcqCuVV0m+E z1sG(Tq%hjmYdgeHjHy>Sz-CDX7&B1BYekaG%Ij>pw*Hn`bl0UER1kxo0@f_NKAXwp~% zs-xZ>?ON~*UCYxU?52&AdjtqDr&C0w$~+7GEptbA46tg#u|TEQ!7JEIqXHLb zT40mdLL8-0&i&Ks`{rR1rh!L9?-tr@>>)m==})w}TH}~~sKj-kwlFFKo1>1IByYS!LT92WXq^ zS?F_rN~ccMmCocDQ8xWhS$-BrZv4&*k66QVTvl3rD;poLyoOS$!o}W815wWse}d>^ zJaXl7q|vuRjCSosM(j)D7$z%)t@=E`)NeehY$L?dNB?CZgpVRjacjEf;%R%?@Irt#>~fiL3fMF!+5Y>?S+ zb3?9gmH;OEH&HGM*-H=BW}%mtI?)j`TavO28_GuFnJVJbuHKODtKyqmwjHGH%5YX~ zcU+nMUhK02GCrS&k=1@}NC%RE1{gjU4{ho~KIX|c?Srg}SPPi>hyExY2W+QN8?#XS zosZJw3-08bwH0+vf66NYmKYPe>?$ujoVq{79oyW*KUR&$r$=WCbbx!g+BGzO6R$bagl4`0XqHx%U9td_adDp8p1?pPb4uo8-d7 z4=|*ihP{q$U)o+P3+=KQPc=MK$b}viydtpeo&~`Su{@IE**zH(`x}lVA`d{r1=BeX z=Aq}?1`x-6*YJtfJ5X3?cj~uNh3EM8AT0+5pc8UM5Du90pY4k@y`PI4%Q8{z; zw2(B-`$!B^D1Qjz0CPH7qo}T6p?EMg6Gf(_qx`A4BskrQ-!v9g$p&DYFF>$UT(&%) zcJnizOfi@^l=kTVRA|?(iL%Qo;)O5-ejA(AdvJkn4KSzV55Xb8w5Zfne6Vg?T)r(6 zb^m-uIA51WcDWe~toCFY57r}KuD#4Hfk{c2M;9AT+F)oxk5*U0#>7V8PZ zxGY`jTOCK=G;Jwin8EOdhOK%QU1PQE32PAwA{ z=8#+woCA#iXlq4Sw=2SXnu&gF9D~eXq>^riS7Fo&Oq#*LKf|{KG#-z!)86B_`Y!ZB z_d|XZjPv*`3_!u3$6)_9odi>lo8o{QemK2a4gV}zD!RHH;}{Lt4#H|wfJu4ateADJ z3o1F1iSn@-UD*QugYDu4n6<~XYZ5S1MX(K&{UkW*_N?OjG={0zQXsj+9z*eXmeS}M zl*FmG(M{Dc>DBc>adFEn91|>$^Hc(+t!8u-h-DU%x;{V|qeIB?>RrXPW~K0* z@#CvuyH5R@?R>PCjq|Yj=Ao;tbTvE)|GB0vYE=KBkUr&N?iWkG8bf)j{unU3Y$w=DexYb+b|z|fA()ng z&miZ0k_EGMN3os09d;U2gqIAwkF&;@LmCzY3qyUw#O3i8vvB5kXJQ*tC=A+oOl&oE zE*U#N0ITNh5?|caMr<|qGUg3n)Q+c($eaWR_tUaam9A&8!S>hqc&a`s9g~RdLJhf} z4O`8_=k0Lq(s*p|1ruE$F7H154sQ3;pA5d$3svRDi_WfrWOMUdY%+GX7y_qJ3^PE! zX^ntU-yBi&z90!1Yo0`4i7iU;^-t-9L%S*Po|>rz@n= z0lkp@T9A?~hnoh+-OR>-RcqBl;$@Gn7uh)9xgSY3k0RP9wxbuI6m!W5BWuU^A>Os3 zIQ&p3$DEZ5k5*-HK%Bg)I5P^ytoEKlr-t~7!WgWIUJHu+kq7apev7$)nMp|&{hEuP z-AVgj$74;!K(an$56S(w0qI57iNDTmB}Kz6$$P&_vC&``$4rz94;{cf%L^{YK2|{mI_-^T_vHR}|4l zgI>^{N?z{oO?KV*E>79Jonsu~od$)6F<`7U9E*>={twN1l#TZ6UWP{bC#fuKz;yY^ z8SJz>i?7DY9C`#7j^f8TXL&`y`Zst)53;S?lGqHJjvh^HMY~q@BDyJENzkDHi5B8x4v;LFX z!PWVXF)jc8UXZ#4{C|zdaKQMCf1tQqTCDsuEe}%t>d}#f=ygMR@9l5#`fU%XbzB+JdmmQpxl04H)vT4@&=UZ&-O5K9^q^3Ded8?p1AqD? z`;^LLlR0XJF1qgJceq~n1UEcq8g{0?@eI0y|8`Bp*MGOc13L7Sx}j)1)}s#1QZttF zP5z=&6ShbP2Wm(Rb3xv9&IHWD^?Q|Rj-BYL<>yfS)2`@LW}NDFTQgpGxCg^|=b3%D z(dZVgEe0)NMKK&l+`wkD_u$|Kt?`7;H|XBpgHd#XjdUpI7Ikm9ifpxdN=vLN5ySkF z_t0*DaqO0??0LoVB+%I`-X&9<&FKEi_LnXFmy~9k%A9OKT4b5tnULA=OWn z&EKwK=MEQf>R}V?xdEo@R+jOvr`00J$2;~1IqtcjT=l?Gd3+EiE!V9Aq0AEH!NfJn zJ9@XV-e+%)=_(u0?f^{W-{Z!N9uDj!8Q;tRvokI>3Fhs8Nk zEV`Z+O1|v*gJ0|mKnGF^MZH$t$h!UqIVMJa1fl@5FD_cy!XuV$w#i48V07AMzZ-t) z(YNH;sYiUke{6mS9FhQ0ArQIe+xHQ;UKZh}V_RYDct*^-m51(MjwGr{?aBB~DJb*o zE%Du5BeG{mB*z?p{~P#ik^s}N_org|@DN(ur2s_)Wk^O>jfwG&)_ewvi!VF|-~q!* z|0l;DefuKr_S+g4j_5?kyJn-nrV#Stdk4~^(-D+=^N;vxqAr;MSxj;_=mlbb~ozgmydq5x~JTGCY?MtAfijlXM8@b{$&yliF|>rHfCXl zsT}eK=PHwNbfY8fQ8f-(Z|X+6bOob^h0Bre*>2Qw>jg~4wU>sQ?Ln6S1G~;Lz_i%j zWS{SIS^T;#ADwNlhs;)lxc5VPdAK^MfoDZ9Ol-zSZU{KZaTL`#X^9L5 z4wBflysIU;bFD9(-=&8%ze_icnI*rWuLGuL|4v2Dy?)~3_4%mte-5aZQ4ZOa`Kpjj zbg{S)Hk`yd9?Ua^jao6)_kfcnxNwjKUF>&Nh}mq&r>-z_1o%OX37`#g^@Wt#&;?1DNWJvTl??M9-q3(~2AG{&A1T&rZWgNR z^HIn0c=YhnArhInRIu#;I>PQSGzJ|H_2G3mqg_5`vx6)*iupi=ZL1Sq)2AyxT&q$} z`PG7cty+idGR*{+r9on7=v{$f&dBD#?*Y^9x31E6$V@1nI|@}!P9@>J^mtr| zPvvpmieR>&R^w9f>VO(tv=|01f?=Xa?Fk~ix8kRZqrsOwUhMgIKQ;gDx{g31n>8H>Gd$v2O?53R|9?>0+1J~`9zRzAO`aN30F`lwBtlC8wfO$V&`M7Qh zYPYfw4ce4QD+dLTXw7@ds8$k=HrNS`dpX%}!WU0|q{>d!8Ro_Ozm(1?!;g-*3Nt+t zz}fExp1MAddJ9LyfVcV_qakCo026rIN*PeL83m*PCNCYutXM%VSdSK*wq|2H%^7?K zifz^7Rw%I3u+zLEVD-(eUdxcllRo5iQl6k;ctDh*`;pM#3#h2PP_)gR$}!F|MjtRb z=XI4=SB0Zfj|x$#u~A9Kw-#h&xdIsnq~qzo`*FP|3wLBXX(z429OKedfd4J?#N8&l zk?S{p2{qfp#6uRFiN*Yr`0e)1VwkQmVvm5n{M(oS#xh1zIlXrr%B4lH-RL3SwkpM| z*GxwC;sI_q#RAe>PTW zmM&?rVLzGtcO7codavj>DvsO;=}7_}?H0FN@8Ou0^5B>)U^+RhR-Eht!ntIgz3Kpk$Nc5Jh{yQ7MEK{2KE6LHUhN-2 z!pyBn+u|HiBhQaxZp&MBC157ZwNUgM7Jv@l6;aT)KvCbpS=CJ~jHk+{Cv3vH!LoUl zx9HBhQB1VNDgv`yb7E|?g?O&@M3pPviT#UwNaI^8GQZ<9@!_x?91|*U)kgzn>Ew2b z*~N=c%vcGnHMK*kL6IsGy+{=02|eg1aXbRa=i@_sN;4eSp3mXO-E0P`!Kw#Y=rW!x zAGibw12pNf`YGh%I&<>7MUz;!!HZ+wz(E)MdrkpNi{+~n((b`17c6s>J)F^l#zU%& z2b_`f3iz4l!c;d{fw77pcX9?Ey{Pzq;)~ReIwb6P7gBwCB1(DLmS&#mL3Z6SCSN*# z6{9bJ-xoY-i{;h00LDzSSTXc@lki%t6xp1OMtj%htBgZdpdw}hln(P8qvTeEy8_&= zmzQyjS5^*Q_OuBPTwH=*?Jz~v*Sb=vsTSM&wj<{wv}pg&onR<%8)`2f4J`u9?$ox* zKB?P<^P?`HRsIR+)YS8;hu3ECihzZ1*JEfBLt}-7)G;kCn}K2mw5JA4kWLM7l03JT z2o~AB=|4J9A{Pfrx|emR#@sxCVS394U8@0eI0!3$T`#oXI<5?P(qqW7LZy0aI|!+t zsKCqzifIa2n}`|E=K9N{R;*y}Z`D!ie@jDJvqve6UfYvic79BQ;F?{jN5`A~Q8LT` z`RlnEFjM3ADAj8hiNAiAp^h+d5@QeHCnq~Y2shj`n1Ry$QOMmAD$8H<@DnyZ>I?Ce z16G!xte&pY6{#gU6|65BWY|ibOiGdVeTo_lBQeA5k`KCk0TcHiTKT-=b5SV1hz5S@ zB&<$6u8LdpTJXt*hVa0*_)x11 zSba?}*ydDWhmrTWc~;|@tJvFQ4G!P_74>wHXkDW&?s2-2{xeIY*S76Nui~ocl7Ij4 z)x4Km5wU>zz3qgOdQPJ{J1(Ii8+FBF1$$Lb#X&r((nob0>rY*ZZTrgN3ubR<(EU7) z{xcFk-W!0rH$>5#`xW>J{wMfW4Wj>$F?0rO_dS>@a{+iBwM zOXxs@5-l3CLbdWrwerxba;#-?mHXV5`jy~GGiB9xhEG0jkM!`_&n?lhs%EkKB0Zu9 z$!moT7UF`13k3~w7`GkkOxR6pFJm$Q6EwR>*}FqH&AN06jggFKez}#Zhua+PbIVlU z*|oYbH3VjJPgOXi-%T)RI*rxZyh1fQZYV1jX$#XA&mtRoAHaKuJ{K+<>5JnXKjMq= z{v2a07lnC%DLI&>JaqK{t<$bRe(#>pV%Is6*J{uIi7$HI`i)9sq49O65Lb@{3#twB z43yZ=Lu_9&0U2fc6La-?9RG4UdO7Q~s6IrScm5pcyLdWdMFslM z_=+Aseh#T++!TG^*J7U$IXobpHCAkA!UhVWksp6MgCozpLPeu@iAP(fp;`Y$kg}_q zq*v2^v?BYVSZLCn>>ZcDF;w2%Rsd#Q1Xiwg*iSFdtw33x)zoqSPmH?OiL4dDPSwc^ zBOD%5%zbW|#=}#jd_HZ_@G7xo+Ho{1D1w}x+JV&247BX;Ezx|85gDy6ucke`1>g~= z22A9wH;VeyK>BQO1$x!tn>4b$1G(906xAA12Uct+Fj;}HQ)oG6KDTV5>kzn*T^*;u zUDp{>Q~iTz)|WtH(n6cek3WJmGuzNNR_(}Dr5|5Sg4`o`2$;G7L}9dR1?{O{fnsB} z(MNN4k*Xo-qRakga58v;tBIKSg6X7-qM)>be^2IfTY9YvP3RPXu1G70P8)R+8<>Eu z!We0voPT)T19y&bkTI_Sv)ez$zTX5)Q@>n7nTkf5a4VV^WbYPzET4nc6O1#z?d9SN z7VE~GlbFwKeMmTNpr&;BM^6;+2$9=&pW$%(AQXGhiaHiPz!xtM=9tYg<`ZCWLCA=a z!`jn8=@RmUUMHPhG9OpjRwc?&7$G-+o>TaroFzz zt}Wx{p``OeX-0?MQbq?0X{PHoB*?=_%?$JJz=-Oz$HgD;f3s|jm*5kZOU~JcD}Coa z=NgY{aN?=-Y~TSKtoDo=@d?{Q19|uZ3+jLLx8PQwC$a0f#UNxeu0P%Xv8}X!sT#-R z!eMhG*t3F9jaar-aq&V>s%3qp{@-`eNehC{(oEJXBEG~rQcr<(0|1V&pGVeXM ze^P=EbZkvc-z5u+BWpzKqgSZLm7~IxPd4;>Af#*l>PgvZ)a1`vN5K5>`)WUDprl-r zbqRS7Iip;cnM@Yp)&i?>1|&R1t=NiAf1i+?^3COzlvCqD~Ryqj89w?b}K4ItulT zJ-qluW`mMp z(&f*Z8DM;Bs}y0Y{s<3n1*-nk9ksSjBG0r3a_8WtzBrf?i>jM7ji*E2^I~Kz2 zzV)(H{V_?AIL=V$voKw>&DtlJy}uwW*r6wGTAra`m_hKpft^i1z<9JSQEVP#gZji) zpk*zCP^;#BME(3LA>{LQtV=^U#x?OSF0Bv7y7x=@s1-ZB*IVN!c|M$nZM42Ag?)LV zW&C+k2Au%Vil~jh5W;7z!A}VdoX;4K7Iias}!ac$-#S^d)%*zbM_em*6tn zmDqR_<;QkRi`zUa7w5)3z-+7DZop=`q~9~F)^C`w`okU3WW^_3+4`EOIO{D=HZ|v% zM)_2o048)yog(PbE;OX?W%R>;pcpjUi*&oVt;EYQ7nfbfe4^_aw1>8(As$=J2K-sF z-@>TBXxjIoWV_Q-p<{HRn9~7~yL~P3*Bff$n3W|0yJ^GaJ+u>Gj_oK=N9^Hc26&fJh`oq{e--rjKv(&}(n6A*xjpJvXOcl|}_%JrwWvj z-#9P7i(5X>#>Rc3_&$wo)y)s66Tj&Z#No38N_u@=Ts0?(JUrf>jJ!BWT+?qc$3)6< z1y{h#ooT7)X&8sp!zVn$E0 zba)K$=;@Dc2i_EQqW6=tq!+Pq4i)Er+{!VXJ^7Qi3^4y%^c&H7P6S%@sS^2l5z%S2 ziRw$KF4FQ&!g=uy*y<7FMM1{O*N}8ypMawvO#b6gSq96c=x#m90%r|5#3vJo^&c0p}sheJ{sE$e3+_QIE(f zs+l_-scpE5tOf=PhNiKqL&aT?)^1Qf+>hrNCj8F@H@J=ez*-lM9}W%6z-F4gh(n_z zu{*a0*}c)BIyaQ$tWytiZo)fpa54lE!XvPEDPK(hU|OWDEjpEAic;HLL)OQF(4u)6 zs@z8)x$dv|IW)^&Wf?0PXYC}7 z?Y2@yb)I0H(w*L4I9z%T*O{Wu)LN%mU>F5RNdS`$7#ea@vGqetN$tJs$oyd`nxkE! zS~(;@(0Wh-VvBn0K2vtP4r%+5r(-h=Q>>Jw&qs4Q`bz5y^abN41G*U|bk3}rgxb z%UCh^mxABkYCzLW1u6R4G~Ds@5#-dzT1uF57qu^_K?W_4W44+e@;r0_V6GS;Wqb<_ zYCX9M-LF`MP8X-Cj?SzQSdYM^;wkppmB{7TlTu&e@~efs#C3NF!c?Obe*5huEv-t?rU>%x0TRWM&#Gt7^###)}`C8RM_xyf<_4D`V(> zG~R+K?^3*@svM6k>xU1N&O#kWxzbk$oA9lR(ESMQO~2pijJD1ZQTn#Fgx$0*uonQ# z9l!)n@>PDF;ZJX8S0T+&;h;yKq?+03q^Rq19lPL*_)~-p3@7E_+8$SMfCy$L7fNvC z3N<|WcdFp5a1lLj4}gitq4?j=UL_9~j2Ds~gRR>cH;!owZ)m_g1x&5CpVBaYKfSuL z3aJ`Wlr`pts(IFiqWYa0Y<8y@r}pTG9d^NN`iWB9s^&Vb)G5F^Q()`ZabbFy4o@DBmqep!XkLM^{fSrl-H?N{*}N zP~Z2^PaARuyM1VZC+#_ko8pS`q))dn8%`STQ-WTt2p0Q>?LxD}P_pO7FZ^o4N~9f- zCJxT;Oxk^l=a^OUR{bkrjA~{mGakoN*Pqu={Uo=NYj54~g2jH6+2*j2y3Gqa;Q!at znMdW+eQ}&JG#HXl(LjbIN#?ruoFf@tvrI{bLdZNPb0rOEpb;TaNlB$r&pr1kr4*qu zg?K}#c*z{{+vhxM{aWk({aNQew{!MBd++b}qWUGS*ZHmH0S+sqU{PIzhV?6wmfK!H z5#}Mp@ML>}jABur1F6ykz1}4B*h!ALrwVRc0P|dr2ur?%((PAnA&t^?cEdMzCUK>w zsK>}!Zi;HIZHePHWaIUN()lQf;o+M+@whr$k9Mm{LTFwf>3yjknfoje#of!2y4(jJ zk6*_)<_GKo@Y`qIu|P-InH->Jpbl2RX)g4aevLraat0 zxUs^G8eG1KuH~7E2@ejDC%FN%y5SX9=dri+#@=7<@HDEq97Hrh1n8CPT71aRjMBVl z^s;ge`R-naYbQmZBSjtPON;g-;iVhLj8$QJ0cKvQnP8too7NR$bkWd3DEXA7>qA?^`kN2KIp;XJ|tXA!dw3OpzjwuL34j2 z))`^LF)6S^!%OQAn5p)*!u*9TQf|}@)Hh)a^4GdVv=8jzn7FVc-j={jxMQ8uImYo% z6V^>hz-C_v9pXF&xm+G7v*+7iFS!qUwGy1m zJ^sb@qjI=ojN@LI#w*FfZATi=mWq|4r;R%O@pcvMk>Mvcr4FL^st-{6Zf6w?V*@)h zoHq`DIoCf@$a$_UIxoMD;{5$lfnzK&3~fzW{f5nWZ2k^v${;jTp_YduIy}Z~>YJ&I zs4xC41@ycl6u2rBy;t0n4m|HE#%^m%<0^8bEgr!l!#q`CrUT|tL53h-OA#$&3y@~S zeMGm!5rfWFl!*g-6lG%jKLyz1_CuaY=YF}z%^lUEuHsiqFG+jv$0A$9?F#F;+a&XB zAMD>p9rww6uc+7(&oK_Fq|ga4yRY35jz?>v)YyFVq%l=Iw<3lJ<0exNe-N7ebqc$+ zxsJoZz9)O91r z{HyAIa05*2@N%IpeKdNsBp=Q0y9)mo;71x)nN#LX z+wY}(HHx`|{_h@lv3(|X>aUM2O-GU)Z_-4)K?kLE*IkKofFG7a=Sjy*S~%t*90Y*b z514fKRN<0qD0*ENa8Sy1x$8Y zXS?EUfhc350%eyO%bsM2lAL!{Fw4C!UqEguIg@v(HqM=k>jO@4iEtL&n*SV3)Mp+c ze$O|ceY)DT;iNBlZDvZQ{7RB;+5~Y-PgQ=C2$*kCv+|bx*o+hh@{sM!wlv;pw{n%8 zh9cJ{8PB=3`~QgtbBx(OE0GHVvW&pEuNCS1Z5x?awdhj$`-4;rEQ z#)Ii4yT5p`Wm{qxQ7+X}AC8%>!rTB%X4`Xl4@M=6+nlbU+VeVSTaKg*IX##fcD#x0 zp(&Zkf7rWM!&vrXyw|0OV_3H4QbS~yVH4%dYt`bF-qy6XX_|Zi9<{PRl2#N(?(N)B zmMZbM3z%7>+vEwRxx#?`IcV4J^XU8dLZzkEM84Uub{=-o#TqW{-@oJGU{lV&+;!3N zu7zybqpwU4Wr$$|dr|L&1LTkJtduqBaIa4y!&Ji|4F^FrVDwK9v6~WQAZ^^3jSf3# z<5^`n$^jZ{Da&sPyz2P9084Q_wtT>KIxxWki3jUXYYMeT1&@}=`{K34Tg%mHS8(=Q zVs;31(fp~1ThP~Gkig2#MOYHVf z0^XZmiL)FVcr}Vyiq~r%!}bBC=+;bqIi$CSd?(XKmR9P@Mjlm2Jnk*~?8v7K;}8Eg z5DR<&Oq&{gL21{GcC5%m8PZPl^;d-Q!ZEg$@6#bTxd z)z<$BO6rtD9fq7o6S@kr&-Sa-qo@eIbFq}KKiA}|Nm3;qKL9gs)LfzX*91BTjJ6WP zz(sk-apjr9p|r`b5a+I|z{`twVCTOuApvqz4?ak^`{di$ck%?hbB8}#=zN$~ImP2H z{#BA^*#SE5%Vu=rp}q9mOXe6>^n%r>m8iG!YrRVl=We0;uIXrg!$qXu%}4oL;Z1Ec zOW_`%6g&L}|5b||Jh{z1J{V)OsSpour-wgenWA2Qy3=~}^~IhlRW^=oJ=7T2zfZ#x{<(_F z+dst3+Y9m1<|oK;aDnvDF%`|w3?dmOU-A3Ulj!~Bvr-;+E__2ZZtxEcb?B)~+2T+8g2^XaR1XHZ(t6{t52B(b~N$?Wpp%{>v@FF1rd;iQHO-yohZxE^xQfy@g<4512sD|1cdJhNtWt zLN%S{AnU(sr1O+O{JZ-$l)Iz@-K_VRZf;jkm)f|akAQ)#(*-cQ2UiL>@Rc-!o$dBD64q5y}raP_of%sagP;-(aryg>t9{K*@RGKaC>xo=>VBM)5=GnlVQem z`JRvPyychys)N8CFi(=3g}p~Tq^;%AXiDZ79PE-r?sZO}ZbeWR*l`)IQE%Ypudi|H z?kt`WQ2 ziKA?u=go47LNObT3VAC}lZz(dlznMUu~3RIDdsN?jk|{3)gN=6+dk9NaO=NasKJ+) z!qp8gr5m4KOK%^q5!-5O)5!C_bm!VfBE#HN9Ryy08FkTAd^CTs_@{Lwy4v|VLepc( ziO0#5`FOCl1ZE(}8er7QV5H>5LtL>EjGbV5b?~HDlEDHiq2^gD>Bj*x$+5>J^d-4g z?D$oOy0w&Z%rzCp7cg_1ZNz9ZDn4HU+IH0sP?xe;f*)t|p(WO8#qt|=(dBq29)H+S zjwANG#C2UV@ZB@DQncfSsl=?aRBv+(Zz$Hnt(>1or*}-@7^bKUpTJSTtk~or z_FScdrj{N<9Y(C7@9kp9m)n+n(#v}~$Q%QPh3a0vLU3w$5!`>i;El>BEmLIYcR{H0 zXl==|q*3wqX9h|g7bhv`e8|UVgAPdB!n+{$(!5oeEWlV#G7{ZDd34gyV6>=bJ9&EOP24}HUeP2Z@>Z)p z7P{5TelGyg@hi3b)kYatpNdNPiWTvjGG}m+-$1u|%_-&Mc znfdlVLCQOZ;vXDAda)t$OOHHhBUR6HKQG~N&}L;0h!Js36q zH@@>QkfhJ_K+CQNOI!O#5}iRt?-eu;)MvZm_{*3|QAt{VOwKlOIC*&kjKg+xtt#+DAz4 z0#kB3`JOaq*gTFo0=ocUssMAdXNKK*$s2`l2tY|JEk#T=Z>Q&pDWP)*R z#12imR415YhOFS2CcvDtS67Uj`AwYZdl2>AQzbp~%uqHZg;OtZB+U(@Tp5DHdR zjtc@Mz6%(hO2z~J=#gUMwnXP|Yt;5pFB)I@0>Am(nw;&_k($rj$uaFznBRb@OM9N@ zq`hC9-Q5>0w9!KuEwZw)K91^6E#c07%nOfUCJ%*~H4tcGo6X)ODfr0LY4VY&j`Fn5 z$HjM(t?B)GM>%qoqny;nlx}v!Xk*A)R0|l`)7srsZ{;{+e%|qsr)^)kd80|2^3gZD zLZv}c4y{-M_TkB|RYOb8FvAX05zKOrVc3^8Y^8}j%*8-H2PNd?>$*{S$pHC0Jg-X} zXw-`5BEx)zSO73OfYJSvWIKP$CTYFbel*5P4gELdnsSb!h%$o>)|}+L9Sj1XA3AKz zC*C#0?gg?eA^xVg0tp(GK4&^7p80Gynz#tYI9LVO&%gL%__=jJGSR zdnf5a`;GVO%cyebMdj@^`P8vAA6x8ug|!YxV>Rsu+{Yt*6_{;6Q(x+t06e4fGc@M= zU;0?B19kiAEr04}ERU^hhg%2llY8a#;;Ttig&chWW4F7zV7IhCl`eUrW6gSKzhSg; zenm9Rg_1X$$Y)oobi*x>HLB$j;kGb4ecW&nc8{q>wVCm>_24DAQ`{T6!L^chC9ja~ z*&=F_e2}juTXm&s1(+ER?Sx62=g}Q7xRf6fkM> zoQtXBcPKk#7T_0gU9sBrG`xOY5zH0b#%TLBtgN7D#hRDGux0LI`ag?F)irRw__IW; zy{sor+588uFAe6HkE)k86)?o=if}nGk{aw=fwW@6(Ba7|7fFOVHW4wrH1Vg(sfZk!vYf?uKPxosOMw6R25u%)E+?-5zj4nCk`KkZS!*Z)HmyaiuqEE)9(F72TQL@$44Zhj>dr`ATG+5<3JF_O@FpC6rk*AX3CbpxgBn?#mgFqWBY4x3wZ zdg_SPK7cYD^guBqwAipJY<_tFj(+h=${%+QwLIBD+O39MXj24=Xs1KJz3WYWRE2Vk z>oShn3YaBXlF)YGYMQ=mD)NgPiS`WNNleppWajnl*z*#u7_}cHC+}ge@nFae!{zK) zdpdGHwp*h?mmiHlRUxy8%ltx|IWZL7KVwMMtGbi^g?l;1R<)YFfLWkEi_eSqKm&G`E@tLFfTkUHyA9-^2Im8I@7a;J5e_fJ|Alxi*Hu= zqo41)QLX1~NgL?DW&byiRTzK3{8v&TxXje1c8>|P^PWLEzY|FKf=_&6r9KsuM&_nr z!?M@-!F`qGp3TZ8?0o4Y{$y%QEuskORcIlz$FtLPly!9=&GlE4bNzqNlBH|VEI8I+ z>kI>oU%+>v)8Hh@ueX2>eCvT*d8Lq1+j2Q(bNee0WO2^iUztD%l#LU>S<6f*9n!mr(A(IH5OQol7cInIh>5}||#FD(r)ivFX- zf363LBfW>BkNYm6q@Slrr^mS}nKrm;C^%loZQZn76L5O^eO&hhCcr@@zSXE0DaF?% zZ=d3x)Y#*&9fphiF{4}IF9F?Y;mW=oW34Jh;S1K$^?QyfHqO7mCyQBA-~Lz6(VgGJ$hpcV;+#LzrT79{7+%uH%bZiB zn9?wgd91?J0;bHrkNC6T5NaRO7u8vhqLW?!;uoWjiq(%2c&kcpTMyxmDv62L9&M~Km-2H zl@eA&koX>5$+Xw@(h9qo9J3leXb9E60p`>73xeIPBgj#wH){3xlw2`ozpS_Xw2nozsFV-i#%IeA#H?< zME0dst7-(TO4VCUY*S}<-`5xISzv@l7A49t7N*L#%WOrDY|w$)F&oz&1?l#nC-`Zk z0H)k=Tp5-n>=k{i$kxe6Nn~%3mP)LY9PJO1b^n5bMMJb?IWvG`g5g+$)o1}G=H1_1 z^Y5!s<(6JZZ}Mz8vSpJ}U&j(L0a~pZZ|rsCGJf#!DQ;7=8T)Oy#9Ky~K-0t~8?yf2 zJtS`EEHtOPK3)IYjSTMJlejHBCu!_I&N1PzLjy(+Fj~&ld422<`n;3?iNMXA;YFOQf4Pj2<@{O+Gd0 zku--J(hyJ8YVN2o#(;_J(42SbfEG%K?TMc494I~VPE|H2L0|nQTs>UP;lGV>O$}x@ zP*(e7?iIld1aF_{Nj!p#NSk-2sLgO|dTX2pxiU$EENOjTa;SFWtI1d8H|Bs@yY60I zL;P9ME7B14`o0!TxRa;cXnS93E`bJ^(-l01wto#B_;1UweP}Vqu*-Y(+SX+BBOCdA zK#^EIV;Eg+WhMu8Gn0FpwxS;hWC1`@`Ag}?9TZ(a>hHHdiu-pLspmiwbX`!<2 zp(#&1yq>-0`T|;BHMl(BIkv4SIL~>2+fv$vi!Hpwi<;^It(A#wbJNmxIUUu1Vy8)p_ zOC1OO4(VCF5* z6rSssN!xpML!H8pqAfEoDJ%K}(9%}Wo%*=}ZuCxY?Fakyud!n{C5UE0EUh?-od-Py z0pY>&My!S>LPS3I`=e1@4aEW5dVWwRPT9;%Lwr7HS5c@R!s&|NN$N~i99 z%1}4;wz8V$LcSU%bqsNuGhnXw-7l=#JBey;)j^uGi_wPpVM=q`9<(|`!7Cnpr4_h2 zxdgkt0Wr->U|u_}0GD_oeEQT?G=5tgy*=_aF0;QWJjmKc*F^6|x<;{L(&`3|DO6#W z1IB4#v~W$ah4#(th}!3uqLyA8l&RO&QsyepbfA`c+rpejKDIx1n-BiSv;)62^G|8qJCFO zP`|I%${~A#d2P*RWeL{rWq{T4ul+wGpi45a)4T_$b48>$pp{A9k&8+`>rou zN0Y@3Z|bqhqX3S%s9KFDU|zZu3Ky)8({P7&NL@#il(j)}wMHVXZ-N8)8^tfSwFhC~ zt9bfAiL1o3sc(NRing!SP@LP;4c$MxpUjLaz;+$Xk=c$hQXlWmq}PXNjybN%2)qIF z`*E7^>2d^J{Y?#}X`HcLI|qzrQ*KgbxyK@#7x7y7qIC|=P0hl#+K-?uE(@Ec-$fr1 zr%Ai51JO_aK$6n44!>`N-VGmxbo#e3F>^f4F>_QI!C}C}emyA!w}evloE9$!zB~)$hW6Z+A#5rd8!a9%uGf!7deK#nv`Ls58?UzL9dBABj6uMKJ-`C?UMX7b)^CG(eJ5gCUPC9>KI6CQ%vJuzj4B-a1aws)@nAA-ql=wzX;N4E zt6wB)Oj}MWFW2H(MWHCZr8Cv3>_8R;?%|kZSB|*|n2nv>gas|*so$|T;^1xVsZr4} za&(H!gIjia@6kJ$9|X)Rf~k+PsR$2WU&x+Y(Xn7=vqBI_)$}qveEcD_@~j~Z9Qq0W zUOJUy)~i;N37DEmON7iX-Ke443-Kn5gS31&L0-ltatwQEjy)2vqu(2@KFTm*xeYuc z_};q*jnA2lbeeQz_RKS0f?hr`p?gYy!lN#a=(Y&GSkAXj3K-9E?m~yU0;%BpV^Pa* zKDxFpnf#pP%MH?*25~LDhO0Zi=Z#}AQ)_S*`N)gK^ZW<80PN5ufLS&Cs1V%UO1k1#C3=Et$f&e9vT4C0j?oRt!1fr7o+0tj zI-0?M8>Vy14uT)0W9Z`AU80SVNL#EE>CMD)ac!bL-TF~UU503j3=^cfv#9{g5tC>k zF}ujl$L_8et*{q2*+-MohSk(!DkK?)vas_x8H&U&aUcjYFjsk2BWT_R8TP)XlBL=d zvDkj9)Vio0H4NJzx}WbtCtHu8L;n57F_%@Cr+|s8y(sMZu~1w+{FeCieX=;rKbk0w z_VbLu@kI`{nM!g086ePz zOQ!Sz$Glb@YjuD@;aS2my}Ke_RxBoXzDG8eQDkCDJWc=h5ZliH1sIt6W_mUiIk8+B zmZi9Xt+H^{@EX)rV-q$wl%R0>S6^~Se z^epxqdmQ;?LSvQqHPiXpjoJ{946p&yA&Qn zv#E%HdC^GQ$c$KyPZb}136!otSykuh8+328w-kP_j$@)!m`;H4d%H)N-N6SvZp;z$ z()DSVHr+|OPN-;+15**~RvmgdSm*tZt@?QK?Xw)i6fQfIt-~7voS=QDMf`nthvYbC zI~fT6g^5#brPQ%w5&NJAs4)6~xisHF7(F=%{i(?jH}APGXHW72{~9gs9`^;AV6BO& zmiVWc8rab61b=BvphS~v3h-!RE^*h-F}s^HcVF!z^?&6{WCiz1g?72iCtmyc@b zE9)L)RvL9K*WJ{;A{Yb=KBVw%{ zCH?!-n`5kCPlMHr1kBO6rn~_iJW#S*mZ)&bqgLk5%7<&FKymUkF4W!1-LXsQQ|^V= zecwf{oKz~M;>LR;$nD)eB)-*B)Ofc=nquNXa@O@C4X;i~OTHiF7;D&}0Ydq6XtDuW*x{=5ayTfH!Y7ap=M7*c17=l{j>0XkBl_4@5*>x_&|{IT99Vcu ztZobD4d9DgVRVI;SDBM6Qy*;(ea0_Sgf+&*!Lu)^J8z9@d|tWV5Wy<xBDQzSJK5{4|g@94N#3ZPdtvpayA1H+yvO<^psLFmMno22Awy2f1O! zX+na}b@BPX`9P=1|5kY|N+W?|3xV>K$DcwO=vn exNPUDn@-2BeJ9#=eQ9eG5h=8SKYRGnTKx}VAbkG- literal 0 HcmV?d00001 diff --git a/data/quadruped/minitaur.urdf b/data/quadruped/minitaur.urdf new file mode 100644 index 000000000..c483bd4b4 --- /dev/null +++ b/data/quadruped/minitaur.urdf @@ -0,0 +1,913 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/quadruped/t-motor.jpg b/data/quadruped/t-motor.jpg new file mode 100644 index 0000000000000000000000000000000000000000..dbd5d1a6e46fbc6ae48c0027ce95fbb1a9e73c82 GIT binary patch literal 156770 zcmeFYXEdDA_b5DiNeH7wuag*p5WOY3A=(%OgGdmD(Mb>zy+!Z64n`SKMvW*TdhbT> zU35{Bo8O23ec$`(u65Ua-}~k6_3ZsTXPtfaK4*W~}Im4+%r6@Z5az9|E){K*yL@?W#ew2UADCQQQ zFs2N9YZchB`cEk9f9yl_?@0e$DS!YEpOA=zn3U|_v;y@%o%n zlu{D`IfaQ8^hjv9EL~_t{NwVfezlLT&~YmsKZDZqya6eZit4)tRFD0g1KcP0w}hI2 z8t@#jw5BCGO7nm5|Bwwlrv3u(T>A6Eax#bBjm;Htztsuq!GKX0`<;etQto>oZ^1;yt=xf?9Z%Qiwl^vBkge9 zDSM~ge+a_jWobl+0c*$*vEQBc+9@8{+VAam>VWut`I+@tGpN5*_iOo3*hQG95FYeT zD_6mWEgOQ#4RRv&M>=JoI1zv11)(Qc39VC!RvWfplT&yr9B6;l94r9FlVm+n+rSwd zt&HCU!WvG0(}@sd{{@&YSztb|6MT6$uB$91M#}k-JZTeHUc%o0@cj4QxlsSAGx-N# zPFVKc@vk77C6Yg^My;WL0Tb*w2l`J>f3wf3o=vONTj;Wkc7HvAChGhJ1kU{a#Of9b z)0Vtm>$Mm+0M^d6?X6?RePVL942FvuI)-~bv3yFK?wDT{c|ou<|K;LLnvp=AsCb!- zUDPQIZnu}eHEyONuRjyu>as5TNBM1CV}`N0&lm6ajJLn!M1fCd2rBaoIHG=I%tXhb ze2>!Y^8f!s`wbN(7X8eBhEq80#)N&Zoz_;4V_o9cI#EJuAoCvaAP+IPstb0hm6A$ zSxP)pxylERU^WcfbBh|8j~Uw)eWK^`d*=-WjXk`PY?VjDLdm=nG>~qRv^Kb%7#0c(|lZ^sTW3tInSE8N%F%lLp`GQ zu8d!jyUU|C2eunqRdcy8&iM1akT>Q!0ZPn@nv248qjLEPW9<$;pyh`D0wiP5r<2&D zVysR9Th{UrgZvH@1Fl`~F;EbX36@SFt%W@k*-a6V<3t7Hlj{lUcgNUFmQ$V6+!!_s zA+!@TXAuM*X%vM)8ouZh*_|B-SYuUHt+CS@`?$$)&L)6T(WOHFSWVrvtz&h(;%8>v z?KL<}W7+Xi6mPRGz5d#Fj_+B%#*-@pvY>ZMWxd{*zW}Zms*g3(Z>)`n(}(0uGPmG9 zUiHo_V&vylw$L@6;GVJxyTpfIp5Qx=S5Jks1Kx4?`&Wt!=KclPg_iqHmS{xTYNk1j zt%E-1E0?A-rLD)yD%U&a)%*&~WPJQ0Ii@0WOsG0#hY3 zYDN;UC}wHy>Wq3frhfY9c$xg|ghbmSr?0-%ze(7CfSKl(>E+ZX+w@~Hs7d2RJeZt= zE5>T7_$$drXR|lUy{B>waWgDi(utXO`5C|QI3*^FzGVM7s&oIf_$;nd2C8==J>sXm zGBtre`ADJdN->k4py?Nhi1V|P=?)3Lmd*$4v5f5|@k#H0M`_-%+rL!#)>k{JEb7h? zw=SD}H`;0&|J(U);}{|TY~cZNfc8F>4Ar0>j~Bu_-)~gQU9!){;9~WSVxYaFN&ze? z{wdk3P`EbPHSgNE`A02Bt+sOCD@J)c4YJ=4BB%AjZZe#CxPebixe0~B^&ZN#Nq>UK zyzgY!{|o4nYs~PGQD-yH{Bv*2r2Q@zA=ht=(t{TvTNHiG9r!%N?-M(gKuc*J4`@jx zKjbg%*C4kli|>6%%KBMy+C1e3nnm`^W#WJz>$WYH&T4`LV)nu-yNj#j(>S+lWWf(` zd>V7dX;-f0w3$ivFJ#RB0xFSz2BswZDnS>RjPyE(yW*E>)}kA7dNfCL_u5g_wXuo; zv2)+zzp6hramBmx^p?5z*s#jA9CokJGCMv-p~mr z-SZW{@ujOMEs9?s!Q09h|80&neRuOBdr+=3jvV-Yb0J?N6{wWNs33ZgSP)Iw|3S29 zIOQ*Z_wwwhJml2^!o9xnptg+pL5?75+&!#_~#b*l+GwK6-bo zurk3;_b&iTtAeV(Bl6ea8qG!63 zD-VxJLz1`*qYlORLT6CKE29m!jR+6f>H0$B+TA&tM{&+#!ug7~8t!4^ZyJK{6Xu-( zzGOor$sZ3_okfeRm+WfDsvqV-IMC`A5iav5yzXDt)`crsvI;Nq&u6QEZ+mdsh4oxd zUSaC6`g~%&*mSpp;9PXDO6p0Q0@PHBwM~JoX&^?Y6>C4OIwu9B+|hmFi_5P)wexVz zYf&u~sD0fq2dd2kuf{*i8GrR>L7z78Tg1UuA|jvm7yH!)(R^jGw*A;07X9K>U0XPS zHl8jn^9$P&=6gFy&z4El+3}4@3(Jz=i(;p!&`-!GTO*?xu%gk$rtQ&r4p2vJySuE( zrozS-yv$qd*XP>VBSX>Gr6^_e{yW_aq?er3eKaloq4Y=QbeTv^O}LjkdE|k5^c8Zm z+0ty%Kb~|-MI6jhW90^KQ<&`dp~-Jm{P8t&=u%!&%YhihWygnXJAy8Pp1gZVC5}+I zD($C}gsm-1zhhD^FYgl|W`{MJR?Q)%sLpScjE#{Xe4VnC!mBoTb{q~*_9eZO{nND0 z*fyMl`H~e66p7oV_S-2+Po+}%*^_QpR2p8CZu|cM-WtW-#{9O8ytLpqqD}f(b=$+f zhmn6pq`?E?h=&~bqixD8-aJ!z@_h{Q>Rtk;Ht7J0pOIf6bA2sBEe`rwuBOB~QR2rR z75G#NGZCA&BDc8V-tt?X01=F2FPSB8ecajiv#$6$7_wxz+QZ=0qett7&X>3A$j!n!(zlegL?+14U&xX%X z^rd~B3AhA|HucJ!8%$+r9!T)PRrnJq>*|#AbJYbOrIROS(iVR`#5Tsxp-!^yRsd(#)$^?|PU zanFhyR{QILYZI4j*itv-_BeO#?kMSm;Gw`20+WY#1eB%w8E_dMoHC}rviIPdoUW7M z#T1{1S=aYcEDUBX19HEhZ?a}ZxTqkEQPsbX&3dIgPU_*e8b-cvu;Y`ltjuYQe*xU} zUE22rCS-(JLT;Pp{T%BZcmDz|@-MFYX^?-i4_;OCsq=?SniQ@XWf?wE@Asfkw4Ug zvVI~Ftrnm7oi$M-T)Or8qc-<97dO+(af@Nt#}t6_kJRiuWhc3|W(oX~1MRbB{%KhE zJipL%>4V`X@%bO>*Ghso*f{_I&y$I4AX=b;0;EsV6GPDn+KhEu3bcn%WL_6im>I;3 z`R=(U6PXEgSYO76yhSy}m&O}nRvHqUtllleCT!C#`U;mFRmo-Lyd9@;S=4%FjkDC# z<-bXT7b25HVBtePHO}B)WheLhI zZ9!k}a^ZeMiRmsv%CADI#s7$98GaMLakDv0veu8|3)Zf-=UNL^!)0h&Ju05$n>043 zae@`q>x2XOlGtRR3BmR>|GWVnQWxRtIVRzTSVxPLxnS zTj-`A`h^>74#K`!eP>p@>!nE1c#8X6`1pvhDATSZCuj=6UX$WhMzuDG=xg0n{UFfw zoY_h6q5BdU%LjB5>f_UnjKc@vJ&y@ws}f2-9GTp?F}X`734VR=$71qQ73_X#+K3=8 zRS9L2ab8oTQ(b=qopYqos{Wj`!uvv75?@Tc>?W$Yxd4QJwWzf=uQr(kHn^GE$~Ggk z?i3v;4Y)!X9}0i*+9Nyna!N0KswN~ruOjO{NzxP*lWw*@m4VapV=9ZRIGd!gM*P}+ zFWN^ZQmK%@^wE~i^yg@dp`zjLL(tO_tXi)LdHd?tm7g!xq4`ql=_O*>)CGr-(-xC1 zAe)Myok-3K32L}zv9^+=1B=jQQtn9}Y&=CiYMZ=FzYVuFp2C`}U_ybn9e37vJ?=e~ zoV{fhbLS8D%TcxQ(0ZBc_w5to6AOSbtGUxGWV?QGL`BJtQ9vA*0AD_1H0Hkiu4dHf zM>^0Jusm845NIO3T@?FNR{dr#Wu@2Zd%W%J;-yeDMPMdrBXd+EUEFg^){1wJOU%oz z{Tm%_3~w5mxGr4Iou*XBaT3@^Vm}=E7Af-ba8DiVCZ!42(dkWj>djVz(V;+1AbQ}X zRsEx9g82>SxbFQAMXyfifP`Ft5(V-^=77$`mU&6{EuU+~go3R%&Zd}rR@;#uI~ znS3b{XL~p`a;U=D$9igMw61Wo{Sxw8)i<0}GcUZhXQ+h@?%qOuy*8~@YtyxBWaAl$ z@=KG}to7#Ek+7{at?}e?xNB}=NIsu-yjyMoAD3WFuTST3hdDqG%k2r$zQC8!Z+U)1 zNnJ2-X_5s^2&}fbG=km?auDImSj7nKpsVK!h8i*CpqiHsrAWsrtpZi3ZW1k~Xz%5R z&(upDO0F!=e>bnch35N|Jb=e+`XFw+sc_0m%vFz8;wPo3p7hC_rY0FCPcXe?I;%ra z*_{>|u)9!ppOASm1fTrXC8r#~^x?~}Y(RmTiTQ!T z_mT{I+d<8`KcgdW=c1N>#fX1=on`<&sFkOa+}krDuexceDht?2Dbi#p8Lah}PHHy% zCO1#V^u_q*9UMKzYvA=u4^-Qh^TG_FbRRZSh`vvMw^BcGvm;QaN?fi}Vj%K9;u@x+ z0Vz|MXlo*I zdwbTqu(FSvXMRU%Ah4GoMFEfCn=I3=>k_bf%x6kx8<#>4bCyl)#}LFkH#0@OFR=f~ zH+3M}U9LzDzU=$>`Nke9JNA~-kLPuKTz}W9Go{R~u*1TFDw5~b?$`RVl9tAzuRta( z@x$g-=tR=%;-J?j#=K-FUyQ>vwX@D<&04fZe&Ftj{K!+|?A)`U1l`}aihIdI*>Qccft_+65fM+;p~-h)3J`K^=4VZ+ zVvf?(X~w=Y+(c=FBs0E=lmEIm42e&5sH@S5IBIIR?OuDv3gR=3QAYx(3ebXU)k4hj z#a!X;rXKw^Wvq|~Pa%X!`(vB;n=hAYK#ofMc(G6Y?KNxc#!1RBPTN#Q(! zUx({|%--3aUye`BofC`&)6ca?0EfL}n(r&rg2va(eDZ3sT}l$N(uAJ#NXJC|5gris zgCn0JUDxVrbe-trnb6zxi}kE;;YMg#UY#Ox;Y6RmhDLpiE%MC=XX1>4`CjXV%^LNstauf zL3}5&O}aOBMt|<$&bCUwf)$nNvwtnw@Qt181&KpU3KdQ7x$wz0qdCECYn@=e!D!lZ zN{&c;A)XDXl|bsGocC+HOVxeOOd@!HSocaD%4 z60U+obSFv{KPeud-YZ}DuJQJd_v8&Xj{l2Q^$mQd;Wr=T85{HB=h3P8Kaq2|*Vnl- z*+mDW@4x?a?8<5qKP%aGAFkbdT3jmK4{`3!qP};W+Y8av4D+Z3^AYiBsB^%%HOU=- z-?A6l*;+pD%RJbtq(R2)O89!aG;x_XGc?r?&6v^NUK!jIUoM6EZai*ELqDT@3n^3M z$!WCU@y9XEZRN(ybuVi2=sB=8itj$!HmOPu(>WrF=mRs{s*b%-ZW{dBpS|bG-?+Z^ z+@|40Hv`?4sKI2cWL**PYPe~oA9)=sVY`s2bL z;@EE39f%C&<1JnkeYeDWyk>|DkIILu;rMj9kJ5X(!$^G1cg^|&AX1W&lIK%%*-d1m zuRV=e9sK$jlrQcz7<-CNQ;{E&^|tr?l<^#rxxU^@F@B?Uh%;9Gm;DqHFSC{W@6Cd~ zf4GI$T>GVtpt&E%?mPSZW{ z!c%7bNd0gPb#lFj8eZ98B8`0!%#W>|QdTdEFctYqSji-M3RU2wB*wQeYgD3ESVc|> z(ThjZ&Lx#%RWK+Ojz zHjrvbT^f?ibO@cu)AU8hqv9Z-ZoltIvs>|8c*HpE@28myCS4Lg(HbJOd*C-e>WVlj z8g>(*yNG8{90*MLG`P49E3;_cC|I`UyrNkGuSxY>ZmwuTdaslXz?&vba`ekogY{f1 z`AkdUZ4cwOI&vpGnfv@%08_QnCIQcX?2V6FDdSar3aY;{syP7Oq4xSNJ@@7gQ)gTw z5ps-IWC<@yp6-zfa^zd!B+7KYJBGhe;7~<@Q&}UFXF2Q*SZ9|i#uu9g`YzTNvG(ET zdAXfN7EtiSaXbn{mD}(tdW(DE0bQ>Y-($u})xApVckaI@**1}#Om4?WJwwN}>PU!H z?OlayEuVWK=%-tEhvi5x-Yg#yBG=xdoCti#zo~8|ur`wN(Yrvg|1^qIYycdU3k3j6tDhP%0@& zoON5iHWlf^mB4=X-&j-6t+zsDlY){9K>d+5;8}P)6g=|gr>3^_b>SpEY1piif}kff zF^Mpjh-D8n#jcu+nJ_t)c;>@jw>f{%pJ2e^NW9)7>TRustgfFV@2*a_HF!_#O3MTt z#j6KKzpUs2-5aW5-v0~0MW;y6l$d8Y%zWK@f1dTt)T`n04()F6Mhuu|ia9XQtA&e4 z$@gm7u(m?u9K~LtJ3J;eQ>j%n$&tm`Oj%g1x2_B!U*k|M^3$-34{zO+AR^Qyi#V@f ze~R<%?6R?}7N+fHes}w*^ei;i`boJFhsJpn@-M9S7EV?mI*pOzIiGO? z0>MIU$8#>q1w4D+LUX*^MF|EMzNURU<4AC&iOkz?&Jx_7C=;jd3}*>d@wKz}N77}T zsOy`7F4`sPB}PAH(wkhWDBCWFeU|<#Q8IdeYUFio3fg^dY~^2oD&q4i8wMHOcJCqe zD{yU^56M!v^pyGV!T2%1B;8e^=->ccCJ*B@+|-l*&PQ4jfpIi}WYVWioS}G$rRmg>U zZ$`CK*Jtr@G&7XF4P#NB)*qqIkwV|EC7y&&z)xV#K(&^Ra3+!oTuP;Q!1dxeXuQF` zTJT9{v2!J5ezA`myzU0@Vx!ffbY^eH_`qQHPi~X%?4N9?AbH5IgN;XYX?}*UUkI6y zmfe(9zaI4bwmLop3*q7=p zUR@kei+8m;Lh6w|2I6y*&Mz|$m^=)61)ovo_o8dZ2YM|@o!>0kG}U~+W?8zv^Big7 z(@m{A@-Ukqr%QS7n^%91!vyQP@_^~2L}!9C(n%WBvt?~q;BP|zYz)MD$lRzkB|DY) z<=JJlYX)kS9Yh)0rXa&>y+8UC%0a_*N(X~KOyp4=be=xrxpI)b?i;6|s8(N9tskx^ z%}$kyk((dgd>fiOo>%pIAFC8%hZZ){GZ5b|iWSj}wCH@|u`6e=YO=s`w(;Qr$BY$0 ziw7d~xo$EGy9>H2&9HO0fe#Mf)|nA&jqu_g6E^4Ab0$trcnrNE{-~-1fzw6)WPM@1 zBhuqW;J6FZ-VVsGHXWYzvI73nm=6w} z>Av1)dB&o@C#>~XOtmK8%!!7bbUL~WQcz;~2pj^rHz^`dBDqsDC(5iRjU2X1#W!L9=Nb`{p$3BauIU9wvELI+@ZG@jI5rOgtX9 zr@cuphWVzFI~E9}|DZ-wvHvIoJneGLUG5f1j0rVaI?{|QtMl+fO3NIKm*1?SfGl3- z+w&oBU_7N7PzjRr?M>IqqGB23FmzNZW z{<7Pb^S%VdRRz5AMm!G=-`Khvjk`@Guh$=zW=SWH3#cn4;`{{Y<@6wqRh-ud+9Te*2P&{62I`(H z%cdt%bc~~Ru~hIZ-4ycsp1QR8|L#!qpELlYcb$35@dA8evg^7RZ`=^#4`!WS>mF)K z=Q~CIftLmY3#8}M#D!+gyzNDIt&*qskD0!#=I7nh#C-jltI|EZ+0Sds*gLv}suu08&h9|X7My9{I9iqcim^=?`KRl^VpCDh)V4Yh~n0o6|pxv)4{Lopp z#1UU{f|c;<^S^EYpD43wWk-0FBXjJw&itnACU8MJ#{mP?7kt)FCZK736@B7>@6uIF zn`uo7{Y*T}e<;j{<<%d9rYu@Ci)NDGPpk}41?S}Caer5k9*BA2qjG=3_Pk!;CSu{c z9;Ifj%AluYlwpQ?^y8;%XAw13JnCO|d`T-|5-&j9R~+42d`AR$>*?fwHy&yPQ)Z~o?45MBIvjNC%uj0=IryJ}XhNCF+U#r)rmxyM&rgcmS&mQRPBKvVAdmeM5_MQ%Rb&ad}_eR(< zZ6_Jfk#>5o%I2IPzjnkV7?>11!q5@18sSbG6uUl{>+(PGb!&){y7NXZlvzF4KF=|j z@#)(In2dLZywz@3M0(+4xx;{TkJo*6)axiB7i*D1u;p8`cOix7%DjTIuo|Q>X z7x1HFG{lbM7v4O;i4UsImA0~-75YwpvFWj1#WvO9VD9*{@dv}UF?yoX=VA-LYCZn~ z(CK2L6^+o{TI|8bv0j)71n>PqY{{6_5RzOHw(UU+?&42vU(K-H-m|e@8kjhg0Cqu< zP$&+Z0Wd`KDpls$i-E?Lo|O!L7=!5V+OI;@N#wBa>r*tv#WY%V9j9Cm!qt?ja*OH_ za!g0{=t%Jfehbl3f^HX=IvC?MM|aF)e?L)g z7G6cniw6Qx{dxycg2D+7xh8X`tpfO&YfeTr_9bN1X7lxzKE)(FPubB*jTeJ5h4Wr7 zD|X_!aP>BG!$MlV&a?3mpK!DYXWvyuuPzYz$91pP*|k~Z(9U8)OUC;Nk5S8s%K%aP z=HjD+E+&eudXLCAFQEr~?eqL0!|+f6fv%FLp=`gHlzKxNDY_JSns9&ESj!d%4~wm& z^tA$Qo;CKN#)#U^nU<`tJq}ADmO>GU_f+db-VJ_v_zL7Q8yioms|O)5;@|JN2yzO2 zap_@ib?F*x-0H2{Y@-m>a>Lyyis)>tlOsoJ%ZSPRY%A1=7)YJ8C3V@+Rt*aRcc}{g z^hiV2uHY=cX{o*HxO!x*5Z&S=e=8}R+qf!h5 zkH(lop(&IZh9x68*(F~ZNhf(lGK(kVrr;9v10g}la88E`B$@}z2j)l<8@ZK;d?X#l z1AawVlDYon-SEcmJr7KwH}xz<+RiG)Y@G!3(yc%L+h1;wReLyWCY17J&+$jAiKjtLA z>0oxGGA~f_9V5{Ctt1At>+3yT-mFsc^n_JuG;rI&a#65u_9~#;afiFE?)QbupUJE( zTPY=+b}KUNJ+|qkiJR%dTYV2)=bf8kIYYB<&hw_N89%Hc9| zxFnJd_^S4Xxa3y$JAv%u=2Yt3#W{9R#3Q?A5RZRV9Zm=#nA4OpvsmKb?YZUfXmc(j z$J)U3UX(F*Pr!hxFH%7xN?ydd30}y1tnbLfQW&FUG$BpzGIJ~2B3mu<`}h0lFU4vL z&gYLuE>^gmn|$YS5d(?0D}2RH!r)o);NIn1Rn~Te_>WRl^Qur34+D@c`DX9au(jF& z!`boFThGlA57Kj*H{MacJ+M^0cNz)oPC~nZZ9Fm#a5}Cz@M*U10IA4S3VFN|82V!3 z>r@kQH=TNOMQd^dnA7rD@pk#7ems44gz971^EeWVrl79)9&+bzvr7JKOuq?pQOZ}g zYJU8u`%oQ@yt4^)$+uj6%tX@l7NwE& z1Qrzofp}QVf9fFryXqlVf;>PP5`V-P19I;X;LA)O*L%I9j=(f@kgZ<%K;CxiI@0PLwLFR_IS6A^vWbHk+=( zR9%zhLrTFxKc)DrDiVNJ+w+cw?1HB9xy5W`&!yig9AC`rY`|}_nzKkIMa+vLpua-Z z(w=RF@LRy@Mq^MRKUnYKRL*159V2vOc&Q>OLX z6@ej~D)LMwWXO&WTd(97verr#L^5I+uQrkc8XM+bY;0w+Y&|@`-lKea9Y3~*Z9t+qzH55 zulK;?zd~v2sZcxu1XcRhuUt5`s(3dlY97vDnQ*0@@rtLZ_Y2*PjTcL^WJ>--d)Acj zRXh?HY-pxqTqs*ez7mA{YlMw)Lj@sZmg`cF_+}wL$_#0aSYlkFOh613TAO(zwzZl} zpil>m8gvxyjJf#+q+J4!(p_oD!KYJ28g<9W>A@418vFI{d4Tl@*9l6K_OIu6kq_Js zSrc2RS$&))kR=zm`QA+IO@(yf@rO}_24A0vQRE7!D|%~%k#INCTuvJ9W7%*C%JBgi zR*+9Mmri}#OPbMttmw_kxZNN5=-v}fMU5mK^p8GDh>8F6&#NquWBs;AvBuGC+~de( zZFU_oq_RuXD15-XXGmIGy?fvuHdy#|2ddjm5aESa&BfpqNm%$mz4%r~ujZz0k zvOH1>k6}$j1>qNl{Cpv$nD`f9z=~f`6kYgaCVK8ydDEBXrWt|njjEb(WsWE2Siv?BEv5Uv6tfoTWrh&CN~?_upFP^zPa?G2k`k#%+z zP)zy(=sv30B+>&$jvC3!OaA!WEh2fu#FpbDR!c4?3mWY&jjK75@$W_3~atAw^y=PD*mU$|&o_UJv5;FBqR!3%?d)FF^Txfxu?I957%{vnpXy~jOGV$gQX zKrMQ*owDlX8~5ov$pwfGOE^W36`jN;UC&3!>5{G;vqyMO5|55dHaA;^i-iQ72JJr> z+B*LcDkwr1Aw>r~jqbg&c&37t!yj(>?Jyr6`BH`4p>p5h)xQ2V^`Pah#(;`gGJDda z935|qmSmb<`^%6-Z3st}7LGv~7e$K>&upKEzz^EQ3< zHqop+Q0>dip-ADXt$Oapdk2q|Z9aOj$4fozC!V43->KTHdUp^q*M#K$lrhij>;Bs>d=6VF(c+8475b>d@MNAUta3Wm?CzE7tz+rlX#yOfb zayEN{gzHQqRf{#tUp}o!Jt|BTrb}T`crh?ZfpAm7nWpdfn|NoCDWroyy8&*e8Tq}VZT7yV5pTo##KPeN>`D*> z@^W&WS7;v;z&#@cd~}-H6Zzh!k@edU{TxzV&dk;DE2x+qy+}D~se)2-V1tgKMZtnn z0{k2sg{Qib8u2=u3BGqp_(N}6T>4YgZ?wW9={!rqF=NP$A!{snvM*dEif;GJHK-vL zcL?H##_L$(DE<2T|7eN)jzSJ3=|mD2j&b#R!q3JtkoayI>-8P}eXv=+Zp)ZRvZ0#1 zmRcG4SWv4|&AVyvDKt($MY!Gkjd9;c8#Awn^Z@Qy82JZ$XHsqwc>MZn3x$bIVLgMwtQVRGoDc`+A<1P5o9S8i$>C>y62P1{TuEx0G&GRU zCFkM|O4e-LWsxdxDxkvXr8J=dKaCg33H|HdDYE2i-b9FvOVr7_9tSiui2Sd1i7)OTPqP&9@!E#Jt!*c z^h{C#S>S6QK>TMN#PRB;?e~UvMlF%NF2%{?LBP3*84ecU7nEOi1fgGg80FpP=WTxh zTFQ>E$oyTWR%#WLy}u+928d)ni6LfKmWsvqV``S0OT};X%+q{T=9^roi}@R>^E`1k76?^Hw!IKicnSO za=-5u9>;?OtSv_mU9JLMF7GLYJ3N2nGx&8pA~Cdj#zDZbGNJG-0bl!dfVQ9aOk_S< zf{vj`bJfE${$gX4!}JN?`qwh3Sy(5|_xF$jHN`8jBl-nHu2u1dKIByFDp1yNVo~+0 z9&wss`OZC3=YGRDkVkSqfi;ZtN+4t{_=zR?YOHz>0l;29h1Jh_$1p~> zNWH;!tjjQmydk3H-TW>sSa{Z&-AXG35;P`gf+&#Rg;|TQZ|}IPQzU%Z@Ql;#Ub!*= z;0JZ0*)Bge{-yy^*zylo!HrVROm5E}=I8ykK3In%gQ51Q8p zHk6jbjJ@N)jxr&6261Np3JfJ(&Zr_7u9uQ9z*)OabXHS@@~826OIwQ1P^dFEkS&W-!I`_=iG!L_j<-<=3jwEPrAwaTLB5%E5>mPRvu!PtB&0qxn-4 zo&ldqH|0la?B`dK`Tmi$+I!-wsQ<()f5*pp+udIiXIh6wy!0cC)Tq$OpV&;TLJ9O> za3{NzYGpzJFvE3E+TGavLd#d&fo}$_ZMgbgu~~rT1boh_k8YnseWIU8rNN! z*tMF1OG&VrzDVT3E?=eBt0Z#Q1*BddCd|Fwmaa6gN*@da4SsBk-W#K>OO#asInv-d zNudE%3xf5gi~SM9wRSFcL;aDIa#*eSGd^GOmuJ#9@$eMmBmn0#Sm?<|H9W76VS0vn zHwB(b7$Xev#IUq~>UEc*DJ2G8okYK&38c?8c@5Tt&i!iRH_=vOL99tLRK1%zD#4O@ zHi1kr;%nrMP~fe%;+PjBQRrF=<0Ds^H9(c_yQt96NHT%OrQc@#$TUsdFB z*!A7)e}{G2p&Qm}e}8SjTw8M5_j~-R=|W>e^1IKCm3OjxJ~=sbAKH(lP8OS>x&wYl ze1t?{ks9ULRW5FiNE`TLePQKVa#+#q36Ff{mXRE`mbvbCx#>jlT&-Zl#B4OoPC~9& z&vCkmKH1RXS8PQ3?B<+Jk1uCK4J(Ath$ZuL*(lD{LnH~`3Jm>Xkft@SBdD7k5Ty2$ z+2v(QzGxw@0I2cg6-gi0S3qy8n&|`O=4~3Z)2mT|rZ4XcV7j|J`tRl(Q0mCf6AilK ztgh?w4R#h{DqmW^Yrs%fUekjO$G47GsEOwMp^4Mi=`r+7@U{X9`TL}djKK`b!P*K@Y+M!}x zOEQosYS=KuPi`Nk=8QMpu-|<@+jb*4sqiOWqe}}$VeI+{sh0oiu6%Mt-_re9GZCgv z5Gl~}S+uVHDk;ZQqTEz%_87PtRfUysVvCpHLXK+5$u83M(g?{ld|!xu7$=hO$eW<* z!0Yhg#s+chZ|kn=Rf5dus%LMGh%feurp@Oma+~u_MNJngp%ri$&v6@6T|G#?`Y4K0 z7N=3T7Mr}Lb*k`+%-JdyT46$zA2D=!_=Ycu4t{6~+}(@QFGDL9z>2Udjft9ZON(&M z`$1sHG23$nSMBQQrYy0!vzx~boVpdeSz2iN8-wfYRpVGD6r7HJPs5_Q6JrcTHADte zCoVFqi2n$KNNH;~8Td&MQ^>+5#n|UR-Kmd6n%^-DQ(t_FemnE3>uFELedYLRTR277 z*ZCQuS9Jxh($0Gd={EBghPxM)uBAc}I&m7g!h$OWFuqe(iW(EF-Mx~02e2S|dG1Z8 z2XX_V$ZUkvV=I$Oo_;i{D|oNQVcqO~6koilZ=_<4wGOtPGU~`ElCk;BrkkCT2!6eaMTmlk)DF+ zvzy3Mc-eTVp~m?IUj#jNiRFrHoRZ^5>DZ#yK0)dT#Y|1rrdfl9Ev}BM3!bQ5B0Dvs zWc~soa1Im2mJRz5|H}+yekj}|z}(&^Xze9B`zc@gw)#}3Mal~Nl%}xcMAMAHi_M%B<^Ji82jq1PDJQ+F>OYP4#(?6 zsn~i6is+!dG zzWJrWmV~3akPBp&R|%G1dnNbbkU#`*2B8$5pwxQ#`R+7c{lj2h0E`%z8|%drt3bfP>J;iB(~r#FY@h#a*JHX|8zfDgE?eoiI$ekR zgsRf1cDjhTj42GKKkPr(*K2%VRvg5|%9h|V=oOK@aS#O9Wpt2$8q&Gr%Il=Sp*j&b zWB|RZY71$T?=Hi;revH3@xDXWr9$fy&3Ksy+*Tgx1=ty)$-vt0*@yB4!Q8owT9Wn=iN zUcXFwxMV74l32Iz(-$9nl0sLa@jjTinwyUHWlUFB^RLXpxIC*FOQ51m&*o_R{O7M@ zeUIW`C#1cc*tSbAlj*xl^Hzvkz2n_*-jKqokKbDhbIza6G9TO7PwT2G_IEGR-S-Zd z=ThJQ8HPu7HLj>c-8JJhI*ar?jK#c2HKX;{yE(~I?t`sFZ|tD-aq}nS1U#G*%h?-} zQo4{;a>&2He1JM;-1rx)Y9-gF)qpk*LNh-dNt_|LtHbeN*rMsT+RDR|zW}$&3Y*Z3 zdkzI!qT~Acc17u2|7-Xi_BAf&xyXytwo?x8?Z}nx*lCaT$ABcyw%)dfLvA@msPuDW z`UeeD#T1YlnVx2Zbud*lXmyU1k(}j4UyR!qkg}5FUc&ylDoX!{_B>6;05QvEk+CgU z0AtmKlC+NNAv`%X`FxPM_o@|XQ8(AWJvNY2)hy-O)mUHJtP_WC1{F<`w*7PZ$icY8 zM)O6HR1DXX&-IB?7XqUCT^ik)6+)rPNLJN>Y^u5j2<`8I)vNN7kGxE6C z>1OAmhonZkjwI=l$Jrh zjV6Q#qXz*r`LwbkL99#KG^l@wSJf7X|6z?&>Qt`P;hhjJ&$du4QhpgZO+cXth3!R} zw%!9H?T3i*qSA|X|_2!Wo-#p{1bn?v| zo{^&rvD+!%h|^-zgx5_axCI+kOH^Me(pFM$*BF~36b*5)DcS1FSm@=vstijRfOf5+ zr|tAFpwFW*D(W>+{v2=dTdhjB`sYItBpg=DpN4;6=&XX4W7SGd*?hZ?r)4%cEqRvX z0RWnK=jQ|Vp$*(AwCfi{N^!RdduYg)0HN0WFlH)mp|HdLP!QV1`Z?3f_cUBj!iMNA zY?Q6Zp2*I{yOOh5-{avlUKd@5lrrNrtD%zWX{~v!znpM%ule#iwX`n z>Mw4K8Fl>N1B@ZX=uYV)#2y(MV-BWkj7G_`*e&%-;GTOC&dzRAJpJY~YkSKjl$^>hz&hWK7QjY5IoT@Oun0Tnb zrZE}u_lwcAyC}JC112s^|6Cpf7407q;p zNrPV_YYxf8T;*o)q}Wof{Zwho&kQ|XY0DF} z=#64-E(ED(#4WfjsXkn3D6I(=NYn%g#CsGyL@I0|UzD^77~BIn-X|b75xB{oNY2=+ zpuI(3%Y_$9+L~6Z#hDlN&uxMYUUHAfLuuzL?ksnqg1~}3WyHY`+6n?`7RWA<2LeBu zxPUNiEM7IoD%xqK;hz6xxyEm%M5%!~(Yqyg+H-IwHwRc_HI1ypEy}KE#(`fQdd$jU z^y9`Z89P3T$h14+&u^_bMPBUFhrcN*Ntq!qi`g{MUPF`cWKcb%HW^Xs$AVWX*jj;J z`HPuP@8+EK+paea+MRr4-~+3kB*OI~Cwvs0Ny^U7^JKX{wM?iquz&oB1zKYFy;bwa zmulx;QH2l;6uShceL=f{!t|Bzrx+iOj(#`zJx@u>UVLh)$hkNbZA!~0^>uv$MSrf& z0bVxts$}acZ=f9IGb|{ecd2+Od#I&vr)^yIM{r-i%zE}O{v$LH+wgV)A`dDi0Czxx zU#(3!JxV28&WF<<&eSpoS7xHIeANs&Nt-zoa2-qULL#pAH|G@FqqsULK~N5P1?XpT zU!Z{7<(?o$1tlH^iWY1jUs3r)livJ?YwH0iQ(NNvZa}b+nMrTrI$D;a68nPHcRa&o zFjVdoJje*}4-4Zwn~kQH@LJ&KcI!2KnD*c}c0xBdc!lmU!7A1eZ(Mn&)kJ zq9h*$KJF5Y%)0bSI_Z5Je13nAtUZ0w&IT`TrjTJA40B+opfDm)?*EnkJ!yfM^PVp! z&_jk3XE5l;tJv|$3RJMJncx_Mw+J@Sww&DUP%>iBMb-Ld3Z7`UdRPHHC62g<6)$x z9UU?A^Cls}xR~G+yOBV^oVkL)x;7@@F0rS@dMJ=hq&$B z2{P0=7ugjb7q4m6YTICnb;)8)#h*Jq?$0tRo(D0pWbVS71w)}=qW_3unn}Bf%lEdE z#zh|x2Cj6|x;J!mmANRj=znYnn=V?#z4;~G#MH`2`fn*sag4jia%{v)Hld@nM!^?8 zH2d$|cpm!LsUGGi@R+-|i-zy4?SMnI+j7xCt$8Xcdnq&fLCmS9&=48F$J+u2?NbJ< zb|(x%J>{-_kQoD7cS<$YjBW+B>C_D9Nj;2nLtAeJHfG1%mp~$)aEUUKbQ6a8XiQBC z6c+Inzbvt=oi#AEZ_Oo5J}Ov_~@u!MTzCWq2 zAztU2@aijjSP^a5S2x{Z4lV|pSJYM#zr8!7>WKT$SK8+Fm{#jGi7fBM?mMlm420qT zh#D6}N(&nCdr{Fmt9GlX*9n=XCZ!#JjbTTEI^FETE$v?QUn)&j*AXUmU&$?|78&72Do zc_UKCyTa}6!=*FMv@XGH*<)>Ixz$YZU@3A!uw=G-Z}uNQ3wY@RRhn&2uDd0*knTU6 zao_r)N-N}zNt@I14DT>SPG3dG*Y7GlMb}iKrE_^>Ht;bDxb8ofW=>H{dy}<&RJ2jX zB*PfaFL?lRXiI$lsf?l=il*sKG9BLutyen9+sb5aUdiQ$2V+6d142ez99yV&rxN@D zrbrfx+>JhRihnDvuQ^>cuH=L&xilV(R;hs3Sz7?TOr4VRDZ7VV zZ3SGl?|mZVuD1#I(FRUw8PB!VUel&%FS>=@cd3rkb%iaYoL8DU#tEj+Zg#G=Ug;~(#s^Q6_SWkd5>B%B7e>Mz%=$RTse_;!f>roz!KN<_>R50pM z)iM$vO&#@Cnv=T|wDZ2*dukNm5sa~NGd+sXU6lXFU1gEyI=w4uYnl1mGuCUeavI5h zRoBWdN-s-P-grt=nt$cy3zfNFAEGueWWs2zv1UJb`E#IxDdGRHc#mhozn?J>~Nk zj9@jAB!GqNbwW2hTIeTl0#@cWyR>^Zs}Dr5Om0%Ck@Nbj&s_(Z?n{KgG_HRMaxDw{ z%(*T~b?B_6vg4d)H<{YrDF?)yM^_nW*m*r~zKJ^~Psp--5N&3geTbXTeoI0nSK~W| z{CKDsu$zk3LVb-_&_Ivie*WTSvSNdbX(m&h5=e+mOTkQ(h};@RG22JAJL^LwAq~p zlR$!YYgBy;gZoJ6o=#SYkcirBebG$4@7HQ#ACbxk^L?}TX@&sd1ul6rJ4hj~aa%Kc zzj%PQ<_V)M(6O1y{)ikpdRyR|{-k_dI=_*C$D`GbMw6wV`)$PNZ`2m}b6$7f18MF8 z0jnk-ZC~#>2a@b`?UD1`hf?`oaA6Ry(V?HEO*Ft~7!t{1?@XK&R&124`Jeb$Yo1ofPM!HWN#2YWh&X^WUsK`d?AE2I8Q}?+MxB+(Ot9cNC6-=Vhu*Q@>=?!@ z5-6n|&!PWoA9jHSCoP}QZDMT6RGHc5G zVIv^E^b=0p9$0m;VW1ccopDq!myfiI+GsJuET0&L#Fq}Ita%vMk#jJxUI2^mW^wgP zp;hT0D%;XK+$}UVA$Y|h|8_i;)Cf(LsAUz{+2`Hc9Ko1fD{AdDl@nQ{7Tlp+>IX?m zTB?t+bXA~KI~=f5S)`DOyY*g5fD?^ zV0f{PJtG#_`N@@(YyLWLV)_XZZ^H#zqb^K00ZzymKR%LR!P8%PgTA4u5OrgzH6y<2 zY>|J8a+|H6P9bcQH6>=sas~1ayIYS+&!S8H?K0EZ5NAk;Ob4#lCl`AIR{VQudGWb%$ z!28v(#Rmbm9Y_^mYlqplrhqU{*lu#R#+~7owM&)ED`wZElj&2fd~#v9 z0UwrvK-dk(-$rK113p3~`iWH}ep$=>>|*hgZ$+7u7&mA!fdFXtx6r08!U2ZJ;aHlx z)^U4D62G*d%^g3|?`6`W5=Ie3^UZyY& zIgYonIA_Ao@&K`hFuhmLp2c0%JF3twzR0lE8up^`@&FkRk@IgQ*HV|r9lWcTQ9POV z>;DLNV>&-~kU}_eidq?Ha7RzKi(??#+1-aD{Bw$Z(&Y~lBIJD+CRR*%)r7+wn#Z?T z^*y`OP97d1&ojr13*Uw=bF(vk{%Rl+KKJ8vb~d+EAWGuJ!ol6kT>w1ns_4;4Je75R zmbae7Y+!@Ll-}e2|FIF|qFQ~qSIRN{=x*{GDzfWmm;FeJ+70#l;uNYd9h7F~s1xW4 zC8Cx7t316dEr%PSl^##z~4Imd`uW;B7Z=ow81W4zSLv++}@is8^p$bw+8Cbr09OK7q zm{s%dELi+UguCU|1YOT$-^}8|-S$$e^8OWS$GZ1L%NA(|3wNA~_`C|O(553Im0_aRe@Z?jswC^e^544#M=HDW; zcwT;Du4;j-wfX6PKZK9*Y`4M~kEW42+1G{69IBWUf+*a(RHLk7%z&9*C-B}Bot z*0ne8Wb#)G?ptM?G7n?n)5+igrT}xOC3@8|WSEkk3TQ(4wfzfSxHh!;w=y-Rr{h~J zo7pVlo$+H1ZN-wE{i7^3JKx}wjlTa{gO^^QL2<5WrlQl>Y&}%eiV1mZ6_G@@(U8l_ z$Oq3v6WyZsColYs+;s-rORTVg&<5Q$!HRDc)3rGXQ#)BTF5VqE_;sZ{G(;j2%vqns z^2+#}gxW7ElAkJ_08MU!Kqp{RBEE7_QG|1*jVf>Gh4+fXWL?2@-7A$Dk_Z8DDp?ok zsSE5iol69cpc}Ja%ffjiK$Wnmx}+oMS!>`JoS}&^n_=GW$5#crSxvieVbnmTb-QBx zK6*I9wXVrqE~Pk$>kX)C)M@%g;$&gKbdE5-c3?K$2qN zC{NiOhGo|mF8cP9_x-yC?G8R%dEDkz`i~!T&?@Nt8lGj(J0cq8-*ShJE0^NJ$~!q| zB^CB*>ZeNy13irV7un;`v55AcKEw3O{b(5d%F*%$M{5_>V$3Ttz+JNTl&!tYn5}6M zQ`2g=1N<=MJ@mpkHIEw4B`Zlt-tnt}V!IApfuS4@9O2*xNz-kV+}X5eQxDtX zGbGi@Mq{w|%iD6}DI230jZgC2!*myClov!5q-jo)xWiQhocWiHpZF0$U7hiS?RJKD ze{*dA7z?xOSy{|iB;p;$u(CfH@i13QT z>f9uth@z88Si;fH)9lo3nd1lTsh*RHs8}p37VP6B!Bx#~_94>S>+>-r$mVEd7stO7AGmhTUO$1x%DtC6*fDoz z4t~#+_f2Z1)yk3PX}M{<#GrP8=uMI!ElLN*QPwK#D#T!;$`{~-gBB!u__Ve+x&7V3 zS%=@P1gElf*L`(?WOnjNZZ^&Qv>}{)_ul9$rYOyml4@WC0;P{P>&+&-nX0*)3d^ie1HL_dfxYlWf zu}Z58##L76YE;iRZ+I?AzM6LYIrH<$COD_u!gn;As!v$c7KKnEAp%vidJ0STysR+Y zzOa|1Vy~`ckR_X6TAclqm3#fM;TDX0-2ER>d6zwvU{w2y`*T5%^u=B$z_?)cPS{Dc z^~J@O#pB%>KIVYCp<%YN@GDG-`W-9NBt62OV2{vs* zy2ilzFV7O>9WW=*@TcJ#lB7t8MfzmNIL1ps>NdPY1c>!Jp9e`@j7n9ZQ~CC7RJg1Dzd1)k+#zzLW*Gnr51V z0^b&SR`$iLSB|#2Qh&|=7V$+bUpnscSa$Nu^A`3+;(~V9@=^@Qj;wTf;@Quvko@@2 zlWB>m>yCMh8hZ{N0H7D)S!8zKYujuFDHuoTzxeZvM%+;1X1lMN$xU+$+oin>h;ItS z4>!k)6aK|G!HSr=Di3fasGfuX|${J9Z})DC{ZX}GHj99gWuVBEOZSGeUfOxTp4r`Z)=aq zayE8mu-cB!*VSefcwQzpBU~|@V1{626U@{rXEZuq$Fnc)pM~XMc~VMA5Gw`x)|X(t zSU4dw$GuPGZG|K&1|XG)FD zjI{y=A5ABJObYJ<2@#%2`g`HNDRNdKh0O;b=jI5rw26 zRN?iR&mU^A$*rVci~7d-EhgoTG~S@`lrFfs5pm}}tIFV7#9Mo1?B`q07i=NgDQtg5t@;2nfi)Iwv!@#usB1L6} z7Wf>^Q_Hym7K8=}6!gdg1V(t>m%m^DQYhjaL3Co9zNQ?0qyJAB!mkfAiccT&#>UgS?A9G_yF?c+HiT z^!;J-PMsAq)6>648amr-(9ON;Lu>ENWe|^=8`~o z)ZH{zV`C~zcE?icQ`|8-KiQ!7bBPzPGb>!An>7wg)>lH7IatheD157wa`anxwGrcF zG_!H#?=tr{(Xy(CGWfggDAeUlio5y;C^b?zVPmR*QjtSxeZvAM zilX`YNbY^QezW?V)3~DDX7AYiU-6BeNYr-LE`DrEA%xsI%e=1dZOzMwOed&6N?XOa zPpIoNkv(z!%*XHpi#B%|T7uWFr~vsdqnLV*D|q=S(Hz!C>uKe`2NB;1+>tQmB$~o zB|ajxlQnnL`r@Uh)Wnn7wS2=P7Y57^o#!OwdZf$=&i%HF4-jgNyrx?)%N`C(-;~?% zSva8$38B#PUP_7Z<@}E*6I3dX`XToV%RNnCbwxUCSZ(nPY)mM#a0z#M7!9Va$@~IBuqV=tJ zuECeDkuSAdII5+ZrCjRmI%A);p9lia+uK2Z>vH+ABMv64)@V>7820H^fe|6j;Vz0< z7oO|UBz&(snao-E39IKy!l_M9!kWyZmHfYT?K?Pdc1ekwMqGJI?|jowBh&k;!szCX z9Dwn10%C&f9=h*wdWeVStPxc4bVsn-g?W7MB5Hb`;SW{-aueNjj=R`Bu`69qw+sZM zO%r*ht6Sl>!?6^!_~veUE8{W4y1%xG(VEN*4<`$t*O{ID8xi87K$f`v zN9j-hNIe*P1bA|CU8K0iO~n2wu@05(5k+{-pYtyKg!3hy+1dBd>hna%RO8B%G{!ed z!{v>Y)G@mosu}D&#U+F^-CrI=phu5aAy3b8@L6n&7FwyMmC`&pn#KA^thM7?N4|t1 zOeBYnuXf zTl(jru7w{d^1NqU+IiQm{H=3KW>Ovd8*~>cluqs?e=?L}xIcV@BXzB?@@9gS7@#nc z%306l`4_}iZ&V=sCnX?T&8X%kkdQ?7koLTHZ$iw_`Ze$__Wik2^4VY4S8IpVSJdP?46XT{+(gmq_o&mdX*M#~p2Cr8TzAGYtVZ#w&2)iWmz?v^P@rzX zFKsk7%`ImTanSYGC^OtCB_4K|x1pU<2}A;-cyFf=gLabzLsGMbi&S{bISB#Lj{@0h zfT`-ZzIcc#JzU6`d6js#Np!;EK|cSEnu(g@v*4l6=(m=1I8D{}A1S~5=sn>>bI=Fn z1Bxd%t$d`17kP(=xP~ajZG<8U`a-eaO12wv=02Jye`^yI2T;U8+1j7`(*=Df;jfB{ zG<$=Oyn+Q6&>10xflTl|er!u6WP3lFWhA%T7*E;fwFKlDNCTjoVw0@hvt4e}sPF!H zdq3%E=wJp5SL#42FVmq7I5+W^FUW=6U=aG-pk)ZS40nBwsG}y|Mz)TS8*m^P7C6m$ zFFbs{cJ{XA)`5*FLC)J?@!a)xNa`y`zRTQ5ixLgzJKmfcAtu)GeJZZXz4*fYx;-W- z!(-})Og~y1O+-VU{zkld=05Wt9jh1T+ulz~LE8xYZX^>mID2I|TlBaMRX}u>=38;m zTz4F|EKo+{n!)&sIYU5D^l3;@pykI84xbfwjDQ*Cd~B5MLl=KIYHS>@_cKyE^NKOZ zEO6Bnj9+wF?c@7I)}O*Or8D}9Cb4XHKMY3oX+5@jui++@63X7sq%ygY#pxmOb*1rd zGWM}$s&W~-qH@NsKnLS0#6PMi&IF9&4!0l6WG|B+zk7-Bk{{sed=CW3i+2 zkH`*Z`@yI<8;>CA%X1frJ32X5A~pyc=lCg1>!%2H{zEgAj4i8Z1CRV(SZB`nff(4RT9D$QhIJNI=(f-1|`)Irnl7swK|^(Jt7F$f>rR#jpy@9@FmOmDvi>|oRV4>Wy%WE-rTFqcHl^-sqBGta`{dDIiT6D$~OvHm+#2Z!VMpXN5Qgz;Qnea`kW)8jp zu#=a}M2bx(Qv_X96zBT5JToCHfz*6&o z@VR#y&#oj*?LDerbKj;8?fF`Ke<>{8{)xP}CmE}R`19`3REo82Z*!&Ll~_vgp1xQX zjsN*P=IPHeQj^r14{Hf3t^aq@EcKNA2vXPMNau~I+oB?^}C8Qls zM*-U^)3$UT%3^}JGdwf9)gwnz4O_nAya)*j!>fbfk<@`+h#^0of(O0&_D``kCV zIcmc{AXj))oSw96MC2#ehb~&MaP+SIGFaOD%qiOP#(w;zzO?Tpj8!XLE1d2M7kr0G zO2Ch<|Cey~qmo`vTX*SW1#EhFL~~GJGA|WYu4U=4*{^$lm2$eeT>$L?;t|f%gF%wI zOMx`kbN6$n{p#&IvbVb4Q1KEy+%Ua7D7z@N`Zr-+;VQ}Wc1NN!f`CcDD9szPAj)Wv zcOo@o^13YFURNA8H9(su~~A25!x5%(p`H;R)YQK@cYZunP64{rvPX~Q8D2u`*V1iaCGs5L@TJ2A zSkZq((k8o-jGp$IaQk%_BJ)>Bv6txn?2d;~?S1L52UwR$R35PVsNYhZ%RqIKFJ-mn zGxCbM9O=!i84^JvgP1b<uVEn#PVNXw$jY^iT`? zRJ80xH+fjZaH{QQgkbm;lsHZsTVQPT(4+HI)19tXQK&IT*+{-LD&H?n2YdcwymqTE z$R_U#{9A`KaHqBI2Jt?orro3lWK*Odm)?To=yIsh0(b?eQ}*AfFGngXgmCQQMVv(n zTIYk)ch{#nYhA7PDlOrGBs2>Z1DNg_h&VJ0g8GaaNQ-2zaA1ci(E@kF6Sy7avbUR; z|8@Ha)zlS_OY{1p$MO!Xgpn4p4xkY}B=kT`K=nZ$yj^j2G0!9Ix$Ihr^}z#AY8iaI zF4HfUL%Oho0x!3uUsJ+@;r1|>F_jIRuz(%+t2zjsW{jHln6(>O3IW8-xLwxvC$i?k zDueAwB8${Ige8r3W1e7zNDbW&U9cpTe?&dzr%$zC=&dWN;B=#?XHWdxnPrgP54~HD z*551LX>kdP_B>*j&+@mXMfU0Sc=Wkc$zswM!vQl@Rdh7FOu-f9?i?iAWne`=sWZJfi=GL3GYy(*KzX?w_paZFuA#WTC1g_HQGR)2df`^}+^WIt;2jgKQRdADX*EzU&D5r#MR#;dUqEOTn5(3p{p0MO7cd zP5tp+OCcT|@1}C|)N!luw%LuLbb?yrvP*#;C<;IkfY^oH)^ilSXyv8?37m{)vDn|S z58PV;xKCplzzBQ?!54e;gqRbT=W-qJ3gJ-;wyIsLv8&jR;44w ztZ8VpSStQ;<&rz7WU9<+uf-}iU6FE2YU32PlbRP`gc1O>pw4DALBnxR*6>DH8H>Z1+8nhU!+V%aNq9&%ZHXP%Egq(|N4 zHC@7HEybM}0HQ`*{U0ozsd_z4Cr~$+M-JRlFqLUWNs%^7h!D_ZG#)ZX7=%|F>`LPhL zsck_y;EAUV{eB|cQeRx)@6K!jC4WD=6fGv0Fr3mm?>=CxT{#5(N+r6^=ddE9__?2M zwX6N;&Pk2*6WjV6t7R}gMLy3hur5j7Xn(Oiq#?F|Sog|7r_P<=1fZo(lfna*ANbo(B3TTyP zo50Pk6)7xemeS?$J zX##F;EXcJk$mAa`Uqukt2?J`>A*&u9(UzBWD((DFx;6}sr(27l?{ zGye(zcN)v49=lHg2D^*Mem1wLP|#9HMN0N7$O{Ph$fUny_uSyF_}$4qq{QQ}8~LRn zJy%RFHuDzRZ{J1i*0cp%1l5g0Ym4X?(trn2OOFz2`_*b-3U4eCsY~ zOSLh5S=hm<^)B@DXzZQ&^p@K|+E|^4VMMO8OJ;V}#~w1^-_I3CTgFliqEOGKhDh`=D_!bdj$0Ki{rrO zt)6V@ZDZfkEzkDA{W$=vo7pgmC_Zc}>F8Nd8Y`vo8b9|e?TIGuGkN4JWuN~{xq7mI zp4ckv-Qwf5$wiBb!R+7M;I{K%gA%yK++CsoHRLBAnuvR$4w8bnjTTnt-A-+twF<*2 zAq0~{R1g{Ja%oKi2<qVgltC7 zp2o-fTH^0`UV^sCGm&(U2{O|mn?s21ISxoI+C|V1IK;T`nQ(EvOL2(g5+o+RcVa;E zy3QwQ;Gex*Jka@ zY;`x2^wr=-QckHAg&ePtCwWlv@I<@Y2CWP*r0QJn^uRH>z%#w|jXe(i|3MdxL(+dM5#sZt~W zzZeSP$7tGWZbWj>L|NW@^Iq$lZ|{fxEfmP&mjNg9m zvf(}pz_pEZtY%*jp!bAmNzmslDOsu*_qZ1UVRgrsL!WS}Wfas4gt@3KpH5sxd(w7e zO(10=q;wY6*MH-s*>W(CWsJ?7cG^c4=jh9ZJPx6f4Rjfnv$>SZ0?JbuR2h9YL7lU% z5!!-HvcOTX(~F5pB|ekiM?-}L3ksd*8?Cj7yJ$Vb!>gUXP%bWJyr_?naXNtiIWvmu za1=BIkiLuj6|0(TpbXW~)-ehXA!=4A{uEQi^>`I0?^-@1RhWs$%;k!T6GQTCKJuah zuh!3Oo&R=$m^?Et&@wl1pecY_m~>qnaE+PO(^h^Cfj+K?zl+&3f2MsLgHqlE`J!2t;?1eh^(#t&W(gwxiOFc8sAeV{B9lc~#yUgmYJT;7wKuVUMq7;iDfoEUZW}S zS)F(VUj=UgqlU>W8X1;ONn5@ZD!qR8qtb&w)RP~3Rq7A9mNYG2i)0-qxOz*_hY2g~ z5%WRDQ2hO7aH1skKYYaD+ny)BybT9?+xIJ&0D8H)vo4}lGr8RActg99O8L(c)tB1& zz|+jvuodeM76;a|l1Dh~f^X*5LYDB#aytGtYhkVfC7B1q>H$F(Q1R!W5~Q18>Qy?( zcrYO#QA^}S@hS^Z3LcIf`x))c%IS%oP} zO)f`E)Y`UqcsjYu|7=W~x@-lape=;4iEYnA<~P?E;8Geud7eNzE-8dn%b+fY+8 zfLcN&W6-`~G%~bv`3Za{HfRm|YrkLx!p5?9RB`YX4=osX@nW=>)c&`$l)m`H)VoID zl|{nSnP^aEjA#Eeq71F51j-g9Pg+Nm^9!iZMxg7dKGM)4=oLE7Wr9)5V4;?sRPr(= zwRh_J*~o}jsxI7Uksj^OhE)8c{7*UA%$a`pSH63y=hk2K;Mt^L4A)PlIX4|0-&Q%2 z85wWvdkB@Qv*^&Wxu%Bo?^?wT<=f_(3+4io`6gUl&DS)6oerttb$b*v8+o6#Y-KjW zHEwY^myVJ;dgLbSEl)m=Y5>NMThT0POdHXdB*IT-Lpy^elr<g;v8l5LjLSbk1R*qcU?+XP9DXX>A1IT6r@L%=nTNrE@y{=+&eoR z&I~@ZyBs}~FYpER@uas$0jM(C+NFcLk7>IZE0zW;dZ~Nzw16fAL7Rl&pHe?J$<=Y^ z?EA~}N{ueygYF%1e?EElE~=TwK2*7N!#=J&X;!T{z0oy!jPMvJ#Rt3aHx=UBIxzlm z;t-Y?8DVV&L0Y$~1CSTEJ^>-t&07?C&SYb->@L%>At|G7jN*{I3f6SBF?tF}*EnFa z{!-;e6!w%De^i^qk!b8v6#+p{In~ z0gASAvpn1SGC$`GZx7zZ^*P42gDzjlg?dccXC&eTl2c2 zUU9ib4wIr068Rt<&dXxglA*SZDLHiDTKRr&i&Hr$;HVO_;^AgS^(@S2{LS65N@#&7 zaYs;6ZR^tfk_(8z?f?@B+lmBSL%(n&^HfP*=RMiLx~)p}^{Bmy<-dM{ph&pg&KZup zTS1E%v`(i)Gmj*(xtn%Q?^;YYxEj@rRW_piG6u-XF~@CBZ?lDF^5Z>WxMv0W)jAGT z;*h9a&12OE8Tajzr&domYQngneY;`NO>-nJ<4urK%ZY z(IU&XXf#8_(^N$FbR)85OVZOuD?nG~h1P7HaXqS84$L(B$;f9`(E6`sjcKu#g?Rx_ zebnrjwMq`V*RrM9h8CQ=VOZ38Hh$s{*h$7a8gqh~x9Bh2)nQJSf8Q)9$Tr~dhbgYK z7W=n{(^)n$>K%pq=szcnjfLW?0W<_lPH~%{u+|RCMapWnf7gRyU#oNIoC43~0_~Jl zYh!@cw(3G<`7ix~-3C$$t?8Z?!+g7arf%!Xc#hfxZ?b$KQokM@K|TZ*o}&$_fhjp) zC$hjIITzR2gvu+q=`pho1xP z(P!JduN+bxWywD_H&Og>UUACvBZrL%h_020(D9H? zv_3FiWOg{mH^Sw0d>-rJuA4(+E=M&beolAdcBy77OT9tCz0JiX7Zy0VaHrx5HCq0d z^Q#G~k)5nHA;LRdd0FSPA5EqttDXk&)E<81OG#B?68+p$0`3-gfaHKWP$6f+l*WO^ zEI`Y7wx^mKN8hK6TUKc?%QBYdrCC90Es+PyskbW$#T8_D1SS}B87){} zaI9rvKeJTVR0WZsU$vRKEv8k`Y3z(oF9VV0C739-n&w7cm4u$OZy`^q3~#kV5>6Mea)~naXZWBSxmvcS{G|oziTF?d~_HE$2OfRvFg?13sp=p~ko5 zyOvjpL}=llv#XBtS@#RcQdH_yLSm(R6whujsQQCWyd}ogIK9$J*KGH;hblb8V_n(p z%1Ib)4MXt>lD<4UeIM2MczjhG-g&mfBxFnVHq$!So?V@?fo=iq;PS+AIE6wN$j%kC zgtxqUG;NT47}sAN*jp@Z-GY9EL8R$LD;1CYs-oen)sqTWjoD>I&teW5i;pWc+_+sq zAG@?i-oN&ua=i4zSQiEcEil<=v+}vq33}m){jzj$_(~K(EX$6-$?xV|h}Qe=(uPNM9|-yf1ZIi$r^j|CA!}uyRmn30BjiJTDyk zV_sfTvsFa#WRI%5MG9Xz=xeW2h(We$I=jJeNB-l}v@?7YXh|u4PVOcHe}GMZ=z0gc zk7)A^z`+`HFtWtFvWPi^q`mFL(x)O8r<7lC>EJ%%=;FLKS~lSL%DzJ9!T0=+&78ey zG9EMH#o~R=8yauyXC3=Btl;sb<2ywqf%J0+0G@9?*>m>@V~;jXY%+{=N@#tJ-(g9> zjEpCslue(9Ej4zl7}n&)mW#;9u4Q>0yqnHp_)8C0e9#k&c%irF_t~w^;3;8pd5lFC zTd2OBB@>h%L8B*Wl<#+B@_jC4{V4`h{~NtlcbND}s(yCU>~3JdZd=iv@wF>oeuJcS zDjIbSRSL2e>E|o`H`Lq(F15=Om-LY|+}5r$Vxv)elq$J5lZv~*&Uqx;!x)nPCHyS|y;~RgkBCKJAM;SkDj3>ipj^8IW*Th+2&X}fUJDDqf_hB< z`Tg}xwuj=peK*T5ubJN29cUHacpN#s_-V%rZ4%s|nUu%6y`*~oW}XFn(4+Ao@nUs%b>kS4`XFrWr&uu>qcQ&J_h9OIcVIS zNI9iHl-BVmoqV^%@IO?YS3FyP{QrZ}(l1&?Yu1X2S&G`Nn28-h&9-V2 zd$-i4wn*%~WA6~9_N+~eP`mc3RaE=;`(OOW#rxdk;yfPb;^chZ@7MeJtV7LL=+~@@ zU!UHZC&S4YKcv*}P_{t55-Z2qUa&R%*Q7S&(Rp2HCKV|V*}h=Z+YMuLX#0g&VER^M zkKCv*Sc)`+mkrKjx=2Od;X{ioI*ZTI;`2l5{sD%5N079&I+Aqz4;WDDF&7pFSlfsX z+rQNi`mBZf_4@}YJ=;Ka+C0?>RS%K9h1Zww(!}J`-$+Y|=g>q`4WPotQy*4N^`?1a zH)J&}vkJ+ot5&Bxq+f#V(w?i8`HaE;4O-0>)s3_F^rQL+BSkw6Wh&O~3Vk8>S09?N zZQv$m`mzzC}ek2>$>QbbO(Df->?qpCb?3}u5 zYH(+)G65UF`QfIi5-V6Ua31i@w8WOq{`c9a%$BTVmU~eTJ-F>OTeR}k6O!h<1)9E8 zDkVHj#k}>*^h67m$U0%~6#*MTBmQl7bLa8!EE$RM+!7-k z{72y*ps;uEyEFZ8L;B}M2d*Vuar|X3ns+qV*O7E-S+TxQ%<*-iaIu`@#`iGsD5E~S^E?Hh=vVy9(JSep)dS|sEQ|D5QVWN=RIZGFN_y7x*E-2sFmV- z^c5{6?Z{AZXQnQUq z@w*q4!=U8%Z}kYV)$l~AWM~lwh1Ce}Jylzru|<-8g=;j8o&Te5lHg&{5w9>7(~ksA zf4|4>t0{(kPZ$O}7Q>jD+kM<#;o4c|9HkYrilhfD1i`c?j^a6~{B8BBDhr>8LdqhU z*giq*Qx7U2kqFN0Fjb(;SZVOY;8J}wbhTO1=z#Bbj(l&Z~3=9I{5N~BQ<<>l?ywO7_M zCj!LD>~5>`w$7qy=``QJXM1q(HpKe-<(KCXM;XxCgaX+L4_wS&-c?`A1zyhWCfw(R z4fKA}UZu>v=|?LPXW1V?KpbUvXV#tS(XY8-1+*^Ld2p?EVSD2$?DTL=YuR~)(UUJC zi>Q6MdRz9Hnjvo_b)^6up}l`N!l@Q2NZLbHL^LVDZ$txtgY0VR96 zcKVu)2JE*E(>~qr+rvI5C4&%t#{gH7eph{#CsmP9?Reyiz+<0`?1;ZYFE;-Qm>xni zAD%(*=xxSZRiX94Vt3XytZ3SN5-4l~V|uN_TfT4zY?@jR3EX7oy|Qk^GM&HuJ1DpG zLa7$pH&5kkZRp!kJ*FB!PM~PjsO6vB*_Q$?ORpn^4nkH7&mwGeTy_)-U|uYi(CH8%SGiBc6XJUop3yU z@E34jIQ@XUv(=*^8}ef~HUcM<+mUyAJXyIg=bD?cYr1elM%m#%W!(o>nWtkK!LnQh z6{4Brr^3=koyVrHa=3_{?{-5ZNWM94?&d{$XV9+6rS!T|A5S&^16=y)J*Hs*!QiiD zAe_~EP^hc)xdfNLiph&kn$888heuW2?pe&*OosaKdtC24ua>XutE6%nIfZ!D_WNv$ zP`i~)^>=FfpJjxGKI|!oE=iodvkPBx^1?15aIfa?PZl4f2~o(dO`RR9lo9x{p{UzT zC!Kg9i*vC_?M7__yN8mZhicdaL;!bW6hOZJXt*E0+Fu`jetgE@bf&bgvh&SNfLvpw z0W(wg@uNaX{fe<$?*85rd`-&uvs#vPjS~J37y1cXV((j-x_yhMoz&}p%Ii+PT(T!X zzfRrK!5vDLQAm*t3*Q*y8?bR*ks2Cwsmnc_%;A2SxFo{;N>DfSl3Hq0C|0dXVhu?? zVruXq#_VogQA#A%OqRXFh`yj@ifq2(6NNHUluKt?{qp7JqRNp}jr!yY@y<`bJV9P3 zlSSk2nk4o+FFatOJ~RwC>*sm?cIy-2+hyVa5HAD}P#5r;?P1Wpr@jB_xG)?2mJUWF}AJ@}6Y!iZ<_kj~k2Q8<0KP%e+(^NkwX7_#f+{*ERD z&CO+{h|sQe$K?*svq)!J=^!#`7N1T3p~sEH zV{@rAep#6+CaPHeYuq>9mdW95V`JNbaYs9(G1`dm<;*(ij)aI+p2@sh)N0a?A*I*+ zl)g`tT#D1xhMNc#Qp5z8hC)PBC;(P3z{?Kd?2qk(b5TMC=Kz-hpM|T?;%Ez0@vW~m z9`b}ONGqjdW`=8%In3XX;VIZd(L7t&pwCQ(L+2)C=T%m14BuxjrLCOQH9^<8_z{3+ZmPH5&v>?5yL*ogR` ztmK?_fKo&gU!QKpTg%5renis+FTODeICs}SF}Nq4Z(Dmahn-BN!U&Y(x1%fIGxtEe z7bCnKBhM3~z2!RN0L9un66`iGX0_oUNQc4zSRqSc^%lmN5gg}CNE^pGUdbvGa9i-Q zw576cU!Zc7aj_C+((Yjvz%vrol^g8NWBiAb)ic42No(#t9GR1X zI}$+6bW1TBll}a!r9y%V2hCC>)a3f^eZevHrUA>*x^z`^NaDy+1>R2XNvt{ho#KS*Vv9#by(AVa_vp?uz zbkpO*br>Q;S&RMwxG)-;fx>+6PKekcx_8;4o5XZ{ySJz@ZDC$S!(Vrv+3z;;{aSK~ z@@(U%6B)AN%XB&2`lFhJTjYd!;Y<_b+;6@5DyxOFSTnxSNHWt@tMO<~(kW z3FD}HUWKvqBy^i^Az;i+`&;{l&r8u%@>>Tc!l-bYU)e4vt5T^OJc1JW3@+n692QG{ zrC-k*6CS&Wv;O=hcwb|_e1>zfd=Bi2_(@aW^!+6d`tGyp1=iOULVb!&L;d$WpRP!S z&U-mr`|BvnUOoDrCmaLne3L*r756Y9I3$3I#vg)zbESWdp24|gvLRX4QZlfwSS)WaLaEM+H>5;W-DV$(6X-wCJ>-cV5@;-GfVwGBVpmcH@}HSpgethH8_Jww5dQ@$S{Y85JeYW`7D)`2%a6Ggxt>UP)p)uxb_ zx{D(TJE$kpvx$t$E$3nDVP{lZRhl-x^+F~%MRy-Q8&&5jf8G>RdzA@;S`FyjSv1gU z)!cguZ`A9Ve5x-VYCh4F)E_Nqg*gyhCZv~2^A`71wU_qTirvn93I*=}{Nq|o0H^pW z)MU6&Z1yxIIlb%tz>!)B=sk9OFxg3tU-$>GBw%)(J2V#*$Vwi88Pc8)5n=9X^9!Bv z8Jm?$r3Ts96lhT_1fU zJlNK|p6^~rlTIic6IyI3%=vDV0ZhT060wTt1~JF5%ENfE3? zs$U=_c=mB4l%e1);IUxA5bh3jCpoxqaMWv>5t*DllcBMDs!O&z8 zHOKm?cZ|nx5*~xI14O zd*m<=F%(haAMC;k^xiiii?>%A$C`OGDb%@CBaQt8=#(2dZOUWfAFV55f&T!jQUX4x z$OSvbao$AJPjw~+}WeCU}y+=pC;L+|fOQqBO$1vhpOs%B)JW026nY5~s zaQRg1RE6x^t83wYn2Mfpl2K$>)Q|4qqD8rq76l{iLV&yy{sHsA@jE7EEwA;5lbqpFnIqMx;{Y{j!~TL`w(@ zcQ-zAgsR1Ys5JuLM0SV#{-ZyYvK=2w6;fjAAoWRAd+m9*MJ@G9mO-5kA(;$S9zZGjnUiMj8XW9|psAMs0ZdJ-H3_+L?X95b9$u?V_McN%Q<~a2zu%}{0%}z+A7yHD zdp9o}-{s2YKfg8OE+9w+*?$fqZ~Lt8dCB!*;Kb-l<`@fpa|iOR)(3uRes8*dRA7td zrU!-v_Zl&lO_9FfOtfyHcs-B;;-RGJZ8IQy4ZO<|R+~3Lp~8{p1NeyibbYlux;ZyJ zt|K{D|mvc024J;B%2j>))vZN+x&yGSAa|0Ww+h zr0>P4{jgQ2vz5A1ygwcLujP(YPQwRJ$(y%vf$(9mU$jV73JB+SVseIGBh&~#dr;Pq z;%&TFpileDZA;c=>VMd~CLZ^0B~-~QVD2>A!vFn)-TzprBK~hxb-q54;`q}K;<|j7 zc=h>r19>*L^h5maVec)BWoK$HoJ5_Svc8xeYx<1bMjQ$Eqd|Jm>-@gGsYGA)c6Mb$ z%T4}2fX(~uyLqMf$yvR^iHkB!$}}Hiz@F`Wt3pRZqUz~GcfWy6M){zla0Xj;rR^2f zL1P!ynVD${?>&CA8-bC*t-cE*9|7rB+>Z%}te;1y7xxHe!0X*P%;BbOJ}KSDp|=83 z)Yj-2H8=adhkX+`mFAH$K?F06?1ZBqmOt>;f}1J4pLmGe-LMT$X1}Cx>-Nnc zs@%}|<&&Gt{MIX}L)Q-W^(6~T0!^&HwnM7Md%Jm-=IWMdx}@AHjmOq`>>FDFdDYJ? z@t}maK@oqCPK#N51j)2f=cJG|WF9I20!xhEq3~w9gK$%IN$-CBa>gEHb*!pDW*?X{ zZAf;geMlgyQa9hiR)Dnfhy4EmpczBnY9;HFQI>2x z37ApKedU#k(rBFMRr!~=$()WNWru-OxPLx-5@%1q(CemVsP2}{JDPjiCnL3i`^h+m ziryW3$7~dRK1U09`;|RNTIo%N%+8XP(&#<4ss&M~tm+Iku0L!*8((} zJO+M(Kk-R2h>+(ZRt02AW_>PQIvS-i_x=mg(o&ou6K)@R=Qp98Zd2f2fYa2Fo5=kk z+LFR?s0h&!($je?_=!k6j=iM8!gzSn=PrMf2unCLVC%ZMRsmy!7RllFbQm6=mppya zFxX&J`~8hhna(y}q7GU^Pgq3vo+1Xg{_C1XSMNa;s+6gaTYuu?%ADAJZmc1 zRMlxd>sqGjDJ}RKyDO-h`lX@e^UX@3#LVmzt>8))IfWhgjr!N85+f_8i`b79j#HI< z$mLKl?j>WZ?VP?lsD1++tT88>SI1?XSgIw(WE}VpK#}^evw)gXOC6!A8{wDCvY~U_ z?S5$CK}j=Nf64kGd#|lLxt7-m$HUfD1<^&_X4r{5LN88?rZtxsJS5L+Hwoeuykcd# zPnsrHKEDz|V41hp(vebNSQ(gxW+ zmi*eZkKe^3)!o|&G}#^saj&R2doCpJ6!zk2VFe}kIrQXy=D#4O$Pvt39@If}SD(;W zJ=W`Bm_RC%;wW+CP^R^B;k}tNN`c za85tu2PMo{kit*&PJ7s1Xzl8>i4IG0Il_w0O` zeNJV0XdyPwx>0jSnF2w2<+sFZ<8UE|D6jvRl16ZjPu#br?KXaNGs<>J78wdJDUnTD z=9Q{@u9mA5vUfK|e&R>fu45mw9myyJ@Hv;;Uq8Crt(o+4VlD4V`oFaW>4zPZrf?1r zBO%_su}{h3<>F0Kx6v(@eLoqql&R7NtuAu)sgH>E zz-*r$BSuyx#=_<*;Cb~otEmi%oi0nXrzmLgjmagh`)?NO>>RMPo*$$jS*FVVwxWB~DV zmw6ie++y?#UVOY)%!doWzj(3rm^Ml1&p!YI66$Q;_59+l>P;HsJ+8+Nl!0TJC=6Cw z2A&$=Xrjj4BDPFC4>N@LQkLwZcWLEe zg%z$7Ym zF!)AcB$wPD`g@sSQ+9i7m14o+6<5w5$FHBf#&TCfH=yz!jvx}g4{D2UPgMi|0qhQ~yw&E{twr?$)UHXk!T7kwQ<$(^Z$^c?5q`_M(EV;hsER zO}1S2?zC*y&HDqhLH6wi+16A!z3uw5?FtF5DTn*9g`g`_xetS?7q^m*vldN1o2Nbp z0xi)}NSEjxnvkkhQVoo4KRbjMdgP6{ZQu0o<*2f)(@5`}MYrA(q^t?^9hytVya^LY zM+W$wMYY&9X}z}h-m`CQx6C+}VnhO>NosUC}@uC`1(m z)eX!beyvKvDKR?wZMTXpGj_>-$owTmu>U+7Qa^wiM2p+_Q;dF-N2`~J39`Vbmw=#T zmhRu>LFN1vy&3FJM*aal`dov-UUg}=IoX6pJ-?M72iaRwRu|x*Mix7glZwH}M0#|q z1F@-x=i_+# zjlrn3Usg~TkZpB*<>hJnon3>!ZT|pv*gUG#;h}d93Xku?q-(T%W_iVNkJJhC>QjXf z8?}~2SnF~8j>?yV7~BDMC(!{_dS(Y;V z&e`_FjuH*5x0}m zJ6GAGCLzn8YhG=X@%z%6++876VFLo8Tn~tqiNDAN^FHk}P#Z@FH#3D#i6!2(O$J6y z%xk=LW}D&w^{$VvzHuLz0fNgXWB#iz%AaIa5p4Gk=dzn&b^(F3b!~Zgjo^jPR*dd) zk&?{jlyEVhGaSY^BcT z+Q{nhRV$b(9vAJr`?`^KA$OEtvRj@hilfWVDp$Nly9941^orZV%zZv%fJWam{&ZmC zZKBxBf-HWgP+&FxL@JcC|L^B5vHqL@!YBP=2m&CnEcXHfhCbNsyTBI|@Np6QSU)+e z6eT7a9lf&C|CsyOC6&5o`HxD5l`&Nv_lua|L79?T;{?j}KPYB!P#Z+QaYc$*iw=?Bxv{;h=ekcSjN)yr_`oV;&NlePZ}? z>OY(Y_LG)93N0ApFB3h-V*TR&7kw6lX#@JrW@G70NX#LeB6wh6jqx>Qb@g4EV_qHd z-wm$(Z{SgqwnoRSlyEJ3tZh!L5zHU7_4{y!#a~~|4*RI-@W@!;gjb1$`_|VbM`^?!xwRdTy z(ORXXmaI~dM&P$pJRitU@!ssCF=9!UO33b%svL>#h(qxcYVjJB#N;qC`GNcsws=>u z_`(&*Hp7(rNZf1oe6xltjRgdO^e3QbjM~doYf#*fiFsv>3_un1m75iA@`U&v`-y zuXin$1-SkM4*Vr~>)WSQcRg=9QCx5BINyfz|7KgaTfb%Fc|tJCNI4cFP{97M^NM*! zz#kuA{2U5~oVwpbJ*taoun&S0$d+s;!xo_EZXuS=Ccc69ToySAvzJe^>Kvs)Oy*aN zO{O&c&A#ndB1G@7Bp78I_;EVS7#RzDIavKB2+Zv5=4F_t^1omxJ)?TAk42EX;3yY-PslYb{Y2{z%V4jdX>u@ z6|9G8!g7Pi8C#RuO1{1>)Wr`j+Wy23#WWdt6vOHzCUceK?pIXQqolt-03#Cr9n&69v;J~IKPcY4incgv0nl=Oy%;-!@VaH7lH_K{Bp)o%Y#a(c>m7M5)cFA6t_@;aD z8IjgwmMAGv|3ZP32oKS#?%tAymPleGbNTpIgC~5xRO@@>@E zzu`H4<~1eA_Qt8-)S;zTR`VZVU!ne`iu$6wZVrWp?|kW-B^$k@#k!_*hs!cu!8*03 zq)sCmLVTBMvPN3OP<+DBkEcIhm>(cEswNP9k3WDs?1nXqMG#`88l&2gI9@6kfu}o1LVl( zm9XUS?LZ9){dG5m}(ZCsxu3(e>FL$<_ zrv2Q4r^XDx-|a%g&K^Ctw0AHe4Fm+b<>m4%wP@Kma@)^r$Q!(P!ACW|Yu8Y!{Zqfx zv%*BQ)MFYTvVAf1BUxO!rj(UJ(Pu1?0qgoppOj@*Hcj)|k$=B$A?hk!k6TcSM2Sr$(4d8xeeZwwQa|GkaHwhI>tyL z4ym#g%O|<(H1gk?o!ykyJn|Y(TBfNm`W|t@u7qjVMhJ?VEw93=s8T(IXBq-css%q< zJ2w9PVuAH#2QL?l8%LsEnmW_(@b^VNxWkZOSC-P`I&TygxLmx-Gt&6P^C?gjAx_h| z3HN@>CojO{#$-FHnFit&PT?p_Dq|}9Up0peM%1ux+K|RbgY{Spe9FW)W(QJ+) zaY2u?U79g`=1HgFw8ardFxqVi3FjRC03w#Ks`*q%@%TFqTC&6r9%cQ2g3t=vpC_XU8J&17;am^9>`+^muCyPT~o>k4xGK*;TVFzXviP{ z3xHd8a&}hp_(MA)C;+Gu`H6lIRw{ieSMlo5*Dts2_ zDCf!k*^L-;%te!q7Tdl4zAP<=Wxvl!xu8gselWC}oQoK&s;x=4RNHKg&2|z{X6Ih_ zB<<42?(G&Gf3fQDMBvMO6L}Sx95V)kt^Dj|qQb^@c{Fn7kwCX96d$X&*#%1l|58a(?dP(KePd9#JUye_!me)}RXI}G(Tt&U z69jYXmZA*FG2Ka11!als)O`-|2|?tLJrCxQde{R;Bf4Wni-c$?v7a;Rt>y1(2T8S0Cz5BHvs)E7j ze*G|Z_lif+&VE`dk=*{??{spmguvC1@@St7o=YzY{D7=L+RM7poYwJOj=ea#sJ}Iu zo&&R|qbk92HO*Kq%LWbqxYY|}Bti;;2HHNc5uy2*`QEr-ze;)UP_N;`Kq&z(F`Tq> zmR2$C4BMZFOZ#&UxcVs$m-Zt>XeXIbj85s1pj8y|wU{yCE?%~wO*#gfDdXVbJdN|& zwwkpXZr~mJW0T+%b#4z$@I7Fv`EuREAj972-H2@Zjs!zU4D0I28pWmgYL`w8pQ}AG zQ3$QOf0tE7D>9$Supyc1C*0P6WxxQ+n_lxtLBnxBRk+GK(Fj+n@$GGyz$VK&{daoq zZ~f=;k&mty8`ElpDv-YU4ha8=qCh=qHwYHfC{QQat&Rnn?tpE@XXZtd7AWzyr~Sfq zVzw(wExNzVU=hc+(JHKOzj1Vbz@*m2iD_Mpzi_9w)?-Xj4=7ZzDNMg%-A1V98*(AY zOVfGt7PNug5rkXd-wnl=HQE;rhWgeRrMzjokg5?T;&D|!tv>Z`UR%*+d(Q@Vo#Qo4 zdWHTyeNPFFV-cCrXjV5D6I2+;MGT9$M`q9)#y3{4?`(`M3fRA4SIe2#QStm)U8qx0 zdmcA_0mg#D>|HpG=@{a4K*O(JBc3B7Mw+QI!3ht!NHMeVX5d2fvoFn7a^ zurDcZqe&uK^Bxon#aZcs8hUA_VEY7Pb^1H14r*F+TfBN=580QwU%<9c@l%b6nWW7j zkMXrPqD2(vZF^jX?Po-ObDDdv=!0Hrs}B&_YlX!0-`)6txC^wHsgVB(I{he;4=r-k zQ*L#e$T1u{v|dCN?TCR3;6LG*;rI=3Mvq9c#QQrc>fF2|QZhy%urj%wxA{>o-O`k_ zoTeFNd6U52J4>^boH_$X57r9T zX&_&pvucU7xT5zbFn#j<4KofD=?}y+DEUI>K=B!MtBrQC?vuP4ON31S--FJ#MU&eJ ziEgG}!XDfbTQjT_5>V34wbz#LtqnQRP)@U?74Ec&wZ`j6L}OAz;SBtu6YX6o z*Y?iua;Vg(4af)hZ__L}&|5H{q4ZX$=pFh~bGxf4^lC2oqTK(T?M&fi_*0j&R}?E6 z%Rd<3S!@(c!>i*S^7^7ynEymlUTnH?A&Zhe&`hKih0`MonhA5*78Q=hV z-Te$W;CNp+D^c1bA7e3o`X%vUY5J(@6+FEZu7{%^;!y z<++7fy%VOgSo^}6TK3yg$EN|HlH#ucF@@^^;KHfy%j)!5BB#?_DE6vkXBD5jxTrpr zuT*MCF9zj@)KkVpvDKcyRz-i&e!*VNsX=_ffsVX+4+a$q%8cLL3nhZE^HQ<$4&n>% z02Kq!O?i+J5y(jMNh!`n^{jgV}Yd--wBVXXXSVj*20U)IyKZ+ENZ_0>k$hh-ck zYE=@ZKE@Vm-X=C60PmWtfG#R_MPgVrRK6du?8#HYxuySzFm)A|yjj+{)mKWmE*zdI zGS%PLr)6|6IfKf~?2LsDXeFpsO_&rKRLt*_<@n9lS;1E@!lkH9WRXQ5@9KkJ+6NUh znzAy@d{2{$a(CAmjpV^o_2nQ6Udqr-9&Hc<1qs7nqlV@5Hym^RljjVl$@|3HD$W=A z`Dzn2jjeBHYwQh_P9`_3a@8yLZy^1{{Uu4B+dtWFav2v(fQjeErTz;1j~}uqN#YCi zuKnxmW_FWWJxQi^TFKn6OwBR{8pK30<&q_5Uwlw|57}VomKm)34wQLq!2hs3+dUiq zzONrIixS0a;hIlaydUm0qj( zC1*OeXnM_Si~$?G9Bpj*;a7p%ZJ1ZKf>#rZs^E1~@zxgoAmEg?yb)?xzW<;c`96@K z{MI;cN}(q<^x1ugA)AXlG}7k}TS>t($?Z`g=#ushO(Dn@{D5d^h?kr)7vO3LgggPP z$CE+ui>^`*H_6SrN|pw32AMgV`@YAY7spm7{sZ=#*2px$Xq^j2ph5BXoS9iP z8)x)?bjU>)v>0x`%E29+9l%u>QWe|0YO&hoN(EX$IeUiH+;7Dqzed_eA}1-_dyAh} zXF+W8ld6#QCD)uZIhOV}zwS6A2fOYE z^)_qeFa;e)P_-m`K@M&GcWePj8NRIoAF9l@7lNBQ;%qL?275T#qXf2TWibtm*N+_q zlJKi&7SSsU;!r)i|4987nmcBKz8F~C{HU>6%MzlECpKng1jIAG^CttVN_PCrtA!>N zqvHXpQ<}Dd;`f?h&*9zykO9ecO_$lvp(F#G7cju-SUItZ|5EbVjEKbLL*%D8r{pR7 zZ3Jh+{;$)g?59&P^Z<_4`@pAnQ%*+YK4;IEs3r;&HvaJu>`kOQH;ZCN8haGayZv~R z5?T<%Y`MVBISm?ViMXfA$uOFnT(y0>E?4=A{Hf6TtD@4#-!JvQ2jh#n8gTS=4p~Kw zR!M1AKgSusy04roth7VAaG<>$R;OM|fugs}7;;H{w{m$I+M!sHUnZ980uD);V1m0u z+*JgBIVoGgxeW68N4rb$Y*)va>{i>y)2Wiqd~jG&TH<0j-Kh zEz>bc>CvfD#5!M)rpjlnvBZ;0`z)D0nmiQRxf59sO$w6u9Z&l)CxH;(!TN4DsZ66} z+-jsqFK3|m*7%eaEb<>7%?dYk>8DmfcIAM=CkG_K0Xn1aJSddqW!t&dFMf^Q<|4Y_ z&P{9_O+T`5@jnEUu(0_bnP1xMTilu&zxG;oH6i9=!56u!Kw=iNM~-B>^=tj!`)X=MM?6uZ-wp!E<<{evO!7NoE&GGSIaFL!>WZr8G- zV}w~pKkBbn-LK-OpL$LDMxR#hQGDW-kN@k$%e9lK4V%TsENEw#AVF@q%s5%8Mf;0h zo(ZkbD{H;&#CMX14;G^YLeS5D0m<;pkU@nvt2udhfCYA7AqN_$d(9#Vx|U~1obwy#O4$Y+`3Lw;^j=LrGs~bV@#g_ z+wYjhe4?L#aCyCwzY)7ADq@T26by`9MQ6$1B8i#dRS%!Zw(Inh>yxP@HB6t+e0;$F z&4#q%)hBURI`N?$JU(CTfnB*6J#TE{npZw$s~uE7UooEL5s zy=R0L#Ax~Htg8sfpwMv-fvTX;3jl*F2c=bNP;rL&D|7 zOhGtyZMI5rSJ%;=Mf3E`>BZgB8*Khd4vcy+rU|~kUA-l2N3(z}O^_g4XyuUE9f3Uy z4TozrLA@5T-Z*_f->rD1lC51dWCxcD6*sQm36)c$QqCl^@S#>l-$pYA^;piAVt436 z19EbdMX0I{pOD+vNcfECmw*C-Ifb^`JjQmUdBSrLN!D;Z z^Oz>F3(h+Y+W*NOVlcd}sZKxAkP{?2a4S~WTd0V>d^|BK;C86?mHSnfXiB-Dlbh}R z*f!CZ0AxwIfsoW@M%3e0`sX`xg1-%&_J3{)bD!3{F(HMb%^~Kd$My{x zs+m+3WHZeR-rP+01n-6dx12b8$U$xgU7kc)_(5kYssT%^*XlfrGDb#;=<$k5E%-*)a7`XaIMgrd z7rw@H7;E070;d{J&g0?2{e;R7^pjG?S`g{(NA@?54}TC>y4;l+Cp|N zW~6?erk0a{x$_~_XGO2NUdRXRLJXo3hbZhM949{+h>}q4diVMpx*Zoy!1u6D=l6vY zA;K3BtXB;#x^Z;5Z1ow`q4f!b6REhy`P*ilmV*V+(ejZD_su1vf+XG;yxe!*iBYk(Z^LfFYlJ!7TM%KHMz;^3zpC?T)$U$D` zZA61qE)3N;u2rCu;%}*6gbn954y1TtXM!##rCkP8Q7Y09O?RE1P0FpGfxN~Yq#6Ba z@Zn}IJ)H~pF{vCu*TeFdQB&S|+u0qZE>kr97o!XA0d+5v!mmNUpe|(-#fvv0?xwsI z=86TC#ZA9#bjIH#Mt4dXcY+*M3?HDU{7ig<t(6P|z7r$YL~>&|%Yd zvJCqNXrGO(vrCt5Mq6_`U=8RG|5E)JEOCS1(OYj9G{h1w=zeAT2Uvp9F|@yCPGvVr zyqKIveAYR*&I?B1({kn$3w3u;L#8P@MH5>tw$sUio;=Q|Aq3B4;@fmR7;SlpVoFMe znnr;=y>aeT`Td`Yz76!Vj!|xtl}a;f1{kMSQvPp@MUf5sDq*q1WZaLFB;rNBQvERc z!QAa#OfOj8munNV*8YJgKgsyV{3rBcp7Y`TcOIv-DWtZTPa2fTuOj=b{dfN0{%#M} zOg@Ggj4X`U+7>C5KoV74-gM&}@=i`SA9!EbFQW3$|3y>vwbg9XmvM)i#tEP?O*`?A zK|mz|nGyfvaOqDP6_SvroY@)dEG_zcMLCq^nGEtO_(1wI{2D zoVZ`1^=V9W(yw&~s_ zmwiuN(f%Y(yltoUf}%HNk8jt$(oSg;F}Pm9k4Id7*NPl>{;!cxVu?41wru9Td%I`r zk9)DhJ-?G*gveUD*4KRjN>8`YKDZlVjoe|^OJ-WwMQym~P|7ma(R`%JmsF_1OP_P2 zV%_yLi)UrhefIq4%YD?$zOVlSIRCmdHC0YqQOh-KKONne&AR=TFu}-#xy1g)uY90X z>K(e!5FLN?{}=v$^00aTr*KX~3ML&OQf4>w1Ml)G+)UO87bx=ta6yBc02m%$F%*-K$6gt1ib=t+KJsfw2FT72# z6(gsq29(=IRi<>QA}m5}8=Bv=(NcC)bdf);6+_$^4KGEO zOFN5IjF<$a)UifR>8dIo<)D#vpIr*FVD*748OPQ(`lU-)ze0J(p~|;z>iNNm!&I7# z%8Cup`2wQYbwZa{iXPq8I1w>qY)KKT-LEf6%73djy<@F+;oun=?qWzcXCNclyIv`p zf^RwgYA95c%Wh+re5ZDflzqcj@(Zsgi)BKXBYqy8=GHZaraI~fUVnUVD`wi0 zsZcNpnp|&h;%?k01DdArvprrDX0%nSjAN1iQ=yoEVJfD~s!H>F=4RgGA!qux2G0`-&^lh_TC+Kp_lp25wFD;>>#>XrRMi3=_FLbwd_kx zO7(AJXM*IpwD{H4m19kC3ybKFYluOdgFZ(p-8tsFRykJlB6Y0uKg+gMXN%GoR&ddy zq(S@xRQReu+p_C4iEEVc`v!;|f76yjQ>dCPupVjb5+1}taWJkHTflem^+vd2;6ly1 z0^G z4CmLjj}v2@E(JFtN?18ZzPW#SwojHn90Lgka*!}YF3g@@P4)0(Q`U50X*`zS?Hk5- z_%QtFU8|B6s?6BWA@XB9Xy+(L#}@ansPKJod`mu#XTH%d7ss!eCMnjd45yzxyJ)!$1p9X{Ah)%gnlO6i5?&$A|O!zq9IVY-w+M6D@Ie=?zSsiZ@&QFbSD zSObKm@fVc~lHSyp)|(%?8ViJ0Y8I%6q~(G!xxXv1Y~GPBKbbtA{|;hNcg~G}wf*6V z&dAYl=cfVe;VX#@lW0i|1*p%ek>j+sGf z7-|Njl^UcQq`OnPYlcv|rCSgfx>ISS5%G8Cf6l$@o^@aBH~ZDzYwh^1=leX*M) z?4-x@mN)&GUgmS^u%u}!VK6=BJ8Wf?QejkUO0$cjIIB|1W!Y)nAAYYS!l0W7U523m z>Oe;stg5v6Rzy63ftEdjTk_;X)66q-%#hAJbK(_`Lp7W&6Z2yKOVq3wx4~0bM6**F z@63B}OFF|QLp~7@mAJ*-o7yVIt*L8Ph)hCzYJ2+2o~z_L4pvN5#lTG-Tvx7qV&3r| zJgoZ}Pj^TpAIM+iEg`cV!_yVpMV4YfB&tLuNB7~STm0r&bhS&*6MBmkMjIyNuSZPt z8ON5f1)F{>bqpj@sHLxtmL|AwX3qHBGGHxy$vmrif09wOZLNy$vPG}d^XMVazzAl2 zX%#?IF(L2W=S_JE`(093K0X}^zyMnq(QR5a4?7rSI0*3#Xgd`k{L)Z@R~n4Vx%cuV z&aK~rsK7iAsheIkse)4rf-U7Nzn=!@;V6Fn&i%@SpT9g%x9$~shOhRp=qto-{Dyv6i*U^7;Ccmhk-{rJ zJJwQfS-q>X5-9zern3Awa;~q27l)`*t{bU{s3#-VWqVL6KV!aG3|Uf zMAz&WSJzbfsGtQqXXdWn`Fe9Ghk~*}A-XOmU$vbZ3J5U*Z9y*l8I%OO<|Ix*@m^f? zsWHp`Syc{f7Y<%g+)c9_FTKb42$~Z2At}2nRo-`Y_^#`7o#jM&s#{gMm9Sf#yi8%` zk*^DO{D#MphtpirrDyTeN}s4#;Pf~*ZY)EiYjO9QYcp9gLLGsh}L zx`*5S9c3Jt#7X{~?Qq<4<|{L1&3lB;`N2Vw*uv`ZWsQuDmin(0o2CAxOL`;-u5VbW zR?-%RSpX|+El<#}m`uB?kp)vZOx-KwH_(DtB}GT3YE?4)P;up=nov))$FDmJzT+l! zp+&4&^L5P4R;i>e;Cgm5^$E4!@NbObV)_dskgXuMeUWCs=jm=Ox5^u1=kKGoRKXEtosNR+Nxa#ze+Cn`<1m~sS z8-%(&G~72Q82qpWmYJxs2fbmZaWP_z;;c&rv2;#|l0oQ5B)GYfi73rn0!(!(V)kVj zpsow4I|xcuu&++A+7&vZhPhQT8(|2#Es#4;W z-Ld}WEhf&uP}TG@KxEY}@&A##1mY6oH~+AS3B&zRAA<8fTIni4s+6Sp@66*f61RTwd8|B6N$NT6QzSLE+gA*~V+2A1dBIHKbixTyd@P|tiGRP=OhtOboSsbeDq_f{M)hP2;{9HooNjkIBX#Of8@qOwg$fBcAY|Dc_2wzQnH0*cOnHKv|NCKx%;yY+WS!-ivnLpNWe1A_jP z{tCWGvvntLel75MvUKsf`Zvhk^TpB$VF$Mq9qoXHX=?a0%^Ka3TgsME*oDw7a(6Bp zo*cqhhC#vXN+7c@{80XyxHkRyR0EB#^2zm`4M%R9X+9l@RzJ6F-e58bIH4VRboT!I>CqxTYSuf_7p{A3j%@;JFv_D?1t z(`yQF{R1WiE`hrBa2zNdt`2**f)-b-WjYAc-N(1}Qi?w`nR=@w*#)afEA#9*|Ig!N ze}AzkbhL9=nYQl#=!y}vuXvbshi~n<)i7X*v=inQ-cB6IZ>a(yVK-cwx*A0yle9Zc zVRXv|gqA6b%lEJS!6qh_z`?`O?#e}f>BaQ>8>^U!v6lT=gn=jNd*Oi>%Z;aS>9qSS zZng|o+r4e|GuX?8BaPY{h=66&(nI_8+;MYlJJDtZJR_~xAPUiR0_WD}ho@0|#l^Ie zmW>^2lGuk-f^qF`gV;e(mz0B~Bj9zKBPZTf7*dI5N$g+=mAWio@`~X7 z^O#os$tb|OU#U9cBYk0!(rdU^D0?{qV$t4wFPk?y)@N%^C%{)O^$B^9x zGrPIs26(l9NOdrwm8k=$tQ*FiS4=G7i`r2b>=-{{K3rXkYRg5h-xIdD`vzPt<_@%0 zXED!ex$pGV%=~h%bb7M-{6Bl-> zglR(pLJO5ywK)7Pb;EdYIq{{V)A|Et_TImhgHEbS2T^%Ylwmj-u9naWGLUdW(+p3#Q*hTR{*Z%YN&NRMYE ztl!-JVC4`$20akXZo4TSjLKY})cP;~2*l+5u?MIAyKYr(Vfr_94K=gXt(3+Y5;S7NVolg!+dE{yu3s=_)+eQzQ ze?o;~Qe2yZYk}|sstTBmyC-tV6-6j*hG_UgZ{8&nIR5vMW3tYeJ?JmFM8vmT2}*eR?tF7seAw@$HWBbDB+)jILNDgO zC&mU{IgOu<79o*LUP$R{rYm5 zm8B&@sOVk$eVSdTV!kUNT#)pNrOisk*t+gm+DkuH_+Ft=tT%Nl`5FW~tKB!V^+out)wSlKk+AfRr92NNT=Xh;p8hgITjZB^PTu2C^K`2igj^+QvV zsbzigD{lx@$)PgxW9~PLP>2F9(3wP=n_ep`SV4kyb7<0_x!tLC{bIy;p6(ol}hHz8YK5|$0ugM73XXYbD61Vl0O?+hR0^tF2!i+dfAO01O!UL7O zhIf-)UJcDd2WkytT($QbQEtsvmG*Y8k2lc5az2uZpYU73+xgN=cXpO3g1)noDy<)1 z_K!aJRMMqsnkZm;3zRC=ye|v~1g93-?d9JeW#Cy)`5Du+5^c4k ze|HZ0q#quH{)MYZ7U3Pg-^Li7G1)3KSI$b>EvA=#IWVZ1n>ax)3t=>%Z<8dR&8?$U zW;tRu16IqNDsQ)V@Lwn=< ze>k&cw!-3!lD)mxk||fFx=vaa3jxnG=%f;~{=>oW;PjEu7dwlwJ^jMeD5Dp8I@!Q8 zPzisw`VEQk5ZkJ^n?=}NE-%=s(?FDDH1f5~U$GX5b4fKO-CJh z#iLUt?*3tRXLV~O`eBjkcE8$~Frua{jb5v}eBK@@X83Qao~nVHY6t9adlFj82J%+l zqJ}Ll-Yj!Z2~N7#HqZ)Iwdt3rHMRwn8rrY4cMX(PW>m^RkZ)xvR?-d`kABj8N4O$w zVfl1u+8lM52tb%Kb+TOYIuD^+|Au9MR@uiU{2B8c+`lcPmzr64RmZ!eW1|lZSRW*sN7i07{dgkc zv_kf=t|$%CssB}Cv2I6lCxStp`yFQ&@LV`JvA`uc82ld&h4j^sTG<3zD~>3i)`e@B zkk_FSLfj|rJdmgs9vkw@uQB`ZSwS>Yo9H)Vy{0Qg{-xL@5rFP^wEYZy8oeG!R5cN+ zlI|!sG8EER1#O8>hUdq@lTKOUY^5{|I=EJu%hs2ACi`@M+ysGm7 zt{ngmp zc_ZhtG3vys;y^H%AWnOf@W<@Xb$0xK9dK7p(B*mPf(0MNTfepzohPAz7`jA+lE6kP z_qTr6%ApFhf~HErsVL-ffwS4HDQL?6B>dfYZzmuRzF%c z*}uODLiIRVb!?`PXV7W00!iF$3~&S84*+`(M^@t= z1|UB+2aoliZJVKE?CI3%Z`JskXZEUV7SI!oCr!CJFKAT)P8y!(5hpp+PS`V~dAd_5p+&!9dx$U&YN~gm)-(gTLkboB)t8bfiq`@Tr zFfEBoejLqye@?grf>%}8LF&S(n@0HQ&$R*FoS20Ds-=5|w%WKEEqLymla76tti}UR z_Af$|L?8zS^4kgwB%(7dY4o)gim`x|TP$TCrMXz_^qKNhBq8aGoJx|WsuGE#eaM#7 zzP*12+SP7&4~K*c8@&4UFs(+_pR_0Qde41H_0{s;r{z0KZMZ||Nc4Dko};>OmYtH& z%P(blwtLeJl2gQWq%ewN@=XBekEcI>?pF^d)tro}j5uP6aK_ymR;(MOJJ{L)j?VvI zg{#&7^auPuN0+ysaX|j$e>ek04J~5xdtIcd*a85aAD=Yrtnc+rv;}+ji|yM?i@(41 z8GKlaX%&POlzs$`E%(vce~pH8ZDt(CYiq+wD)$ELX+@P4!w8Ocs!-$hh{%IfncYhRRCHu{$^b;f zs+60Zozn=x=IO~CmvihdVg%c09N4kJn}?Kbl}sp3AEMQ51WKr1#Xo#azy<`yjH<6$ zFL&0i+>Ml4`P}wqKP>RxyA;b>;95{`0w}BJnGCxh*{1O_g`9cEnbX!KA4V&tLQ5+_ z@T37_FgI6IkyoDhk!ym0L+5nv4XY7&-$U8WDbu5afn~HM~mS-^5}M1z6If27v1C^Uoicx5;F`rSoQ&~nqrCP zj{l@+sd+U`^|E~i1DivBY%X34&m*-z2Lb8`B5T^g?q~Tzr^SEa3kl_2xs{i335#un zw#f7f5j+1`ZGVBLqv-ECG`H^JR93&W$z3Yv8A0z}7E|GW=aKYBzPp1X{4M9%q`(=1 zKM~YApwDFS3f}u*bw@e&W;$qCVK)f?r`odLlsmaN4WYiIg$QaC6G(X5O7&1A*0qR8 zW_DhLq&$YAt6{+7jF49UAuE+Yy6v3wWuy}%#4pkNnXQ)?Pt-J#c0-GGQ?6=9@F{bM zf!VDoEo|1}yb1V0`1^~MiR@qX1FhNCUN0U;uQoze?6&Rp^w*3kgrNo5sC`?Md!MmQ zXbKfgw#?{P$ho>bO29bkxPn%p2@4cxJV+HA;Eq6qIU;lzpe5=a$w822!^(z0vahQy z{8!+QUj$~EjBq&_8fA*FgP>*leC}Lo@jL3!^_&&Dt+tgNy=J;|^lNawe)3MdhH9c& zO;tKv5t{!*?bc5u3Eft9+B7$3n<_O|Dv3|Gx1t}~Dw4I7`Y`GG&eXbNwNg#@kpZ#! zr1M)T-roSl5`qo3YMwoYHhxQT*UAG9SNQT%-;1Vpp-$d|FLt+#x^J)3TOQY*Ed(J& zc+wA|Peih4bsY}fNO#3@byL5?Ckpj9COp^PnZQdb>VG0IBZAg88Ppsb{fVKxO%at) zssUMW+KrN#$9uFBg2r5_{Kr~(y@vttBDtaMsEPMp!uGx))8Q@jVHK25YM0W_jXRVU zdag5jgpg8bZYGRF8k1IbSJlgx%ljw~REMfnn`BsOpk#WBlIgDA7Yeph`Ez^`IEGunK-oh zl1FZ{aK!^VO}jnPK~lF$IZU$HvG5W>J|-wSGRiE88b=)sRDL6Z?*Gs}hm8dRA}^gA zY5t{2T2>ecGNdxd9J*=#n?GfqhpXGgX#}Kb=9@-+{9!3X8MX`?^|wH54gfOsB*`4A z$y}@)#c~_$>?_9hcytVw!EstEzIn}#$D8PL$2bdzu$)X$jlPzW!fB?PN;-cEU6wy1 zAN#D4bTrE`@U#>3Z(x;OjjBG#x_7@jUYNXZkB%NOd?4LGmJ6MkGFMd-BkD2W6$Yo` zrj_-#+?w7sMrmw?It(b1h$7er zls@1hfdJ>-mPTGQaY|~MWj`^yMl$If1U6;xq&O!TFFo&H1VgO}_~Xi2(M`ZzM+}|} zTJ~42anmM0VO5{^?u-pedxOA}p+q5a3;r=iLl8c~P*_?l zc*T=F{YPo?BXF;R4!g2n&@55y>?|~e{jtD1QdS_l$q3u;=LTb4D2<;^WlTy$yxjB9 zvK%LKdBS+E#Hxha^omg^S>4NN7glG|t-%9JNZ#S&l(!I1-dd`V9ydHukl^~87P5PO=OMYP zWgYmE2>0mKVZu4qapRWFO@QM>f|G;4ESKIM1SX*M-uPsiF{x~z3<35DVGGCH$uKJ=U_ff0^1ZlYIhwI-a$Mh~NGZhkA&R2ERUmaIe zKcRkEbX3=YAN!N{4Mso^+!8eD|rVE1XH)+DJOcVEBd} zTTG;!yrc*vk|)7hbn#hCE>&hXYBMfa=QT<1KD~NyU)Zb7KWClMw8NT(*dIhx`e*EQ z$GJTC{8K+9;%f-Tt94gVc$tC`WP)AGCQm71AF_gfmyW+Drn3tEMxCIqD@hHPh>4hsU8;9kW+ zMpq*^-UqIAV%MlyYdwRlZ=^C!n;y_onsYl_rN|pACmk{)Y=lWxIqt3gA4h>NRp8Rm z>WTJaZ=}X6Tao=KnZ=@V+RaK?DHVCDAs{5U`!A3okK0iq9~41nEu0N{pA|s>R3Ycq z81H)szL7&XTa9qe#R>3;h#i+U)T0zgpn=518RgFZmN@oiOo6&q zc+20>GTo$19lvA!F3B{Bg$9ChSQf8_`gT#+KBe}@|63P~Q#%3m$SLgkwNusN&ft6Wo$lh!8Ipe#n;kM+m>c?%2@#WIO>UB(Tc>E|-;dWG0^U__JS${Fz3r zcD5iWOaP?AH&l4Me=#o?dx+XGajlaFK}PXZozDoU`u`4}E_YRIIw=aYiOpZ<+NS|& zvUz+w#G;(xSJA!=F;N~e%ZU0ty-iK^ipqv8hv0KV>$8iVDF#<7;z!uTM9jNPxoej< zHJqbWmv>!KxW=AqvE|k1=}nZp2W(!sd`G-h*N)8n9UlrOjSrW_AuQR01aaB)hYi-aYQNt>s}dc89ed=GW}bsBecsKo{pg`nM)mA;p9rclp= z>zBL-hr7i;rBmRA6N&zyz|my(`oNVy+b!&zOk7@`{*5NAjmS!(pG5)atoH3;QSRAc znG%L$kz)UVbwQ_&?n?iemJAz0D#KMaZ7|Gah0&tYN0b~XGa}8n0$e`!!uqpmm3N@B zf_JkCt9jE)!CP6X%gEVUdmT(~o<%;XsAS07;35#j0-+zvI|ToY*F#YT!L zr=g}!1E@gc@o~hk-CY`TY&p2KH8RO*)D4B~B#=pwKnhj7PS?Yq|8qqx=6enXjVd-MwU}= zW$V0i9g8v69h2>Fy_%m9zu?;Ni((bZ_*pak^t%~#jkp8}4my$eIl-qG1}hmwp*iYs zjJyLuvc7KYMoO9)nx}O{=I_;W>$2HVt?ng8uylfTfd?U&$@ec;!th}^;4u`iZi~r# zFA0^U%W-C(kN$@9XtH(&N<-HAhESvFvqAe1MXDG6b60w%5l$}8^9dPuUj@7YTIZ%W zV$B~E(cO)yqfem;L-&I)jHkB2!!@V5EpJxhVU9sEu~4tOCj#HleD8p+aX{D6y1GqZ zuxvC*t}p3YZ|^jOB@F7Btrig{b1A%uMHx2rs7Gq!V@)IPh2h>qX#?tzNMe#9)?_FV z@qF``0ne9|4UFByQkukIHfdX_q9b~2s~F)W8+vr zF$~nW(CjEV`;%zfWu>H}pUQn3*KFJ3VrFXX-lTlTCY+SR^)UCK;VI8`0Whr|fy0`=dY?1!$^a7@(4G%1%~~ z%v48%)JNZ&7G5Eh#vVi$jGR;E|W+6}HeX>fYeC**lhc@sZ|2Mqv7Sfo& z6mUmodCjx%RB;Pq`7}O4_%Ox9Q5>stl}yJf&zB>H5+6Oq=%}}4%Gm170&CrxcEutE zJiaZ|)d-1S%9@PeBTl}Z)*;U(OQesz zPOmT~*CVwONUWWyuE$C8a1|hd=}%x!@Ko&V(WrNeUq0syhtvp-zq@XCq#QeG8c!gq z=v6vEEx$~Q=pe`*bR!UFjyp9!^rfw(G`S~@`_}16=CB|4jXEEkd~C5E$DTY|xa=tn z(~5nrD!dJHpGOe4(Wp`9zd{!+yUauL2GI=M3MAPcZr@rBWJ0w4k#*0s3iUEITmreh zYzV^@sC)4)Qu4UP*`{m0`ot|G&(|XLA6j;9)`}Od>>c%%B`qDZ^MKeOmff-oJ(=`& z8M9bfOM+KKMhtT@g^RnkOtc=aXzt3vMG;@m?aA_k;!)$2X)`=Pk*wO0Jbr0UK7%kl zm3n8$yhf2Y3pdS{sk65s^x&R)R-7uNyEl#}%1k`+F|E6ncQwNC-+*N`>!* z0K-Ber_=~v+`zlKWE)+_epA_ng|uh2?aG@(+|bM2m<6Zd1Q$4NUsiSB)JGm`8l z{HlL^IlRF2CGr*c6K9Wl7xu?%b;$I$-4!E6hEgka5ou-%GQF!0RXA}+Cd>{{lldo| zYb6659`Z|gT@8`5_N?%9?2KNo$=;i^9m&@4pZVDK6av@(d5v(&griufjR_SRRz#u$ zwQztdW5GPZ2q~YO$+3*xbCU7o#ScmjC>poa3F*)Ame&n;Qi!W?_L2h%F z^r`L$tA8z2V3)}Mw|nsaat?NV`t%=;)}O;eW60kR=W-9Z`uBHe!Vx&O!~Tlocx(gWaB-Dv7O$M&)te4dZ{3B6CzUlW*Gjhk+z zJ3sWz{$$cz@{_AVf_?r3e)*?vtS0Y3-#Xva#3$FE+?rP2!OGR9#AQ1M z?Q`wJS-ve@8mCY^1%h4|&yV-MciZoDo?!~wa%{{sS@EP*Cts%}r*Z?KU!3$orx%iQ zc#Ea3WbS6)7OfiZIEWVOvwiGDFIGXXtx%5v)L^a>9%4?mO0H|3;eY;JJ~58p407d9 zJr<8ohD~l#QF)8U&=oP!46X8+{f5uNc?w89`u*_NdR5NaTa9={wcO+e0eO-RRaXXW z9(&)l(Wd5lC#(&$6ozGTI&31Lsg-{$dHNAxVs51-Tu$TVv>(^!m(^XQb#EZi3&k-L zoiCf0gibv-Rx|A-%263DD|BSH0GHYJpI4Fa8FW(NE90{u& z)KB9}W`efjk%9+dM4tpc_)Prj8a|j_>%77JGnSq<;8-0ay9x>q`ncj!8N`1-{s9gG zdPDV>jB##uQ*!LWjq}EiC(Dd~RMNoTwykn?vb7qQRA?2e$ElY}XlGeY*tb(8_Ya(z z1_(216%56v#EX06eb9x?5=oS6tNiV17t9R4wjA&pWIb-65+8a=hm)S3i`}2|J1s3Y zdo966(}dG>QkV4@LhY(1NS&(PpKFXb5(Fo!i6M+5X!Bn>`CYljUX`~vAGbTk_U*fr zgDdnRq7}9!k`ZOE1F)^KA2%yydMQ~#3HekJhB=(qC3bLK7hpa(SNc-f zTHU$m>AEa6qWiozz5;egdQ{$$4y3z`tdVZE_|jZl*|h5M3gBKg8qtpjlk#zywfYaI zw&_iB3mm^a)#I5y7_59Bt<5?ANn-_GT>FKsG<%VuB8Ccy0|I6HmrXe2ywgL9I zZ0DoYE5p?>NTI~y{&$8MrLnO6rN3Uc^*JZEoqt@3Q3*$ z0LkrY+dQ6KWI?|xCauQ|NvrO=V05V#xd;kxysgAboK>GFkg{0f*mI?u>N%aHf0(Oj z-l_kvIQ2~T3|N-~u32^e9Dsk`%5iArBb|L)?=ZQug!4kz*tN^Q*wv_JS4LCL-gh zsDRJ;!|!UT1aV~_TuKz9T&{_pLt&}nzb@O1)jnWQX+{%7<}-jZi*pa$U_SdPEpR|EJ@kguIW|my;NQ8#&i0-=QU$l9rRdRCxh@+( zP^@XiN_^=D!iyWpD-mQ0=v?V zs{35(J=JIDJ4Y{MQ%=Qg6cWg-03aN&;sLS+e3MbX9CGyC-J#>RbB^;x#``dea zl5rP}9t;5OASe>r29?P@y}Ris_HMx5x} zGEYcqL3*D9A8RDP*>=;{5 zCPe)k*3g~#^LR?nh$f9wpYIzc;MrsUA9SQ6ByOYBlz``&F4{N~UVrRbmKZsYuGUKm zzjv;{$%}P!sM&N+Bu5?oM1AhyTeDC@1PK=N0498W4oJ9?U-=uaUzWx5t|7Cqm(96) zt@-;nOkw!V^@?%&a$Naoew6~%20`rRTTD^Lb~O+*s`U~^QHVj;(bSEyAf1f2)1JLd zv$BjL9?!Y6H&-t%pr~kS3x2nZ*voA_Xu_yu=qr=81!=^N(zO!d=4^0%v85c)5z2qe z;&&#+Y_!tGm1#f#kIkHBfx{B$n@eTbDshb!Q}q^hSa-3J`z}eY6)AIFR6CeMWewwD zT={)DGvIOi>5-dtpGm#WTlcq)qIKaTzzlWx^zdXyC_fcit9<2bZ!D9=Qaw(X@i6$W z_oEx{q+Jzmp`jGA->S}};8BAWs;Y$@hu}^7ow%uN2`$>Jv#8DzhGmm?w7<=2}yE$ZYpQ#20^|`2-EWYyoheRn;?wbK z7C1+Q@f$+;X7;HlHz6GEaRn1)P5WH`fHF!ov0+mn4{}G98q4H^9g+n6 z{Zo@Ac%Q`HKzuzfhl$56LE1{wQ?!X+wueH@(D?m-HPW8m2X!Y0m{}?t5K>v_vhQ`X z0QiPJamIQ-s9j)YZN~zVoT2Z)Whgn#J1Xq*0!Na#qq3Xs#`Q^LJ!F)3$;86y2_5lGBmK zcbOKVU#I>DeFp6OVdh* zCaRNGQ*!i&!uvw{&}UiO!KHMcdS6ZYYW8dncv&d%;@P==mYn~>6l4-n$E1&nh;bVA z`H(*F>Z6wgbK2O|2 z2{LD~5*)y^+g#g6Vk*a&REsGe)0NMSw}&X>Ih84U7>_PoAx?be!!$7Quv$ECcSys! zo5E!o<-`@6YxLpk`CTjU{+s8boC5?@^8-MB>sZMLHg3ZpY#UQs6KNS#Mu=QLJ%~=- z6_eo{hUHN_JyX#XnI^6eCgDT`GnUVM%KDS#DCQt-&q^+1KwePFtU1w#Ikp-Q)XoRthHYZpo~!ObNU`>Ev$O(uwC{Y6LM~hZiuyys&Mwn zks>bbWVU(XP;i?&9OEEV-D%)a?rnggCDhB%O|6xSH5SQ7BttmhUICiItqlu;=Cs}nW$^F$0lbOB2Ba32#=IYAI)capc$<6W!7?T zB5AjWY${86{}IF4(x^gGY6dh6BHnO|iW~_@62%+T-K{_A`3eE&M;gp@CZr$|-8-Ax z+9|LAxW&9e$;6f$Q!9u2-rk002FMApG1FU0BmJS%31jR$8p|O4$7Qnf$Ml&&&=?_r zoeLlBSd(8T$lw+Zd-CMSo2h3l4p!vLpH?thB3;O)HkvO z{Dk|_`L!W;yFjhQzMGbNK!mq;Y6PEtm&7>duiZpOt; z3?{=reVjy{JGzFf{cy12G*$XEg^alu@jaSYyjQiQdpp9fT6{&;@JuF&+fgV)y#?7r zaod#sGzVyrTLQ~eI8l6GMcMEE>&FlaE72oyeZP_6L9Ou(a&LnB*Ec~3gIPH>U-Y(k zuK@GSa)jLs85$S$^o9#AV?Us+4_m5ilpukE*}=CU&ZbU3Hu2@JaOcK|CtFHUPLByo zyP3dR4;`>qml!Ws-&Q+?H?NucMpx2dB{H$@Rd9i8lU0!!gkJpr$29rhe3Lq=|JTqI zK$T26CO2tp_kUy>m%}J!oH}3Jq03pJEo|(+4(&culdp$TJ2pL$Tgc^f$XgJ;Rl1Mp z;L8RALC_N2Y9Ge))Pt#1$6@K$lKFLiF5yYT0JZa4#%3uf{O1>(EHHr$B3M!^0 zoI)Rw9u-LIC5;`1RO?BM->s?CwF`|7{)eOYI_LR#VQZaN?IBVwEiYm5V)?met?|o` zfOw&!+^YH$#%Z%22=q!&{BbE{@CnRV+Qs)ScH2PcxUr*PzCwm@+3ia@+CY@7g82lc zs78JN(G-!0Y!iuqz1n)AAr_otSvP&QofA?cxA;&D3^BWEZmF~;shGYtzjbRBD37U@ zGt8i4lo#5o^-{p`>|t(Hk|{Iz9^~w+(quOiXYh9HX_-L&{*A5u$xLyLL4;xPSC+3n z{oxa!^hSfv`CB_y0!LKUny-v|zy?nTp>v4>6Wi9Ey-M6!VdpQ2Wc7(DITULUx-%;e zU5%CY?n0u}GIWUsO3)6v-IcU??oof}XG1~&rI+AiETBV4HmgmQkII0WoF%aG`uH2D zTo*vt#E6Y3Z=o;@uen>d0;OM6|4{;tJPee+Q)Y&Dt==nEwe9Vi%oF`I5=9AQo3!rF z@Oxdh@cF;YEQd1hYWg?wP!#^jRm!5>OP@}ZvTKq*I4x=KjniyJJ)J?;Q*5DU4z90! zvIPZf=GIeNoVcY&>7>Q+VsLpKl49RJznCBPnw14``@@oE7Q>dLbPHv(O!fZI_RbnI zd8v@|zkX!G$iQsx+mG*S`d!awd5(Xn;g#rftMk zT2)A5D;vvC{YIb5?0SQmjh>QvkRzT$wq0~qcX(;kQ%8;AmJQt!vB1Je?ri;B=M06O zZBYs4o>{+YlXfcC!QursvgsJj2n4#(uocZ=PcC1yOb0j9KcIbH&+NLLFIdhla@nA% zziNK6PSLK%D8@bJwwhRt4*R1qCYhkpdLZBSxMU?eg<1e@2TEMjN0j$EmPKs>aRr)5 zZlt(@oEikP7)pwU@A?16Taa-LU(T`QG_sW*X6dgId9$=IP6TLfC8ecxcglj*y)#?P zYN`5tMO&$$$iZsBmz_uP?EQ~Yc~GJ%GwF>X;Uydl&*kVOXxRc4!@tV4<#McuA%|XM zs^w+6={v&XnlgUeYbhJw`_rvJFeL(-ej32`cTvna9`FTc5^j(-BWTXSe$jmE0-sd+;|IhM{cnim{p$b#_p013h+N9w;uYg*GU<=g&jVw=?u}%Ff+}tNy>dQ`0MUFC$0< z(#{RUerRYYqucIii&?c*>pPFtR!J~?Q`LFM$UNp#wYCF67jOST5$fpO4Cx z0=%cm-Ynf_PwzbEj${W;&EKdoBYdTf{kIMoKkTe}ULUU+gS@}YsOLh^>JAk&ZR1TVOo;$}Jmk%{x zOv*~>=A$3$-|*lxY+g5ASUGsNZc(hWFi|RY=(KEG+De_`iMUdiEoZld`iVU*Gff?f z;hg8yR7;NN^{2h+W8$nH<;lX}foHmU5Rld10Elw%QZ?qT zmK6{yi=d&2$b`bu*jNRZ&YiC(?q34`jd#`B-y4xCkM2#aCviEx7+$ICUCH3+tv^L0F=wRvg^`D*T8G*1^Q#<@>7 zb?v5odAl-PE~V=09;X_cZfb@hUNufS{;ltkRrXK#4=nYson|L!ZzO`{aV9Mf=Rgcq zrOE55EZsJ-RSUyn2%#c;449SF_aeyKF+1$N4tjxhm}4^#_!FiYWm*olGXXY( zGX?YY%VkGL`%?F(Ow?M3fsgK|tI8w#_S}7MZW@}Gh+7%4?$cV?+BbWR%@q!cDwTZB zz;)~4*ku+xb1h`#cfcSS3A<5pE#rvML@nO&cy#H#_WpzTNo}KPC6`+eQ3k8kp;Q)= z`4YZHvqPtoZt+V`YJd7NHG=7q6`N|wrIa)Nj?#kE3TA}$1RJ@ydg=+he@}zXO|lR_8z)A}BnqLU~I$ zfv0I!X-w)@0LPc(Bac3A22*cev#el?b?`{Y#LJIN z7R=kS1*YDN^vYjxd33XsYeOElU9IXSfSR$&oxjR;v2w^slx^!IC^0g&Ks+cN(<;c0 zLn-`4#$DRP!+O8jK*O$g#U6sTdUuJ}r`P_jtnat=ka9Q`he%>3fJ~7kwm~wC2LLrD zcv{3urOnd$H)4`!822Cm{%f+Luk2-WnKVLB#8}~-&UY?a7cEo}h>I$(PZoY8``7Dx z%TZ`W(-N!{z)6P7mePl*#c!V1oft#9GWI!R9JBZ5ZGBbDg}+<;PMxU;eNg$3Q_*xq zXTQJ2n%bm@01>21zqN!pkCOaC5e_pOVD;$O6K)FCV=Q`DKkxh0i|5YSdpb@hgmw(m zEe+Wo)SnIr8pLJ9gG0siQ)>sdQc~aLwefV`>`i6+8oPxay#dYreZ$j9kxOfn0xy;s zWK6Nk1nDX2Mkj}MTzm#m=H1TDUOt_o{!?D9a)1cf{A%rX+!W_qgE6Wv^3PPu#tUQK z?W>w)2LO*6DZf_UXyNQ^+T+0s}9c4E%@40Z)Sb%Ym;vAzKh3DiIQ52 zNvWEMZ}?UPbQ=TDc(`7en`~hdun1QcOK70U<(yr zp73;XK29i4FLvIZwm7$SkiD<|Egk#pk*14F7&~V==pVdF(A5w>ybbl#)z=98xY=n^ zTU}fKNf90`TfEo#2y1z*zsggGIk+~gbO@=A10d-g22YT1j>%k!6_paSglog5F$JOA z8Un$Z5(Jx;tr!0oqN=e7MfkthJ9JLPcYZ@xm{wP>s8z)+rMT$iGzX0h>KDRILz^Fh z*d<2Tm^??L6Ao)zzU%GRlp<9r{uco4KoY;Dk-;vqpxcNEH~}E}kA!M+1QC#O53av; zdz#lY3tGa;tdYz&8mqwRf7(OTFH5tTjYhfZ6>DBm_ebqI>XiK)({c-q7J&E^R1QBp z>ttP)-ad={r`vd&7VNiZRD1QfapcUkWGxY^km|}9exqqtP_Gr&NhFQ|MGC<<#7Hr2sMmWj0b-7)D6)FL?BhNLfVMQVvt0fo=Ck9}S4n%<(3L`yCbTXs)alpX+?hbWDG$94 z@!C4nht{;#E$Wj1nndPOrhr;VW%MO!abFR|BER~6+YYqjF#0MsotxA}Y67Zzcf6M5 zBvGwCq9Q9o=mxr$jymav&^1tf)QIG)VDy*AgbjkJGc_p+02wYe}Y z*QwR}dc2fLpVl^&_Hdx`dv=ERp0qz@>Q;S&ik+)9$t;J{Q#0cux!XabnmGZH(4-0aG zxmxaAR2$Q1@0zyRZfzQ6vs}032(=hb^DU1VOAJVjB}oaD3P3?|4x^G38^9+zn^}$m z0ZHVA{Ah3-f`tH5oQ(Izvenh5)H&83(M`ITLo&Lh>B^qOyMnPvjKU-D4%k*>De5(L zkpeIt`4LSRF13K84fIT9YRbY!5G)(ELrYy2s@lglQkX8uDof~Kl9GqpUvxN^0@L3F zal!J|$&(j20^40{WsAEy8--V!Z-#!j{#p8cb=gOe{Qm&ZYmrQ0#i2^i9ylWeC@2%1 zc35RRR5=`iN$un?JL+``>g$!J%Zk7R{y?Ad{{Wr!+YF?TkfKTQ0A!!xuG+ zoN*-ta>+TzZsXze(H9twSpbknZ(MnKch_~5BsNbW*$P)>VBjPig%2b3^w-m>4rCP! z<2g@pf$Q7TQ?AzAjourDW?HF1DX-m>dSaBEg4{_JDC{~3N`VLGt7Qw8vsJ@)3N(``seZAmIYbXHtKpTPi+5g7^q`GJpDy_4IkM$X%N29ZFv=nx~) zEX!t*AKYnC7;!8>qe5Z8r-C`jeaQpFQ;rf3JgYjbh>k~wo;(nb!hn1dmM- zd5LYO?7jO@@3&fZ;9~A+}U6e+s21LR#KcPU4iZD4znTAU+kdSTX}VV zX}ZqcsQZwZPSYns+j{|-)Vp?CmD@(0=BGe!DqB<rbSvm$%nx zEb1+tPwC?QiL)+I=up~)3O3ztEEknWisNl|S&Mg3AT3WTy45&jakUuSYv-?su9v@Vm&u*%Af>Q~4p*w7AH(jg3Igu%g!o%TrTdzV&K`D@_ zRE01I^D{v8*Oap72D8D#39-a--Yuq@N&8vOCoF+}3w{6q0c<(`8|rHuKsN9v~uQ zrBcx0I8#qaExyalljQJnB2u6K07!m%&g%-F7k2t~yd}+BRhx>Fx3)d$AdY_fR=4hU zZD~~yl6$U25`d>)`M)jFe9pX&8qDLv^^rA~dA)~SmsIScHaCc%s*%=oL|A;4rTbnj zsk?_@S^Gv_i1pdDyOH+n8Ijw0F3Yhu8*kBAU`Ao262lE$bUKW0E+JkDbC(hg4)#@T z3_YT}<8CcMxbte)TJD{$irPSOL@K-1eR8uE##`>ER%@_r)QkhkYDgW_0jvAD)ZGU5 z>I-qN>LnJS;%QUw8U+#!S}Stds@v2k_N_vI@4BrglH*-_cUDhs!Mci@@{+AwWjg8G zyH=mF87E;{F;1tL(qhw%9<@P8Q8D$=fAb zw&~juY^x^Mf}6Rw=fHKkL;JU5#+Kb8GScZ(=BCsm&6rb+#_D4NH|lj8RivX}3XBGEA8= zxRj7QGBxVBEaU$G)@k2Y6r!F-ipM)wnV-bQWVr6_VySoh_lI<)% z(x+9r1&RLvD42RGN5zxhCDIlLP2=mq( zZYP7Zm@6tvid1&f$pkClRCWR|0q>3{_4C$8_B(RznuoGKshy;%JhWHso&B?K`#uwr z!D+a61ueRDeH7#@B?6B0Bz;RH$R6@E!V=6G_}`mrN3TZ%DDZBtEwFt4k7;lcQi_rSt)e|CCKkLG95-M zp&;k9>SQnAHSBxRF5$Ji9WM0$0J$x`AO6|x2H#g-e5fB5T)SG9XDwJgmG7yMk?27O zzPw=eB2!Y0-w>$e$A;p5ETI81QN_YOMbO%F^H3V~vGyikt!_uNBc)oWiqU?DVy@AW z8Yw&;wkmUJg$`rzxDe7ZJu|F2Yx{fpWj~^smwhjITb00p^b0G9?vanL`JH`h}#PRDhpWzB{*e7l0YRc0RX!;r5*F zOjSv7NU?UWZEeWyl_(}FOQXrT-@;To7e3hT0MB8b`qm-~#z8A2smIjgnLoTrij;HZ z>#W~LQmQiHPcma6QXQq$+zg1JXjGHp zp>4FR9AZPH9p|KMyj|UuO{cOqBXI2cp4ic9GbheM;#ya-+J|_?p~8WQ5vtC>mX8)< zORYB2oJWRySA09z>ffts2H{tCYVe{@l_FC+RkT|HVNxIDSyh8#P^k2p)g71-;;or9 z=|Vi!ta43I5oWOZTju?R&N7# zcdCr_I-^{NO_Ke7l@>%Ad7Dg$_8L_}hKTiM+f;=$4}>_0!ktoGTZ_jIN&{6s&FaT( z-?ha)@ut$BxK$CjwThI9E~cqgnHf?^oYLE-mQf)bk{eM_1mKg5;~Mv+_jTPh7v)Yf zVmjj7amHe%LR)LcSa3xOOGG9cC@r#-b^xayLpqRD&0?iBQPUYkO|;uZwYJc8ILTAv z3d-8;f~wP~pU3P=Cd{+zt7%<5taJBBo9e}XY$SlfR z-9qeanUU?<9W9XrL8u_lsZO0X1-8X%FaH2~E-5WYh|*`ti5b+!r!*9y;w4TgC+>=? z{k6U^u1N{H#_824Chu}0pNS%%@vB_0X;f(x#Z<2NQhWC){VFvk+S~^sDnWXn%vR|t zLY{H=kR!tPWT|lyF_76$93%_^uRi+G*6=nK+@=govAN&k?2i38{1>^vyHv)eoVu?7 zmC)E~*0^-*qRuYnZ>1zt?wa%s^i4jMKCK}OeibgY0;M*V)Y(o`sljn+>O?9-b88iu zYJnK7r&I7DODp0k&$9z_=sTmoyU)7Qeev~J8%avr4ZUN5EK;r7gB7=Y6nMibAvX0{ z*W?epennO1lzuGhUkh^9yKcL#(X^^_Wj_Laa@VDRgssNmM6Sz*%P*8M8@QjM}ll`y}H`|t0`W_U8rw+{iVGo+H)eJRU(~#o8G3< z+e?jjR$NK-h8HEi{F?XJaIi3YxI204)$v$L5r6_f001x&FaQ9041boq?0;ovZK2$K zd|ub=$gWLqZ?YN&2L+= zTQ^?V??fAVB>w=r@sn=fw8@Otpe;mY$m^+5=&m-9NI_GifynD`B0w1=0rMvV_?>HC z`&5?H+UK&a>ZrtNFSTs$=GRsxsB==ge0lu`?YDsQn$QVS?i3RWNZgCEHMZQBAk%MC)BK|)u|#Y&n>k{(b_8;+M* z1gH{toa571Hq|}_g>0(Ix1`6BI(Oe))wV!W)8Bgv`!R_fl$fl55)KA%dkag1=e8FYK&B#rl7d66U}U6B!S;onby}=l|H&Up4<+l z=UI`gI%UMgB9lY4Vfb!4Mz-h>T7gZ4CTlnMVQ5Q8F0IHo;l_!-w*-}*7uOdvah>+SsTy>}s8g)eJK;(y zDNezD&0VpL(+{)u>FSE`jN5yey^yNgyIq|pn5c-5oRvWJw8hm>1_ugyqQWZ zINHNxJj-cN%Y1^8qI`-716P)UZdDadnMr1-)+9w`eTtk9HXCsWJ^t^2%3K9U&mMnG zQ)+}4Xf+7Y`&IYF4mi8kGzE;-IK)D(nFm zB_lom01Aph&p!FU{yO_Cq-Q>v`TBmk`=x^IDxD!++QjCUFOeEypIb~y?Fk5GFNp4dH(J0GsOyft`$q;d%E=WskE z_rY;WAP(5|*Td5w^CRD(_VdJ+m7c@Pf{uK(bHI|>hRUotG!8aZD`vM=@z^cPwKr>T zXHJ21S=C`#Z7rpT+N(#5>R(+o=9Kb$L^{eHM-n@g4_$A~wUGaMB-&z?o&=(Bi`TRx_+f2~=vNTG6Mp-qoHR-Q|vn*=?M>03@V zt_n!XRye4TQhWJ#R{rgy*5r&`oo zcqOP8Y1$3nZEYn@qS702z~FTSL%Y13P(8b2&sRlXLgvtF&BIb#kop*DhZM4e zCAAjYQq;VBISa|gdmx`q`vtF3E0<*YgvSv`ip+X+R~S85Jt5vGhT0K36t)_(T#2ahL2V^T98wCfHGTa+ z`zd=e!6H>TKl`Nw)M6zdwSl3aYt%JGDY0QJ(SL%$6B9hrAl@o zhKUX(g-H&mB+@>Ctmii$t8E*mGv6D}r(N}lO=kYG(@B#iZ5Bfk=rXDGYFtXy zG1#)1aY96AsdHkugMi>J7M(+Hw(CfSY<=(s>;cbp4_tcs>Wy(Xx-VkRoA&~Pxtk%i z7nQv|iS&y7hiXfUCO0J^$CCl3q$x^LK}($5Xe}xMNh(huISkkBY6ts1-qg!3X3)mz z$9XOXX!V*U)kd~#m;KgdRzsDWhEq_XP(?nP!_TFu(^7)djkLB<RA91 zR72T5L${}%JoQ-?`)c3^B2|@-yI4s|LCGsA;yV$Hk)KUl?(DCPM%&}alrZ-&gq19E zQ6TmQ0|WVLIe+7K!|oK3hB?-8vWGgT^?0)Aua=V*s} zoF6cQ=nlM%`jxU=*}kE-=V_`XG3D*%?_c(}g1#tFk4?Dew+%yz%2e8-mQ<1sFyO)0 ztium3L&2ltDGFK0OD}+gulu^5anjIBX>Bj^8Bobc#&B`v&F%2C=k5OhwRfucrZbe7 zcP-U#-SqU5l%h*FJrWy1w)k?p% zHLcO3l_@49O7*9F?hQs-ROX>tV}IopoK^E%e2@J_EHFmiET)ownnT66q0N9_C^Jz}T?Ze8%d)uRXzjsUqgOVcb!z>SC@)D1kAE zk4Ak|`|>T>Hn|EZ4ET>Y-9n`uw343O`R9U4g>UKOs50`I+B%(R*D1FR2JB6jb=CX@ zNVVz|OD6u4M{P=RSr0i_sY6#R0pc_Yh$L$qyU}z%Z$qTfTVc5mnT=FE&D5nWv?D&h zc5z871Rn`$D9FYRbE>tsG$=J~tfEedHK>=fbla-wgB`ZScNYeXxN~^6@)S>q;v!FI zqzn-5GlFr>CBWcz7f(}JA9!YcfYWU(cD?!Py9nZ$J*u*Xl0zAUUpBY7I_skCZ+_)p zim6#wQx`P%r(Zi$KyJM$r-}rYMJ}6d&ZpE;nD|;lHsw79B!W@Iq@Re1A*%H%h~snk zPN+$8k4jXBDitYiu++M3DcXF05En{ZaRFd3Mnh@!NY12wpehx+E!#qaAQVTZ!jgua zDN@>!gvX}ILqTUB3S>DWwmW2e`&+Ed!mm|9g7ShPIHs23qo?8wr?Svbr+<(qUe6A| zi|M0&R<*X*L9ipJ>9X+Hrxr;`Q0V8Zl(zdc^#kOt!r!ydq$$*dl3Gf_RJ8UbDNr5A)$DZdRkHT4d$#W4 z8-GXMoxHd1x*f}MM5^15PK^6>bv)~l-Gt+SO{A&$0S>UG60_mBKL!r|Dkj9nG&aG! z>@W6Q`xnLrARhScKpVJ{b+?_qiriVC-Il)5*F?F7kcl0|SpD(9u znRQdK^eyY(d$#ZC(%-vmJ*KWzC08NPHv&9p0^65XQsz&kTXAAYbA__p$6OIm;!>m| z00HHx65Hsml}~M{H z+0UTNjDVu42vR&k3cIBVKO?U|{{UcIx_n-pZtFIS9dRi%D!nbbdKRLh)JZVkPyr=G zA$-FA5rmA4YY!)LQQoxNoi+2am^r2gLfr+!ug^;rpXSa|57k5XD3A2l-ndy%C{Jt> z3bE;eay$I+M!B`JVJ>S)+^iBUp-nW?S0ZVqnj&eYnj&eYn#e@cO*BN)O*BN;S@qzh z82X&|9~U4yeq;ITv#y+^XA948p2OrpARPYy{!jk^2T)ZKDdr<^(yGu4nh#LCslBh% zs&?gdr_}VSfJlLP3D#`Ap|u6Q)sIn+ukRH8^X_A$m0*t&^s6W&b~(T} z`ti?iEm#bO(5GE{I8(d^3Y{rR02yqgIs&u#56fD7Da6qS6RVtW@(Vhs-ax~%N9>}^ z?tP

~cHDGSbo&@y(I$a^9}0~z?!sv73FcqV zaM8D+cc^9Vn(W)whvH?;%CPcNAQ*)cOYm(?JZ8p4E&j7sFt&;}ZswFJkMIIqvQF!Zg zusbJDER32UcXS18U!%=S6uEv+&L5h?sE>8W`t8!VWzTqcyO%hSOO+t~r6);}*(bQY zUvRj5X24@S2xd-QL0(jBEoEr0!8*il1HVa6k;*1xuwE;V%Re=N4!JSp&FGbSVCBCg zAf2?wxtfqGy|1>o)Vcx=bctbo>?fpp{U1pBT>&e1RD#hYS$+wm2$)#}(|OD#Z;^pC z{pg)K`zv<@df#a0qHtA?#{|D8E(ye=>rTJ`%vrNol>PvV><-vCne=|h>EeTH%3$s8 zIC@~%2FVPEEGDb51id!>1v>erJSM@AAB`Wu%>P>LoUEiuAB<=7 zeJyy5rSNQ)6U+ybtuEsV^l7!F>TG`ME94h=4$VKX4Yd@>W49vWX+z90xHt6i;8qB} z^NlY;hFHqssqcP6z;Kcv@1)G`D|2RNlZNsM8*3zAt+6C2G{8_Sf%|dsmzx0WxK>ig3&DpZFUgehb`HX z^r@`+99!1>p&omx@-#T9j^Z)80%jY*%#@m=*0!Ij@y0bF3Y2*&3yrgx_EAiUded4BWYpB{NSb^mWZ-G+;Q+pog`EKx`3umgar#DYy(w>h%`TGB& z!K5#sJfIF77mfw4%_k*C8Vuuz7hzpHKWPp+#9vK$6E6SLC6-)upyzI$N*`P>RD3Y2 z5zQ%^!;dCaz@!jN@9x~ZOrHgGtgaf{kaL4^cD0~C6+Ga(@N%Ek!kF3maDP@mIuxIY z%qM8@ug;0{i1^~@O}Nst7hkJAi?*7}LSjcJnr40#?Or?{HNKh8W4eV8K?cFZjM5NU zhRvt<{ZwTwX=SlX)DuxfTqxoyw_HfwEGJFau&*2a3QIwp(M(268$X&4)DdWS9EE@F zOGdtP3O^YJm?Ha(Kn)G8A<6|6jA&*iw%|(+=>Mt-?xsPA~~m4f0%VJ!zM1s%-xI^QiIX z9H#Q!G!&ZI$79k0rozhulVPr_9qcn&3hOR5K_@GNKN{Xd7d{-sH7ED-nXdBzXCQ}8)0#eG`5}phgRFL7rV|&h7k`G@X^X%FiAWHl~D^}+$I52t;=IR5zM>F ztuEfnCeScSm0fEvh$*g`#wf|`q&SSq={j)heF&GMi=a{N8F1P`4ij-)2IqT}qIj)n zyvoBJ?hGO}liCSV$)IZV=n( z^+DL-1_&l@@gW09w=faFINbXM-d=V51}e047K*n#gyTG9uvFq$9Jy{H?!6_2kMExoWE) zQK8FJ*{4=1bd=jnM(tn-!?j~`LS=iRP`S`9%O@>qe61t?52Uz4be-%%Y34i=iMLkB z;L)C=@q_?Jd?%?M77W}5JN9noF>lp)j0M5OpBFiglB8212UOXLhFTQlS;o*+Sc=@nyjB#N0$$zh9{zrdA-a%L;w13~S4&F1M? z;+;ZvotCGHn7vcxq2mc#L8oRUep5aKw|`Q>=dEi|P5wBE6!~*g=SSnfVYc_V7}l(( zaw=6>t?UK#AB*42=?~8tE-obcY8Ti)XoB|Tia78q2@N8$guYR&(5TZ(6szwfZplX_ z2cwoim)H%zA4@9mqzzTxXTIdmoCY2v7BHA##KW|y+v9Yoxz=jz_EH6r-2Obq>R|~Z z{e>Kxj*(uqK|%#8qq~py8cHQw#F^ySD{`@9|JW+BrLu~!!gL1C*!2-w*XrVp-Sv`{ zih=;9Ou%>&j6tvo_2B1Hm!yqqY|A)16ncN6B>7q~<9Caw?%!1bXE(K7PZ@u|LYl^j zILYls1*CSqhtzk7eIqlRecZAg?L6d{VoU5)*s--{BnhDy$j59jUMQ=<#{(d?hB%pcfO6}w;%!7$s zkP0e3SHUl_9ypA&DJkI*%<<04Q0{aPE=Vb|`ZttVa8!n6>-J*R-;q%GU?i@3R4ZvI zYviAeo-mqK1hadg9@XI)C0g06#_lj3LFXlt=!5Wom~n24Ku2pYc&Gn@?|+qefq(SH zP6%|0gbf*^VW;syNyohlk^`wXkytGXmwxht*0VHjf4@bdcQsqgOs;_RzZ)@>eCFp@v#(h zV#@#&DHDzll7nO(_~L3E2l2xV$7l}IC}4IHOwfas)TQMOqJNFm+1>dGNcq74Nn_#} z`h9*1;;dOXBhAe{O87#n0+0DyI1ISnsGsYU;mwR#bo68by`wc8D+UsPlqgBtN(c}B_q$REbs@f28{6ZfdLgTx4KCbRYzW z93#PWrQoBXj2mo8v@4mkvJSK{$C{CKTpP zz#L|mGLN}WFmH7?Q)$YZ#9`M|*-fv*(Vx^fvHLAE$dtMYNj+lz7{x{IMP&$>E%(WB zO8Nna9HOARr;2{xuM7p|A=u%0F}kyS3vrA$fFor`_-E6v!ebs1%$U@J)KcYLVktXS zHq%gqyp|kh`bYZ%=bvVC>>C*Cmhe?|&i*4zstW>}e*>3O82R-$s!duTZaW^1a;L4q zekw#8^?NIJA2I@$j@`kJW|)9^NiZe0QPfwN2yws}6;@~YLy2sH7HVQBs31lA+Mafj zhgS?)nku}@2!}bK*bL|B61cJ39X7GPF!Qh)^u}z!539$5S#U6JCEcxoe&czJtuSe2 z1mh;BL6DJ$1u4Xuc#vR+zkd^9 z()g3Ga%dK8Oy7@{Kb9k7#vNzwctfnJ8~I7gRp2M>8#kJ8S<$67Z?Vx)W%fXDktAXL zGN^dx1-nXAu={d(TtVVoxzTW@+8l;Edvd`vpE^h5D+2~%gVT4QU49=Pxke5aUv$Uz z_GjT|#C;yKPM*iq5{yRCDbd zQxf-YQ(_0JMj~@}J8-jdh1Ic2n9ILO{ZtB^;PSS+@al9ZBiG(U169A#2H$R#$5sg% z%UNN0HqqIRFuEh7c*!iDE33F?Z?3-FtGWi^ED~@bSua zxLnW!NlzQ$>-lWRbh-?^1*Ir<`30uGErO}~Zit?Al6;Syn8*AhJR2Q?v6pqAX0}Wg zUEi+AMsM8>wtI%dml0x=ev!PDiF*>K8sf@!g%e42klc81x47ID-qf6Uc%CSNfcKju zd!pY+ ztR758Lo`s$h;nR}NPsSA)&L zui(2#3R@iQgmSw*&>o{k%*~@AiHHo55<;fb z=X38hR)&m45zT1QNE-N`d++c0{#)x=&v!j*J?r&7_nyzW`|SPR@6Cm)*2rXwg5ja% zPqhBB8s@9GPWi<8i&WU{?Q+3u%wt%3nDk2-cEg1c$H8(XakWgg=4?JlxbBVS+>FV_ zT+54PK$HstW|xR@Bp98pgVdI`x77LzD%{ne=S-ee5QKbXQ6MQWYOMYX3CGUCKA(F+ zkB8R4GvFN~hZD$v=N;?rLs9))JgroR+c{02E4%)WwK>?#?w2+qpFB#y+!HYq31(*h zk<`bKUi6R+DqKu$e|F&>HlW9Y$SRXDv-I&4w@ zg%FT<1D)(3siDPf@OsiXnEY`Jyg#D{^V$Byc0x|*!YiG^fm>++E<4sHJ729J4L8cl z{`UNJws(B0>{gS9u$s3bWC0Ofh%Jx8Q%_}}=`l@cHZc*d*Ud$7$$5;TgP0o15kU4Sz8d6*sOTndfSh+3(sYZqW7s>puIyLE4hvOAP@xs1URX92W2*%UflKQQF zkXH0i=8SBe;Loee$hye|@eRy+d9^VAoCJE_cZ0^a{UP-i1wjs7;7O#VHg4n5#O?rW zK^?|*ktYOPyy0#9sx}fey*Mqb=8e37i6WQ~|07hD(J}gur7~A@e<(bxGDT&Xi%`&= zPI%~B0}2fX!7D2P+#ZL+_T+eQQtJf1t#q{yvE#Vuhoc(q!nUfbFjmnN_x+%X!9pH> z6nReu6E8q9qZbJyJy1pCLzm_zO@+U&LBR- z#FwLcoE-LFPZJ4GDE7T=iVfyl;O7IZaou23yt_FHbp^)@m?8h7oXFHgDZy->9F}#_ zESgT}RO0^H%wc<;vtVm*9L0Nd@$)_T(a4E`Dng>`>4b8)i^w&X_@~)Umy<2*Ghm7lk)4BjJEyf`HlhTfh_(%=HO|)Y{O6^y)>* zoOj_yXbH4prXN1bls9w;V-GrOsbGtP>0nS> z4U!qeSo4(=KD4qEvPZ5K;(rcSzX)Y6Z93VcGoLdx(NbnX39&J< zZG|W@dtm4kHNkXF!ItRMdUS!;pFeO<;SoLCz!(bZS3oeaH#oe|9_O!_i33-u!7Ssa zj2!tpAz~T`rt57Sb^O9OdH}1;>F?c+qQb_qyZ12+uen{&(gu8cT+0M?LE6iY6i@H! z0$!;6g+9fmESbQryX6Vqx3q9!nF_Wc!R`7_ZfxqbT$ac5XcJb`PB2yP;;7bK6MBz| z3K!b(l+7IWhp}+_#O&Jg4|wZIvlZ<^49y$R@^jev!zRe90q!d3aQ${Su!XjhVW)=$ zPRn})Q;998&CYuEca#ywV^)Y5g~=p4XdO#wzxYLAHx+JE&wh@nbLX>bsV0UOTzV+~ z0I&9TSbbRoClraz7o#sX2sxXtYaKX~qh?%=V;kC|HWn}0mk67-O~qB`jk&^8b^>PM zFJU!331;cVAnKsp1IjQ;g?rdBgL$-Q0UNvUfZ#;__RU);KT8ZVk~J{znesNa88q|@ zq50uGxa#A;l$*=}C&=j0qbt6&-2b8x|MbRakKw}pTy7FVNBFs|iR)bWSwsMH%O z+&`V^?E8lNsP)x?HqtFK)!65MTq> z-9LJ?^MXj3$y$k!v)LhH90+D>0V}!KIU)P` z9~EvzOAl0)HIqRL&d~#>KSGt)^n^V0(SxKDl87wy*%o4>Zw+|kZIoxE25KjcBE`~3 zy2ruY_)Pj2Wcncp|G1KhZtfSYjvK^N01?czk?Pcs7q!_dKdEq4inEdarVeJ@?s16A zxQNu={zYD&z6-12?>BsJ)c3?80_N5Obr_j?81;2fW4ga@!x?)skfVAOR_0EjXQPya zQ{Z~Lu+t_JOh&df^;~I;H0PQMcd}**`%C>L^KiW_in(+{!0_q^-fl{Lh7xIkYX$!l z8#s55+-X#M!Y<=z^t{hOq@ogl`xW1k9y}6(pB9`zHEGHMX3ZY~<3TV_6y{P}n^#LU zx2bSX11w}6bOy7hD-WgKc`b;OcmvwqGLn8cE@IS5$H0xjok+(~8~pFx!{;Vxg3^&- ztaW}BqkiiDM>_n^(?Y~7BACjzBPr_#r=-KJRk-|D=CXLJ9LB%4H>nQFfkWnC;O7+b zTi|~fzBg)Jk)4pU+2ec)hrTp|>0W{OX@ZK(hhzy&S|k3;+2l0|t64=b4&idt&rO%5 zyGYcTFvpuYV|=OU5S&znfWocjGGqzQQHf zX>j}n$qqi)B(*dM#feAXkpJHZ%&$hJS-@-}7#}Q0RZYDsU9nD?t7li=kGK{_<18C^ zxHSb5UfmStM%g_gU98^XLu(#dJz*sFy4DwB#h-VDa=&j zzQ;{r>@J^_^(t5iykSOyZZiZ;ED=uVW4TJ0w*pK5N_ub>RKWeGJ>XHF78HGII862k z#9O`2(lau4VfW#-IC8j?@X+Rqm_r03XEiXhbLAcBm0U%x!)zft(|QDSUULIaXEiJs z(9S6qwtyhDBAABzZGxk+?3@WU+)kQk-`;|K+oSNPMs?)+-3#Y9Zh-9A^}=eViI@`v zQ`t96>L>}9zH(LM21n$xF&}M!8L$YZ84+t%(&l4-^aJooNIrSbuZGvz@H4%l`_99^ zjt#-C_Y2^X)ghdj%hHW*^Y9UqWY}&IEMQ`P3R@tFV5-j+NWUF1k;<_OoGi|jO>Xso z+994`6RIpUEm=JlG3R#^e<6aYnfwd*5lE>fOYw4D8+;)n3HrVX!zX@IC@MmoHi~IFc<3t%w2*xbn%dMLda{! zIk)9G7q3WIsG$KL`woVaMI|EK8AGpSy{a0Ju1P*J)vq(U-wt~@t-%2cq}8G+uB!aOg4 z;d?xGDU<=2$6ZjLFZ(!y-R@PaN;X%%?NMGm(_%J_EcGJQX-LL8e$;bbKxu>?U z(+-Ib?HR!&Z;Q{G+QW>JsLONG%2Dv}(g(D71BYfhh+Dvrt$s7^h#gAI5i5Zc~3AOz(L|ZVIj4(K#sF| zdKY;;eu+Nc4Mv-v5le95sO&+;SMwHn3QJqb`PKx5?}?M5kvz`a_!$N$t7G4U8rF8J z5qBb4nQM%$W`mDpL%=&d0kcs&Y`zdo)b5p%Nmox$5gBsay{?(`pn4TJaAlp4<#42l zaWnbdEPX)U(?+7^B8sm5ejP&T`)K2H81vZ(|J_CMG*f8K=Bg#P5Dlrf+ ztHp5eJHbShESJ3Q`ItgMa$Hg6P1(d34amdzG1^(7f;|d4q1ogqG&_-T2ldZ{VZv4y zJ78LjA`b2S6r4zZw6d=?x7mu~CjGYLlB!HO52XmmUTGp=eu$W6f?4V=8#f@anj(Tv zPHQ^x?%rO7I=(*_R6~3+#Y-a{YfRd_dD1hYaTB)iv4C3>-j9H)G!l5u)@9_7X#7Yxt&;q}Ge zL%_}FAgsKz8Qy*hfQOs@z-CawCT|}>-?Ei>(7q4sU++A2d`2Ss$2^I>Su_~TSMxL9Qjx2M<( zjhH;B#Iavg3(b`mG0l7PY<5) zkIh=s$x!iObnCec^yi8KuG!cESiuPRxlx&`UZc!5RY5rRRYHukn$N*t(nfl9TncJv z>OvM}HRybwEHuA76=}vy5-< z45b#}9bovJP40s<e;zpYZxLK4&A{Xex}SayX?W$a%gVC3yi;C3Ijc$AEG8PG~-JP|ypMoRY`Mqs*DQH@oqZYh)rug$3TA zX@{i^&G2woAV?=45ms|WJkzEU3_VzrGMuMK7jNihorC4j-H1WVQ&ogY_K4ZRhhy)6 zo5php+J6_U=tsa`qj+V?=Ar9oXX_BWca$S|A5n#XnnUn*?R#Wrz5o^{`3aaj5i^%y za{l;8G!J!A^X7H4?-C}mb*J_)IkyyPUZ2Ll8-7&f=tIq5zq=B6X)li%MT8Zt@u6rK ziookS5JW#oLq8u*1?Aif>dxtL;21nlz;ub2Wdx(6rJMa`y#l>>dN+H96nd6&1=5G@ zeT9d{Z)mfo3NU{qkDuidIge`@+|{jzZOas}-Rn#AFfy8o(J{bB9@*m9)eCXeFdIB_ zaWL$Zh6@ zm>DnjCVXQ{z|y4V%_Gg+U6 za@om!Qy6|Vf*~L&o*dGEWf?#YX%#dX6OQL4a?`9QzxV}{ISXGL6Y^Bb~=>$puR`DfRkLKhxCE<~5KYKIN7VNVbA z#(p;WaIneYSe znlqJI9!|y^9B2o>?mAf8LWXVR5eZ2bnY~7|>ZW0G`0(1#^q^oTK)$Ka(02$fx@n4k zp6r497llE;Vbg@1P2x8JbBSQunhhws(xp_vsK4y;eNvSBR-MW7&0?GtRIuNq4#5y` zRFg8!V15CABj8m-ZNw9DO~7gPU7aZ#J1!Wmp0vYZJv8xRJw1H6;SAGrYbMJ-wC&=% zxj`^St1YOcrH0g=jK8cd={iXnCeK=Ezhd}`$FuprVHasHeRYSpTM>&1zJ$kP_;7F^ zX>SN^`N{@5V3@iG@T~zv?KR2}x37@0g<1VL9z@6OeS2l3Ot$Z%Iu}A?kyGIhLR* zc&RpflkAg>bVXD>g?G*pE;`SOb356BUM=#%QT0i1YrGYvXB%?XdqxTvSMleWPcS{# z>QJ^zA7q!P$#ENBuVLh0_G63c)-plfcVU6veJF2gfX=KAd6|xY86mFbBf-?9-IFL!9w)7}mg970`pFXa z4Pj^A-p`or3ju|^SfOL3Oioourtnr^j)#tbl8GlMP!Cxb%eU+rty#7@jv_F)VMNk9*FFlMTy>k&qoAH%~mF z>j=hj;y}vc-gRmIYB?^#>Lyw_y^0BL8Y1I!HW$-PgsCKXr&aLgM3Px2m_~OqI58m( z1;m-7YsaEw#}|*Fbt)t9dw*LfS?P_R+FV8NyE_n%2^3fJi(s-7r&8{nucd#M$Z@x+ zaMXYvFsEzABY&$n6k@0%sD^k9pG@H$$8NNlz=(G{&}MZF$TT>N7S*t_v@el(?aZG@ zvC$7t9(M{2-6`g5mWp>zIXB`yx?l;F`Q*2BF_Po%#^fN6B6T)vVGvRaK8_~ps(}~r zO5-tSJ4lIjWG7gj8VqWh(P-R5O|VP}M~YdqW%17=a7sWD3VXC08ydwRtS0Jg_K6q` zf+@20rOHC|WNun=+_I&5%nGN^Oj_^}G|=Owkm%yQALfOt2!(upLti{&2g?esAj=#b za7zqA6?Lx2sXYqc>r0cduz~-DAN)gGC1QFL%+%sVly;7pEdI{D|CI4&kM#Q_-j6{`ksF zan2`?ai|f_wEhI+;0x4xh0(Gj^8Z-+VDP*)^c2EUF0w9=j)Y)IqW>fBkUPCj=T!DU7tc{jS;*LC_@In zLh;prVzm9)K74b>XxLuL0KXbf@#wTCn2>4nsE~fHvgdK#?5Yt)wDZG!CckSsI2Gi< zF0KHaPJR$d5oJSE$UuiqK?%u^5uKjWhCay2Gx@a<=>E(Ie2U3MnuoXHN|zq6G-a`X zIU+tZieT22@1xYFxXb9hU97*!Srjnfw>0 z=#^M`z$=)oA?j>`M2tJZjE!y0nm|rwHNOt_J<4a@oJJ7KFLy8{c^bY?npX|+Wg?+( zjbQk0A`Q}$Gf;gf$#C?<{!5Zz&WIy;PG@gWA29>hm)(Q4x>>?QdnImx1qAc(q?eTa zsw11>{)e^nJjk9Ky9Aoj=Yw;ZDmIak-1D8c@QP!!gY*Lu+_Iq;o+Uj9 zjdTp|{AdUj>t^6!lG3xh{Yk*cM9fNpF&-T$MH|Yb0l1yjE4feaS04+}bKD`ck1GB% zg!Ha=77Fj?O}ZQ|e@MQdLBD|aw#zdd1`#V&@$^N1t zpn8COW@THy!)s||4+jA=1d;3)?d;oXrLNa z)j|G6;^*z~93tdz(V7z$I8+bHbQIxytSWvmPXY5LKzttBwxA2r$92HIiS0t#?%j!xV6J=xU{ny89Dac= z`MyNfDmHM{UJDO7Vk=-`#D^9{FdyPoDL)SjX{-7#w)(~xSnd22y_J89mM>AmriJ8U z*hTzo8a42tln&tKqx^-PcT3pqaSkeKQ{lYrTc)zupOwG@wmWekJIh4_lhmky*)Q(2 z0|YbiV+eI>(5dXn$J*EpgKa<|(H=~~j-tJv)Uf$a1(L9@0Nz56uSW6H6|`P;2x&XL zDG6jSY7x;Cyk*l{)wuf9CblBHgdH4Q0{ef9d4U`;vN=vLb0QO|FQxM(cP6&6)0c;$ z&G}0}%WE~FNg_+rk8A=(XC84t<*4qoYXf(ekXbq8?TVX)6e38y=oaMPBL;-)S( z59eJco1j zqC*H9d>zOYJu&BoPtxKJ4A$a~epm@td}#sGOAMfH6U_3))ztWQ*}#36 z3&y$Dg2;k@XneEZF`||3zkMT4X|`aPf^D+9{n4_~^k?+H4M|Z1$lC%$$C@ z@cP^>#9M*!AA-z1Jt5?64^WfbK$}XN(T3NZpt(p1JH0;$1D}NBqRAQPL3tC3PpCq_ zA>PRhc8!k`FgoJ*MvGwd)}N-nE{LORjT>3pTO-(Ehx#Eow>+AcB{VC3 zC)%1kIJ2!35_F1zpRU07NsoI$E{vNQV@WC<_Y_F#E;tjTylN?bWAJ*TvIE|NUgW zGaDHFog9N!M+s*1yGp7c=u8{*+e!l4bDtp1v0TtY2S+L47p?jb5gCq+H&wya!SXog z^GG~N-2z{aQwFX7+i7`XUSJr(+=z;k=rd8oPWLD4`mUT!phDT6`c^Wp0py;kT`kZYO^Zup{IpWNqHknkX%k#lA=M9}v)N!@1!j+% zg+$k|O{dXmMSt9ws)gR^+1j(9db82dkQ1V3M~3-4>0fWZW_f8OA6&+jaw&lxtd zewKc+vA=EE=ixh;XT7@N?P=0>Mfz`eOzgCBDDesJ2ruY@R7iN63pC}8!Nbms7fRXE_uD@Z+13U_?m@F&R_JoIV+B)5o| z(_aP5Y=W5-?npJR8%KZ0Xk>qy{{guWC)Qt?m5xKwjI;1-a~D)7IpE5IQMh479K2~(6=Vq=r2=LN!E|j1pb{@y(tAys*uP^d z9jmixhCQFi*jyr4T9SlJN^TQub9hJPgw%TBcf)6(-bYMj!~5=MJ|slI{Q_;=v`Gj1 z_}F6;&jpOa#Z#;t`QyZQ<3lhv4GvNCElt|}L=ziwG*Wg28?uKNR4~pOq%=fQs{9lz zzAJ*CCmrU{B(%!&PJOP2y4cf?WNeqK7g!z{f-mcoz;2h}xU1J~Hu#Vh$73ujh1K{G z%&Ir5so-xvsE~op>`sL-w0hH4_Kf3eL7eo=x|S&J+JSFZ&}GQ@(FpJ2#|7f@6u;r<*Q%6aGv0$0yzSS~ys zELz55J(B@k{A~vT6Cz^52xd&$NGjHEDz!+Xg)Iub#s=0cU>lZtGak<#fR};{^wL^@ zpTo{)p!h`BuX!?XbWet!Hs)NgqX~D?IvTon_~A_?!S7!^5??UZ;Z)1|3YZG<6o?@h zk5h4yxL@}rH=JA8l9laD_lha(@yp|xj7zcLTNe)s5kKM0H8nxbGo*|d1P@ODhvxNg zU|1+~*}ir`NP;YJyf>AGO2QsO8X`>kYlbPfMw0Yvyu^K6E_{#w+`% zz?s)`vHIA%vVymYGO`2YHi+Mwiv;6z)=46_{#JIGw1wS2(UfjVzRo;2e_xtAqzc{E zBU63I>!uad1a}^f%k7Z)&Q_RQ-s7A+s%k$j3*NT|jW&(IWzM~zZt)6yBafEZ$2}B& zH|-)OonW+ZvZTFRSy~m>!fpvZjod$|vs3r^3OXC!&nC9u2P9Xi;y#fILKj}|RTjXT z1BcWrL#%r|N}bb5Z}C5f9p;*#*`wFs>yDRDZR0;7HMCL0WD<-8+aXa&nI`Quv4wp+ zN)6d25dloWbu>bi$ax2E(-e_k2@W&|px*8mK5sMb|I*pR6W3bb| zol=iaYw(KtQ^;t5qHrlx6fqA8CX=}#nQ0X)onP0?W@OmIK0Jak4XZ?%J!NR{J~AJQ zShI|Lttxn?@Ykr1eaFD}#vf=H8B;OAI~w(UDnWk~!tvpQEUmmP6f5pJfnI!65io1T zujdPbiSphg30-hT`fXJ+TLl`j-!&~vN$+};yRB3h9mZ#%e%PxDJ%w3oJK)8UN#L(Y z`q@Yn!~Z9`e;vAX{4hRyEiQZ7p56G;!Q21oY<`NTKq0|+P-h*#72K5WPj6y}UC?Bn z}1iZu^_lGS=hn3j$|n0Vlh1bt8(cNo_n_N8a& zZNvEo)bMiY2F&lYwc=;3lwjmye%_zH?xA#l3yB3L-=ZH*iJQE3hhf3*v!L+# z3lx1*!2_~I%n+T25Ow4lWIxv;>7a0+3tG|fjxc;!BLk7I7rw-df-CB$g@@K9VrmEm zYR`_l)%r-Ps@2GDeN&Cx=iFe5H0ME(ZVn{%%LlWYUj$tzZ_vc2?UHQ20~7cO23Skr zn_QEue$EdxH!upp95xOwUxl-6^q2giFN-%o9%94*>`BLAn4eU~BmP}7w z59!?{j>^O_iI1V}FMj=8C(EP>2<}bmVzZRLb)#I7;%%ghtvspj(lF0>>C7TF~SE*p$tg+nr3-Fm+e#{P! z;ah(BK>==k3!wZt2fjqfa(MeeY-(u;i^Epn3$q@zY*nx20mFdv$kXTr05m%!}FbjiorDgUjr7K_5vVQ3k*g|&$IBMnwi#Ldv zG-9Kl_+A++Xp+HN1j8FObn2Z8P>BKuxjvIe{XZw-fs4`6@c;%$@-$UbVsQCtFzD&eFG)IHq zLj5Luh7s3E&UC}1G*rz=Px*Mp#-Y5`!KgRj$w15 zC(C%=VceVAV2Hjb=eaKaZYB~8b0Rcr`Qb9j`KE8|RLd=B+39_#YTF^i7rnAp{DXwK zRltj3`4O-D&y!boZ~y!ko*pOybfOy;@4wB4IJB{)Ckxo-g-=x-AnQ&TYFx|jCloa!#a)ZZc|PW;`>Czv&FH#rXU+Cu%<@r`Xu zOr}R-veV`TqV+dbgohT?_YHVewSZRcJJ4wQB4GF!+BP~9ZUha%Ml*+Tqfbb)|b9L&v7w&EgliPhmf1Fm7`Hn_fHi15&4B4!=I zoH@H7n;USSns~gLJ@M`;6P%cf>TE)h=`3YIpBAJP2i337ftO_jcnmlybV%}zG1``o zV6y2V+#^+e<^Ep8+Zc2VY=@Q6%V6RGAE?|Zfv)mtf^dw-JZVga0EbmLaHJDsU3yhklDR-u zGWwP5aJ@a0+k=2vAZDNf2*xX_D!Y%?7b?4{iVd*plEzZE>AR4O%(p5ErVRWPtdQS> zLFalS+M1&+sO@+RtsV`R-fhHdHy6r4Z3b-=5JSU~h^&-@gW#j`6ajNy#6%H{;tf6N zfs%5nJDOm2A7<_y7fwo9`s{+3bUidAg2j~eJ%rx4S*5TyKDLCB|V+Dkl$bq9ez^%R|;6rm=s z3EEN=aKdm*Up%r0&xpK)rX+QvK_7mhXuoS{@&pVxTD-95imOQ_nApnIS=$%Br^ei@ zWKD{0po!+QnT_&Zh&RmOy&vYg41xm%qhO%IPc)er&3SG93F|B6@yyI;vgf;k{ws3* zFVbmtUIocRBZbv);!evT7)`5S$wjSv%6?TP+xLb!IK`yVH#LIsOwH#hHV;FO8asd94=z&YKeen>jD4goP1UozrfbqN~h5-{Yu$rvi4&Cp{i3&H)pb2}^>`!K#ugaC~qGBrH*{QceZxpY7a6KVUK52<`U``l5=okv4J@e26t0*)s z_W?EWgb!2&dJ7Nj|5o#wVC2^sOKwferowJlusgn~uq#6MqxO}W|6zDzGk%^lx>iZr z<|_pU7(S(X)9DVXUVR7;Xm*4#&qBZ{cP8$gXO5?IOo5-vR|%M2;%bTsrd#=yW57}= z)p)vseY)oqYJ{-1>VdfCg;T9oVRJq|MeY`&l86*|J;I0GA53c+Vx-jvzng^o?*q zHDrILSx~0P{FH ztzFCuG!P7v(Sxd56Hh4)tYF7)enqP*-j~gtMAI_z{C8dp zrl4=PvjEc zS?VCHfp4L>dRWoWB+f{MQikQbtQ!ME${z4|ikTIfsK8+vc!u#3WjU`4+ zq=#L)$(Az+)Z((I%m$CX)9~}fc~JJr5T{LUW0%^E5HM54E#N>fH%D1gtNvtUJ=;{p zK7Te7`AB-O$1X}4-oCv#j+mX-{e&$_s`yJAxrC57?b)beNIO#qCL@3|kF?-^dh~)< z`Sb9Xy1TIH+z=c}TC=V49Rj+N*FEuVpPqJUQ)wk=KN%=SI%Uj2AzZq{Uq20KVbQN72LL1 zUceakIS*;3K|oowu`{N0u&%No7^4}4*VV3qrFnMvLP`-EarCRO1-e9x2f-BW_m`Lt zkCE1`t7cp34AAQpz&_i)gZVhb4JK-Ahll(HkQg-aHEBME9u~PxFf(~OYbN_{*i0rn zc_d8Q5`pDr&w#p~F1Y+cwJi2Qn2hWIx#8krvxs2k>OPe;-M%Yzzg^9GyIey3US486 zWlb_ZXLGU0UQnj+nOolKn8)x|$79LZL{$Yj^k`Y7Z1leasPbPJQ9ZcA>vxNBdb6HP z&Nq+dF|3GLMKEe#45@c}K1!={tJ&i0YpADV4uhsVrFfmq#TIR_@~RLng?u5O$As9J zfP35$v}|NgD0&=?X3dwA9jlJSzitkPgez-tz?D;|CmGPqV_e1i%_f3L9W;qrwX#iW zcCMOr-0MZJe)Wl|*0)2ABg4?vA~h&~Tn=y4RB+W<5i_u60C0nsp-LTXcoQ0m66i-<6NQE{g5gs` ze4^`rk&ODD*Qnbl20!Oef5qxt#=6wnA#C`{+h&{7Dn4i7#{v$tOHrw;7lE zxZ@qI$(YByEE0YHu$~f6>%PKa(elugQ)+L+PCmYQU@&|?c$AQ<`co+YF zjNbk`z>JTD^v2;h>-cHtHqwSwiqZJ%S4DV^{ITi102sMiMZk26m?VO!8Dvb&3ZY~d z!zx+F&~SQ>ss;18k2Wae-v$rOCr}<=C}4P3D_&$#eYFg}?9KtrjRE9KT1$DSHlpS| z(KvqTSM)P+Bi_Usfb-2+!n^q@Vy+U*<)UHK=g%%OhqD!IY3331;BkwrWU&)uDV2fm znjf&B`-5Q9#$y(o?1I>F#Ls43A^bIHqRj`MWQMN3Ct12a1Q)Ly53~F3!EK>Lg5T8{T0gm=Rc%oX#+lKK0G$y6Vev2?&4 zwzFS5+R?27e2)h&fZ;8T9z-h%sUiO8oPMAMRL+z_H*tU|+}{XmSDu2N*+=n(pVQ#X z`I$H%styi~5T|2D6$+SV1T$r=ne^}zZCP?&Dccd5!M1+h2JJJ(2yH&fo+Mm1d9KcVHgR6$ciQ>)0_Huz zH2NHnI#`uR>vO-dnJIl3@9{3MV~z)?lTEy4HxZJrEr3B=No{RaHw;W_GOFo!JDg6w-;a7p1WDp zY}k#md`7|=;{KB7O#DS3Mbfv%k9gg5dIWwL^$liv97Gq+?#AcT zj>APaZ=5sX7hFA~D`0Zo3YhN%(@nk4&M@69Wm-$v$Mqplxqri|r4FuG+ZN$w0tlikN1C zxwNyyQ9Gu;bmzPhcJllQ(1o5L`3Y5sH`V6FNlttQirBRA!?ySn+Np?CJ;;oejoyC& znS?^x)=P}#rk*IPhzPya%-GaV{jl{33jtFvzMC$Bsa|15DICemHZA$g=5SuHcK9pg zoN`U*jY`}`9C?UD@#_cDj=g{k*!n-`B*Tx*Fs4Tx%&6WE3RO95uSrR)?z9MY&ZnSLW@0!qH3isdoEIJ|&q`-pnTvlJRm7Yi*|_POnl_LPhf zD-DKTDGprDo>5%I=>A+->Ilv;d=TzaB&LRji>H7g!Hk-6pBmi9lXANLiJdr3j~+V8 z6_UpmAl`|*-xE3Pm3dvbt?knx!-Oy06MCcg5?=CWH9V#@1?qLIxpN~NxJoj(^V9$n z?wg+}?lDzESj{~#>Ksfk6DOuoIrpwp=HouGdHD%U!q5QHG8&8c4oSYD%;RMg=vBzT z_x3rMTOK7~c-4@Lh8fmCW#F*9h#HwB|V2`_M;n!s9xg7a(6vIJVf~o6@ zp~{lFslnfiS!PuLV{msBJlL}yDHkdUBlqUNoCL8UvCuoj4^BIe6)?P!=JgNuc-PHV zkW?OFFYRU7nCFX_V*i(tXD>9c&UCSL(Nw(Oj3t=aPnS`%#+lP+FBG$L7BEF%FUL}v!MoX}HGKmikZ=>J89>AcfJ(-3FgV7gH zRs3q(6Ja&(Vr1h)FlWXZP#ICK^!g>m?4@JstWCHlG01R1d<>mMhH00MDnui;j)B}8 z$`IjjOTY~6P{3*nCgN+xx>(6q6OPP_M9!=I(Vg;M&_lZ$+;!6hOqv)AOeL6iW~q|X z$*XDCiN&m&(oH5geHe`T-HTo>r+_^|>S0suD@3&qhh@-=zHhsaczqh*P?kH^3Gdyc zh10h7hRBfZ=y0A78lqtUM=r=?eM7OWv|P+X&n1|}qaRDYH3!q*T#8wvmw_nqls(Y4 zl#DNZ^Ty2qzv__B&ykQD(2icODMq|C3vYG2Rof14-}D!TpY8`+tCyqHg>%vML&nfL zpcmdaLOh|{)D&w6qOi2x)T?jq!!NmU}nytspvEi_P!b9^C!$DtyxxFWhIHJ8ILKxUIE2%$Dl#s zJS^ySg8Xwb9Cv9K9$MR2VsJv{txUO~fR)BgKw;mH!Dbsby!ai32W{vp{5%6i%szsl z&VHb(%&*a(&lj^^Yc8_iqel|e_FiE%9`nk;-Yp0GRy=~Vk57pCY`M_Adj6jZ{^Dbc zclYastvv(a!DfBH9R+lF+zL?F>WeqryemAkRPmuj5X{g=N!0GbyYv9_PpsauFKl(# zNSIB!{mi+Z=@Yw9lF6Diy`bYmLzyQ;ui^E)1olRdT0!M^NS~As zDv4wY)}%kcVJ}ftB5DrySTq24w2Iz#BSg$;g30k7Lk&G3 zqqn~P#G0}ttZa`wtG3%l#;?Xvu>|ZGZ9H0&bgs~ENZ8&a_}ToJsD>YGH^7I}df@Lx zJ0Lxz7`}|>NJH5|oH=|j-ctEacxZYe<`TjDQ&brXk=N-Y@*&8c^N3aJaA&7JEBO!e zvQrb=o3wymQ~~g&47_blL8&U9ZZ`}^JvYKRMFu#-a}dr-+y;MQ$KvV!dbqvzk$`a# z51ShV<7E0NdvMKJ`b@%S)_7_X^WcUpTii2~;S*iY{(b>(11;?5+6r?kKSBqo-SC*a zbXDxT)EFbyIO%`3@a{*awm@y*eF~PL1xR|}FJB;RHO4!5`jmYv>0dvy#9mBU{d-SOS(=FQg zVG5}Z=8|d$3DtRNFOP{Dd>LxZTi{1uRij#7`!$RSok#P|1VHIEo9uA8(lh^pl~V`2%u&U4 zM^}LRw@=_JHv~$fe?#K>O33~>6<>Qj0iRg-O~AN{@8%=HlzkpST`ONs9}fJ&Zdqgv zf&Y}*+-pyn^J{wGx3zWP9j}L<#s2}nlq#4bk;ik_b;6&+{J(+@9LRVG%R{S?Qe8bH zMt+0EpU2~!i(K%C&oTk?OnhkN1mic*gQ^_lPDeF;VMn*Tm3=UdhweOUIRKi2w9jIH=?ei6)srGAnP^9Ir% zLcX$R?+#=gowV7uy-G}(z8$>bRS zX%O+il9-!1L+VWidQ39J6;Bu;ZRan3J>_P|%b6!6WE+O5(O*-)vKQJ{khG8)tMf4~ z+ts2se)gdgw%ymqF6sY(kD=8Ekug=L6|lFH7Pc8|3O>UX@sOrP@Z!g49B@?*9={2L zQLGkzZmu9;`iTWe4T34`93h=Dx|I5x^_6u^Xl1OM4Oz8{MY0Fe^o0uh%@=*~oJ={q zZ{%OFxv7OU$@_t5ZG65u8{HwPy6M-fAXak>4!ZgtZT>w2)>!M{BA*vRGR0f06!s>V zqz%)gIO`gfOzt-q=Y-Lr$9u7h+Et}*b{Ggz=khiKEF*qty!GVxR$@WvrGz)H)4^*$ zr_sTRUqMP|p;kp(%vtD@aR?K@OsyZT-76C?C&dz8e}Z9)hfBxA?x*g{zOvRy>(T3@ z{n=uh5V|VM5cfN+ge{8u;aTydDVF4HZhqIpO}fhXq>(NjYZA#^bbL&zx-=T!JqQon zWDWVsE}&UI1UEmQAw0Aav9MxEFefZZvYmzxq~giDiMdvY2FB~NUB?fS5f#SR=Bo;x zm1Ky2A5_FcUnt?^^xjx`u`<54Ul-fycQIS76XDI#<1+iS0r>6kaWK3ALs7*@?0P*( zz+{N+arOlBFIzENyL_SKHrZ*8yXw&0p~md0bR{&-sz1KgUmb57YlL~hW%MBxd~%^a z?vtvF*=M@gcbFNQlo1Zj_dOV0FET{%^>i2*Is_*CbHp3lb_znewFxsR{WlB*K@_foX*Zp_5mnhU?0yY}N2FVU1XYJFvELKKO(lmgdD71%HA?+Oj(`jeh)e%Lx>`qTt>Ptm~}2N>Z$ zB}!QHDRJ(7Vklq=Z1r%Oa+0j{xhFWBX_EbU?0_w|nm~Zv2YTItvAFBU7>38(6TKf6 z5R7SrXLgeOS!vVGFD$2S$9O+(Xa4>_rrtEJ#_#+8uQbGWJn=Ho$FdVBqDQ2 zg%E|z^H`CDBr;S&hzyAco$FlZnCGdeM5oMi<|sq{Ywzp({(b&8y4U0JJZtZL?Y;I| zuf0}Le}?JU(UOD;j)aDW22`4m2z9gnXHAryyXtDk`OsrkC$V!}Pg4E74W#9qQ8rxY zK`s|0Fw7*WjKL(t6p!5{H0ydrxxZ(%I_aUSYSe)`mGY=BU(&ZZi8Qk!-Q66?;03xQ zKG~F1#5xfVQ+;yzxh2`wI#P9IcmjM|HCf!cycf|pb%ECMLUFAlPewE!!!SJ?*rjj= zVha3@3tLXVSMJlTRyWTa=G(@tOtt!<1zQ5~`>n|GIS!;tLlffWDkJABoyhX_dL$b& zP&&;HsK%wPf*o*5Tn7PDFESGW4)Lv7Fe1aBF15=aUn8TO;iP3d3C0{5$b5xb1iG{q}zN z6UM>Nz_a2t*+BBww}xR-e=%zk5Oe0qY9aoWow%_8F%wcaqs~gz67dp8F@B@0N&ZPY z^5vEe2|Oz!Jq?{nm%h5h8xQWb_4CSSM{}jfdz&Do>o>}A6@~WGL1M(H_N^AxpBnR3T>U&# zm6~{2*?&3xMy!d)YD+R_%^!y8ZqbZ{L}-zl2aL$UlwIPdHK$>F=PZ8O{n@1Nh@~)e zMTMyDJ&t(xmCl=GQdv+HV!RWzmCL#5qUn5%T6NxAXoS z=-iytQ8t^sNF2RRqn`RXR6aLltIF%=KCw=(88J__B1YIea9xK6X3g^*4utl_rPrtp z&1Z=1Pbgu3O)d&EmyiAzb>+-}>Gjg$Yt`D{I6*!-Mw@T7C_@z^b1XT>s- z^k+T1&m6&-9gZf&9kwt`hJ>j?%$DnoLYaG#`0B1k?S5yjJi6%;)uoFSV*WV?5`{gx z5>K0wXWS2ShdklLQ>;q2vdPBk!^MA{cJ%u#6x zyh6;W2|CIT)$7G27=&D^n4#?RcC>2kU2Ro^y93)gi*}=v8-zX95L1R%S6XX`K3bYK zQNdLVz72AxTE0XcPi{}%1a_TnbAtk-NzX*dPt%n!pAqBn+DQ4PK2==NvRb{t>z7#D zBvAFEmAOiD$ez^JTatK{F}vSTOo6&7p_P-SVO@xqlh<(Wl@Gwmw+XEI98Z3mY=Xh& z=DhWcDdf!c8_XJ+^xgbIjOwAKa{9V0;^m-fwb@=oe&Oedb?3MER>0_DQz%b}BWo{h1dHMf zzNXzo@*!HrT=hB$V~?1`ZI;TBHkso5OV#Rd)eO$rexW#N?h|qLou8+h{=mEP#V9> z6q~=TR<9hG#Qiw6OBpxtx_EnKQ?{Tp1{jbrt-nE(j~SVN+nU@U4XhN{rq~JmSDRa~ zM^_6r?_5r%-rEdE&OhO6W=iCzg zV@Wi)GmKKQrW;~z*1i)?ZO;_HG_6sO3FEmX-|FR|t9`}%x3+9gJAX=_BrN?7$uG=E zk+wAndWfan&oI_aSVd)m7=ww= zg%4XY#0J+Ib?KYu@{3OExRthhl-av%iMN|IaYl)+VtyTDbuuTrv#rPyojjxp`YEZRc^liI%+O0-Cu;mQ- z^;TE8xE6B1wCT1aAlaH&;>G<}&JPgN&B@kjRwTjgFPu*Mh0?1Fd}loYd_e}T4=0mj z$s1s2xHG_Q^a}>IW7f!}V)P>r)7JQbuw?sI@he&*lR0vSeDwIQO>*UlzP6+e6(`xv z^~nr_dI))DPL>;35#y9bNJ#w!WAZNX_f}x-nj?C!W9oPk-7OKCZ0QWMR`n;UADtK` zUMi|R7BQ~31wmijEH-hdQ6GMm#|>7sq@=$?{b;M22B+dSQ?1XhC9?mZZoW zyI~?mk1OTHGe@Crmma*T2qDeRuSJP=Uub66mo!Q8XP9eJUG-?h{B4~n1b0XkzZ%!5 zgB{Ab616|SuyZ&!yWECkXxTDMyD@kNU1UKbW?Pckk0i`*{WtvKm>jTN*90zN=jFri zli_rmFbG@#q~=sG!#tNTa}ZOQI7?{OxK7+(U#*@x=pLuvKb$}MKAVdXZAj5_2}3XJ z$rmk1u)8J6RcaHu1k8{9AIw`=nsV1J3_0RMG#S;1$`%VB=W!n@XOr*7cJb$!86j_SW5lY zG7MLo2e>+=AUb>DH-t z-VH8qi3EejS{|mklK{36Yh;W)AVm}>RzVn5D$ zPX^z+$9paV!=;rb_N3C@fKaK`)8STR+9h-HQiX9FY*_oCdk2Ec9Dd2$CtPxvHK|)` zPqMKx553|h?zJMJi_M91u>qm2!?Mc&)-3G|0csss;nEWW}!FlaQa+iDLs1@-(x zEj=>maWJ%)poY(#49G8g2~#RzZXsq~+snSK_jrg)sx|87<6Y#>yp{ZxS(~_!C069} zZU=Tq)7M1#L#>Hjuo;Qe7!z6(a`k|j(BxiI2ugj)Z^fPABkG`gZN34`FjLZb#WZHk z|MkT!N6e2jjc@T-M{(B;joR8ISsspg>6zCiasC)jD=Bdx%dZ%c3j8ZtWljFxm67bv zCWPub|MrcC*Tp(;InO78MGO zdisdy;#*EPd0oG@oJXN0nQ7oiwqkt_S|3{6X-#T|$;fO28KHif^{o^ztN+R0o1_Eh zSHFU_ySqc<4-JGp#I9Kl;~D0I)EfC6V(N5Ceaqi`Q*J)4Q7iUuQ5Ijn$Gf@|%4I&5 zxbH)YQsqB%)t3y^R+>+G$Zz_)&#!iu1;dEw4w~#SA?J&%iEW4} zd1+%#XmdxM^9SL$?khg&t`T%kx&@=O9O2@VkFe9|3heJKE$G@7?7L}1%!z5~zFoWu zlqd5w>bAD|%9`Xy{Ea(tO0KztDdCJs*eX+U^$tFSRhf`O4d$dsY(fHp3n8lfD!=!J zDL6M=hS_(lVBCiWNNXv;rVV46HN9LI#&9V1kaSz%8xycWS$;~R4)30%{4-m_&pZE8 z>9E$E%x~#PmggFinEo<`DQRm$fMic7f6IUE6E8X+!WhjO z2O^f3ki{6)pi7{{%ZTVDSd-g#u_#a-2J^QZ<(Id&hjTk};Kt26e50*35iTTP?TFEA zZfx2yj2B`)c^oZ%xqg)I>jsT_-eoIMzw$Nzp>eDD1w-10T(O;jk15G8vS6R*p?E`L zIlzX@@2*d_JAMJRaG1}qYYQzE8BoybB7b$aJz02v9vpfpeV(%R4C9L!Zf6ID>FHyB z$yS&n$SzX;z50yrGbcm5?Twnb2lnJ;oGGEbzUgMO9Czo?1{;!wp6K))^{}yP0iR{n z0bU*44CA_=zlMdDDacAVhjFXS~2MxQ# z+yoQyWu`r;yJ<>dT3V6}eQP4t>J!-(TS9Nr53+Q~u3v}vZLhn7-K(|GJ~EfjKi!J7 z9y<(bzRzM99Z!ZCgqWB^Qx(?>C&|P6R;!)1-4c4_m+>Rl?-6OUt+KCnM9)q}60#b%TRF65->uZG4O49;C$>0)?`L4AY|%!;D7E z^&uM+3GLG5dE=_pALr$Xz8CND;ab~7(ZHA#&$lC%_|0s6V@Y04w<0kM^vF=We|9`< zK=x#s6Vvhn-oI-ge5{Fw`RCX1K{q>)DO&B|j{Y2mQF=4X1jK|#-%_NvE0X_SP_3@C zm?Dl}aFc&!yjDyDEDK(bzkG#^nU0t**PVonZsqdi_0{Sh@>AmApu7CXyOTv)HfQOC zrbIk0BO+#`sAtp60%M+gFpP)6lu&(VGS2Z5@1s8yR_=(0%tzt8R%sV({ZKU??i=S2n>O zY?z|JW>2xpT*-rG6}+Z247Qss0@D*7{AzrWKYjWK{@Z@(^z7E1Vd4<8O}<*#=w-_7 zJ5;S66unW5HNM4%EpAX!eHu5|mXz3-kxCnDqWuUL^-Ue(KiwYRs~eGdNp9q+{#D*v zGaiaR&V}MG9r<$weq>O}bv_B*4;tutBVpDdX8P+iVf`j2PCQYq?)%zF8D@TqUt~O0 zNd+*;MKX4yl?1>O&L`L`NNQ(YE;wzd)fJ51Ih&?u$Pus~6 zwc-MA*&&KyvU@UX(h)OOdz-Mav;(Jqs#~un%=suN?>(BgE$BsluPEeK$4_UN6TS?y3o#=G zrwdzB<=i^7=DS~^{A7`ee-)D`r#hS9z1F1Rq8V|>uqO0U*i(hIAe%XmrC&$*c+B8Kw|1-UX=wXA{b8$gEZ?quwd!3OPLL&$+h;ny?GIt-m=*yNaPz zCo}RjY)DkO~F22(Qm z<{xH_#}E_pt(8B~>Z;+x?dL*<>m-=8XEk5Deh_)rB!gf5bpf;Hm4tbO7*G2n!hU`g z7u>m8{m@~pymseY{z2_cF7%Ezu{@3m$Zry6=vORYin`9Xs~m_A9umL*`IG8{k9pIA zSm0#XXB~kpI<|V8+ zFwI5Nz5n8LZr79%{4nji9F_CDe2o{4SP4UuUbH48wdT2wDY@^- zkruhn_`IHx@cD8Wd=akk&cblAdddmD%c>O&Q}55LsYi^_;T3{<$|lb47Wx8MTstqS z2fu6o1&)?9;^Od|QA?OF{fx|bm_f9h&V+PvY2*6vq)i(e7oc3~o{fBArK)@>+B ze{zZM*FK(M&h}y$ond(Q+%#R-U%rK#j9#aw{Z}sNmK~;u&T@KKwb#SPoalX&Ftqn7 zeUbmPzXNHQY)S$y%Sl9LDK9*ZfReXkVNKLizBvpdN8E1lmLBsNCb|#9m?GwA%kjcC zVH@`-O{32AIwHR{PKUQh$>#pP)FQSe_~rMsWOLJTk`XB-zaX}&12HNzB`a2OxAuRI9;OdrY)b@rNxkvc}Zlp~F z!({I@W2p$b1Z=g82(6ZIx6z*1zQ96&w|&X7BhUCVy+%RE=P2-8`h{=iHi(3yX7^}; zG&fEAF>6{P=6s63FwZ87E64mzZ?P*^dgTB&T4l{JG`-sMu4Ik&PD6$nb2HFe?KYrX6Aw#8uEN+sS>8)Tph30=SW_ zBDhJV^W}8V-Wr;b{*G2`v-vbc!UXTKCms9ANc4~H#OF^rKfYTp*kKY2&`Aaz^MXl^ zmpLdZCCr-s4AT`cYZmJWw`ON^cgJef2NFFw_eN83{pmgYM88Jqbfk zPoJeS5?tp^&MYhEUv26RU$f@G-osXqv1kAp=Z3FWFE3+D0D>3>KM<`+V=pSI%d@!} zwC3jQUfk-zSNvWZoK==!gY>988KDB0q^;JZ?7jh8&_2HQgxew`rpk__?DbRreP%}p zUK$U}J2itJsr`syV_Voha0bK7l`#Df^K|brFc*wYoe< zM&>`WVyEZz90T@wX6V|J;A$DkTiB6gn>X+wx*l*PH39fFF3?pwkW9Je1HWI)W|(&p zW*B06eH*W^PR{0L;!0bWRVDwE@m{HQY^F%dx1SG1kF%pS^9972c;Dat8&XQ`$k3lM zQdrW4tPB0YUk`AE{d^L*WP3p4pkAc+(;!%F8_O^=2e3g4M@-!8Hj2o*JGs}Wftt8E z*>8i`Q~Y>gyGRvX{oBjPcJu>k5LGG!$Tf~kI1tL9f9KM3JuUMoHm@O-DQ)#ef?jXg`V=bzcgh?LVj12l^0$0!K zf@qKlUQ>NwUXc$O_i-9H-Iv_KQW+qnTRHR{h#)+;YmYpE0q&x;-? z6QP&^RyNGJrI;HS9QLkkN@Bv$sfuVyoRl_@Uuu8~h#biE?*axo-sJm~sZe%u9Gjc0 zAq=ycV*G20|GY`(o?s%s*O+wW#qg%84UXqTS~;mmWlBQ&*f3X}VszI2gMgH#EGK=U zy%p*6&l!%~`pGXXJpeB60j{0yK!!#xgI1h`IX#SFHqt@6(^%ZTIE_2qs#+aU$}4q^ zI;t)N2qLXJC_86LA|fyti911nKUO2f;^sY3of0$OjQo9XOnPA{yW>j);d^>oH8^0vmR} zp_rTJ@o=z^toc0}uTmGCd3CO2?!L9KAWMpJ=#OBSy@=6j^0zp< z={hb6gOH=Uz4pz0I$V`Gc!x+^xln7Sq}s6CT0pD;sYNxH-DO)gX!TRIiMMe(nB;wz zFU?fI=R1M013UZ-I+q5$|L^^c%SeVfO6O+jtz!G)MDF3X)-mmOB)9J%I%3c*74lGON!iv zj$)Y8bZ&ZGD8AD)p0i(#4phP=;m?HGs*nBsMcT@RemB}jZOBYK+GwL^k7+vOZ=hsN zYvcD|P~eR(jZg8XyWN00iXdot+?s^h<$zsnZ?@8IN|WthXGnKd^MGu|*zQB@twIiL@1y6l4Tv+G*b3;#t*TIZJTX>`zNT%axn zZ)m7Z3q-jU#SC<*0`HH$FcJ%FuUhgLyT=5>TsIT)Ao(b~c-)y`E`>781H^dg#4A?6 zn!wRZ;hfsz%Dj=us!iICezei^?e#J?XtXslJv~#fsHqQT3+d;1&-ejwkvv=o*vxkf zdjjvV((fA^UE&gd5-hiRGt9Fw3{#Dm$j;jpUbjYZqqC~jJ14~{pZjlAO*%J3o-9Mn z6CP{Snrv4KV)+^)xL0+Fn?0r|Fl;np#!c|{?F}hEhL2A94O?DELi5~bU{i7j9@$Bm z!Y*SOMt?Zg?ye9NqjfwmXpf(#tWKHWlBK%SC7w&xGa)Wb%n4PgM&iZrWm97o8q$2YbbFT#MZ7HNEU70n8;~B;RF$aF#Q7F$kajo%w zGksZ=5R#IiGW))TqY)^dDHx^2W3B%Y+$xt~FZQVhHC<-{Q{eavM3 z(|0{G;%F2UJC;DNW)%>OHN9zEz%G(u91&wXqe5XGW5Lbztyb?4427-5St|LY46gVU zM$Ze)NsAzB(sMk1j`_x<_KpEbZeqo}PQ~UN=;l2Ddi99m|6;Yc5;76OJ#WCcA`Ni1 zE({Ysfni!B=C(TOFEnbo}$0Up=VxroXD+($;$?Ns2 z)%WWBluwMds=lV@a!7nY!2Ynd_3Q2 ziy1jOKN_~!ijesJHQ2>8XV&ze#H{Ion3*B9ilwa{%C~;dsGrsCQu@YkQTeXh&(&Tv zWtT$gbG*>q}oBMAg;s^ zQAdwaZwevR_zR>yk_OFx3d0OU%;e9_g%F#=a`&?u zb*cJ}vU5U;YEyjbS1lGQ<$ID;-U;cP zFdv#v_K?-b3hOx|7xhn@aLB!jcdBq)jA%g;ONM4q>v1E-hn z0Uu)&mW8xngVs2mVOAgpZiWgSERE&1BXDkpzE{?+8ma0W(~7%{UVlot70GFDPArQ} znBelnW}K5{<|H2_J~Q*y0QBZb?BqtN<%wN<@mQzPBAo|_P5H6WURxy4VCjCCKfdn#D{+X*qn4d7On+K!fQr*a-@&D)N+((wIF#m!ByCu|-pdUl;}jCLW*h4En9G!r_U z`U*jF9oe8+&0>Rg95H%v`-BN6dimbvHR|u7ca-go?}|gB(v%eQw!)e?pj4D%60y!8 z#Vq$WC*m>#(!*dgtZXv}mO5VJUj?=zMoAN(wsj`#>GciTv}?&QqJ&W(=Fi?d!T8eZ z;)DQ=dS_EkX*}$Ts17;LFcG!ZEaUMO^J`nNCfa}2>$GBK>Y?9QrQ? zPL|8?5WpA1|5=m$N}u!|zZEzBIiRws6R+Tcq<>{|1?Tz-erS)DB>m7xSpPE*Hm<6L z{nsSb(E0@o^9(U{|Bee&p0pE87HZV_kzG0YFd|=4{reqxViyJXGzJpIdA$($h2b z4&DZoCM4e1gv9nmaT0A@d)1ufJv}22LCwV&7&iVpA4{5%p2fj1D3=Q^5Mj}DPR>;%e$b|bbx6vY}j1{|{@ddA)>Tj1glTTO{;)@Jn&*0LD5m z_mfv&#NN2kSCwy%VOkZXR{3j8NcKJxLZw#J7oevn)!g0=IS%o+!oj`CPd=-a4e@M0 z5USsZP_VodB98ZBm_ExG#s)EOla2{D{uC-`NHsC%zI@&NL~fQ*oRT_Fxt(o^Kkm*2 zA5F;eGz;e0P+x#z%D$e0@}r}{rT91hav#1c2$I7j+e>h5=WQ@MgtCd4EFNIXQs4CSq>8R$6u*?6w;;l5JrdtX0hdgM zLh!F|{ERYl^0Q}e=v8qI3YuSqFm+#sdAWjN+9GDp++Bj@j&?nFoxmlKrNepkIm>-s zKERK9o&6_D80vDQR9O(3lcs(e#ms%K1n*^mFnORBYzi?UO-%ftq45q3SbYhi@#aQ- zXy26#(-|?>FQ*HeXKnEvkM9V&hX0lSnWN#x>v_tl4=rqyFw}uctFvIvE%iDn#-uOS z9dzglk8Q9jj?OWRvPV#OEK45 z7?9`hQNNB0+IUt8oXc{=*ry&81!Lv-f-VrO_yX@N4#B}uk~rzxYKEDFm}Q}Uf?qv4yE*HKq~WT87hsLYnDTy0E@ z@FgDI1?b(AT9ccMy}hy|EyoCtY8XFT7bOU~@a6F{Fxl?~g`<8$`QhDAE|U`Z0TN~r zVp7d*g!7G_@(&n?9;yB+ud4CnKSY~yCBuwahMn$dR5G%USTb3H!z*jHLw6~wf>`W^ z6)rP?H@hmKe?uEsH=_x;m#_^^-jXn{*Dz}m5EEM1pt$lpNbZVJ_4(UPxMgp;@TaqX z$Z1?4erZ!ueAa}dU>c8NXk5TM2ruv`khLE90{r5h^LzW4z~t;w=r6d#RxIT7{7pJ^ zZY>4x6C}(A#B9a#-~;wdk$)eFT4{ulKq$S7? z4brF+lrOm<1N?Z$u9xJw>oBT;*3e_EXpMx4=%dF1UG$J{_N*2zc7MRP7;FFrL6>0d zWqUZa6@&eMHo)3`OW7_kYaPSvK}=-kWW}BhY4WN-je1w*C3)#+jxP;PkW-Nb#n3}K zv`oSjRq3*@9d$WY#r%L4Q?Brj8>}I}Oa!glc5ncz_y$L;hMb+Nq|HXc97c>*UpYq2L+T0P~ zX?I(=?TrV=f&>_{DS=^RDa@Kv6yxx>c;|%Uay@_a(`-)2^C|;)(z3Uo%V9&}utdVh zW}?mpH=70z>{VQCOQ@eV5%q)5-SYUsu@VPg9_&wA!!S2DFpLT@ z;C7?4fo_L`)Jey`>*voq#4AQ+D%mU z|7E~-f#unzEDlYNwWt+MNIupUq;j4Qq55R`gdG0yVMkaz_7L1_Z3gB4oXCqU(ZFNX zOM2e)mIkeqViv3`b`YM*#{^-k0RKYwnV$pl;sGhWW@ij4!K&}l+YLX1>a4`KKl&*Zm1RXTayR< z`$bLwrCF2ME>8fdz{U;CK6W zq;F~um{78s4ce?N45J%@ch4S^6i1FZaeEUq>XtW*l{pWG@h06`h*ZwwTx`QGg;D>k z*u~@TUTu<8jAAnUre4VGN$-d}{z)4LDBhL@a}s~?AurmK_A}dn;Z$kRA|#9%Vm8IC zR@iTM8Jnf0EHxj=CoXUiZ{J5J3GX-miIZ~rnX`;X8b13q!M0)@-a3$q#8bRd z-5frR$%NqrjeJm+C#hJ}38U@O66m&-S!0iw^C24*`?`2?$vZXb3AypgyTPORT)ak6 z)zCzJ8=~neX`s^nnvq~vZPMP*o)mZ(kux(KiBNEsZ|>{>VJ6#QV}CtJztDl?-fROm zzDpPz3FC^G3-##=ugTrGR(a@kPDjDz@&JC^YZH+cZXPP2jAyGES%~pYD(B%UvPC-uy&*yd_R@M=BBlT>42EdmvR(A&pGZgdYzv~ z9#U>t+l~(&e^+Vif`0N`Nt{HbR`cV`$Zjmvn#0>O4OF*TP9%8ADgJ4r3w%r20cEcL z_}33RkrSgGprTNko49Rk(7GX}x2IAu^jIIRMKQ)~F6%4vk2vzd+tw>-DKPplM(>9i zc{>gdW(+@c+@OU`1yLrCa^D}BPULf&<5-xc1$;K%0g>&$@Gdo;r0lsX)K^L?EowW% z5X78L*C<9G3F4-RnD=b_C!YQw~dB+%-kG&Ce@YtAq9Q9$ zmcxa7UuX}XZ8G4hV=cdfco91-I|%lZz8g*&v>?Q!e9{rx{2k1>sx<0$NB)ReJ^pa@ zU)KB4ieog;<$!^EYR&L>82cQf#bj_)YPDfTOY(ZvN&a9}2S~}z1pB1-e0&=(V$iJ_ ztn4LOla|h`8G)FCoo$2%4@Ph`0>;z6A6Et|A9K3rCdz3-l0IFe;v|Zp8Yqf!S!2(n zR!6j25tn_Zd5iY#;n18ch|sO%*E)HVB`qwW_Pn&x+$3wpB4&=Pg^*|&%B2=*)aPB> zDX*Nlg)ZS0Ij!JNpDxm{-SUan#3xq9@}2>S_QXhGOdL+RkR?H9_^E%|z{Igx;F$iC zKkMN|4jNm*^wH9wb(H2N8ZjLr+=W3;!nqn$cU#nL6!^Qxx%pv+9K}#YSIH;InvQ-F zhFU`($@ci*O4=G;JU0g; zw}W1870ga<;&$40;6g%l$gnC9HWdf%8GVfK#_B;mn{J+|a!P8HNUksRoK-Y%5Iv z-=I-Nm&G*~a;@wq5nj}xO9hFfGw-l9`PF-E!n!%#)ni;phkz*GhA9_9gg{=2|($ZtNfvnN?! zYz>|VB+q8MWX&eTEIQyPq@9_}otv&vpG)kjT=q(bb8v}a7#dZt+bdycxSOWF=@Oud zt`7TM$dpG{_=Lzd5VUbO^i4N_OD-Kq`sn8Hy*`d@HhU#ZCSpof`V0M=Msp5hH0mL7 z{e-W*wYYtcqZ!7-#*%2GD@a#bBxlM#Pr3^XzU@21TJl8 zM;7F}U@i9L4D(tVwEc)lzQPMX3}d*peKqQ9#cA>jnv3%Ot*3JIyP>HFDz&0}T8Ihe zY;d!oTPJ<>JwVZ%+)lW|N9EW<^3lDZcflCE!`l+)U>C?*B?&J14EA{*LripmuW<2X z3|HMnqwX$lmH#TSk@pRnz%^haI_GDY??jK2N=9hLgX%h|0EXsoLQ|TP;in(-F5hjz zt6@KgKg?jvjke@@a68ESw}e@2!E1H1>Dn=ngI0Zow2?)EDrXk0Eb7*61Ov zjh?8Ymjl@pUBxduVuLlK4?~wfcJOOKE7I$R99mqHu2B^d<`!apB>D)8#>H@+h8p#r z#Yw(zzGNy#l>L*_^Clx6<21#1wMC(_M{f*yhij9Nwdf0AU=l{!kvsk0@m-^hp>O4J z=y|mjG~-*6n-hD3+cilw)GCwBO*vv_9_%7$&5Gu9{#B{-?ia}iUNR6fpNevNdQyoZ z6^;$f!Y#BNmI6uEX6kM#gX^%`mbgv-$h+hiW8JPIu-@JRt{1qF<{SD#<7i2Cot(um zPY`njt?@UQ!VPYyQY*Yp$$td55p`20%gL0qe`vc zD$8%6I7obWf0Lij89nmF!Gh`24tB93)-}e&+CYbdJjA*w7&IP^pRQ>|6PQ)_gC7$n zz$ASSID5p2#2gp@F%~5VH?FU!@QJKG7@~#oXOzQaDKGY@#z)%&_2B+48cWhUkyXg>#eaQ!Zk58SPc zTB*;H#i2MaE3sk%%}LW6fp)zu8#I#&Y-sCl4q2_9@NLYlLeoj!5VFaZ6!xA48;?aY zYvhtOR)|r)=_q*lkKu;sY1H4qNItKNLcHW~QAw34R6hE45~f!%DcKNd%p@b0MUYLuB}FtyPlz zyl%NDv%ahB+0=kspK4CV;iY4ufrN<|h;IucB}{TpJyLSq79KfP@hv-)!idWpaIehC z;jW1==%Ezo%9k+ih`HX!PFQkbDA%ni-lR93mbcaaAzC>+W7jB}$fua$N=!nc7?vti zzSv5b)q)oJVq*h#u1|Q6Go|n;hXXhCvk!e-2bFG;)M}K3@j^^YVpCz|-QZEb>wM24)sS%xU`c0F zGOukaK<5ZHXm9tiLGwjS@iPZu&Y?i=U^|Wa*gTDL*Ahe3ucvj&U~5C-JqU}-qY{z^ zQz(WCV7O%xW}HtwOw)3Pt4(k4@;guA)u7%m;3Nk14{d@6P9qq`cR$1QL5y~Svk>&g zpX$U^t+z4S9$6SUPgqTA^TM8ym{kVJ%6Dw*@Vd-io)eQ3|N^NXR_n$S% zSVoUx0-xaFfPpT$3$z~i37nJMpuSASxBL7SUcDUvLbeWx`-ILAHhu=*85+-nE-Rv+Qt zIe&z7zrhfFUyF1%+XpUJB+M)cGXXIPOE=rf;&!RY1S4(;*tIXJ)cf%f_Z{J`^H;8pW6@T#lL35EX(-D)I z=qgyRYs(EEu2GXMyZv5!v{gA}PgLeB|Az^~%ZFYNhVd|L_f{7#BY56?yQl%n_Fdsk zyKVfvA3tD&{TRqxRR_Z+9|HYeQn-7nTu#?Er^X=fmi#KxU0b z!o(q_a$$4fw{|nG<7gbT8qx3co{lQ51kKs9Y5&9cFE(SF4OI<=Vg&^%B6odt5B@IU zVdv4+{05m83Au!wv#j1i(vCuSmp6c6p5`%Y)*+_2V>4lynGF{(N~2zpa$9k~y_f3v zwJUy9ob=x=K;zJK>!bl-P#CAj`CzQ`PKvW%&*42) z6T0ta!F&G<>Aayj8>$+j;v^$X39)ws1{a~p%U+w4d)CmmFKEAPq=Wtottcg#sJ9?&!uK@Vw~ig=1O z2B>puvQ-6Ru^myt%T;_EtgZT@AqHyNJc1W%&x6hko?%8EW0*q32=&&&#4laTciFub6ZcvEO*uRk2c(OdsF6eP|t?uZ&ENX zojur)JpG1F6x8a|JQ)^(=)! z$@k?e-85>iX{JKtg;uH`fzBMwt^MbxQPmK22Wira=GN%_rvL9Ec>SKhEraF!JEbw% zhcAfy&fkQM8?V9ZVUjhiCCoiKH$QBIoRL@LVfI*S=w?6 z;e;7MFwAQ)-wsO}R_4S)y#5uaa4mttfxs{?B+LuMl$Ey-PVP7=-~6XaJ*2ghaC42l zYM!wNlUn_EBcPc=dLy9eRX2Z00~OdkAFRWB!_l&2{sl%rjug&-N6uGaLeXuozyp*< zZr`6^)_g=vO0O2epPJqBijP(5v+;9-eGCls`h#PaS$t!q8EJnAOSh(}AOy>`mcNlO*Cb3mVhXC73tReck)L>4r8c{) z@LT)UMy2iT#L+}PEjlMduZC)%=%c0g`BF}rh998vFiafK7u0tb@RshDWJ-%U&^k~7 zp1BVoqEX7?<`*(+bVi}PEm&G2Fq`POwZjx|} zD!OQfoxWT1yKoSO_v;1y|E%HfT24l~1}Fsgxn#m^dl;B3A0d zw^7dTO$dEZM%52gmOvv=1(CUcx@nkapUQh;F4SWAR0x)zf^K6T!A=ia;rE`%MSWmq$+HygALMGV6u#(f?yth;L`56Y{;`nCza zb4&BYvxW_R^V?yiBs`GmW4~O~b5I%FfBH09rp@Q{A$X$VVd=beeE*x4#4aEj@?6ir zGuJX$Xe$j`@fn8chnVobeS~{5Q~B)!RqBUVGlZ_Alf=A|4Sw`RKE+%@Jtoc7eT*0I%TS?!ipH9axjq&tqWl$}=$Q+sn;eY+!%z|)vMaID8Re)bqE(q_#x z_-=6q9?U2Ob2|z1Si*!OCiUY;;mEvie!~yq+~g)J_v^R8DqzV1#n7U2^t~s=&{*ex zgQi9)Z;w{_P*&3$ia(_D>+q^owqrcpQJsNm;U4rZkuY)zGZ`^%ZsUbd{a*XEJ5;3( ztg}^)#3s`1)@v#M!{kRu7+R_CKTJ_CoEwjPczY}ed_uSKZ!p4}RW|`<+9_bP)jgOx zM%rwG6l~CDA!hlxDZQRyD|oI12hgzAIVZ{Xn>ev=-fEF z8@mIC|F8u}c&@yapC``r&7X6NvM)tInsoB%<$&O*4~ zT{xI69cw{KX3c8E^vRko1Q?e39Vx6*-y2ox`+9h!a>vs*Y;LF$GRI7^hDO!@!`Rjt zk}BO};GWS3vO>1;E}g8%goFujQ2#7!U2qq!43MnJkT4q&W8peWP|5E4T`#Iqd#Wsi zb@DI5B@-)V4aLwL0Ub12aqK?~&EEvA$_L#?17N>=C%YJ*+{aK!cLAD;pt{cgKZb6dRM%NuaU9w_ z=np=Kxq-EAH279}Z`^6{d2|idH6fyZ;IcBrn!RE7d4N(Y%-_%*no4_Vwd)5M zL(}mHgf)4G_+z34Y29TE4Ad7OX6JR#we7?9v>FL>8Zq+hIAQw88-6Kbm3mfk7x~$x zrhZ!Qw2G-jk;+G@N|o-=RM$yGeY9pu-2%+5Z95M0mj%GVz+65S<8JBo6XEO2GhjXI z2DF?a`Duj`<{V;9-&`)Z&%Wum0x^#|zVJIGzwY;>;DRreDAK}a^x=PzfhkLRQ9X1~ zd%V13Lb9>-ad?5>$F%v`ykdt1>C`+7?gcBs>F8BhxI)^YSDs^Ya|1E`UM&`ORowPF zfP)qn&@#n2HWKF!kjXGQ%VPO)r zH8P<8&TR+PWS9>WV{fuvROC`AxJ+M9smUK9l4FEQKTL$2@}9f*kfSq9=>iO^uOsY$I*JiyVN?L?xC+P8-O=^$m$37ke`tEHkHud4-1Zr2m9yUD^uF1mtW6E+DsCFITk z9Xy1qyQMNXP7KR!)mzkPUYhC!dZDL4>Idco`uhYao6nz2z5kuMGLilJSJA04HxdY!jS{}vt;WkoIcpZ~v^Fb`Dv0mPN=Y~^$A7nO!%BL@J*R&iZKGR`OUM1; zPIe|NGsuH6`LbyCKjATk6q6J-RV25hT9A=gPj2>{6RP;6XFgswRQS@9&aU?|q4Gv5 zz2;;I+-Z$FNps4S{mFM=5psdPA8AV-7n(sNeo#J40$&~!z_@9$ecI?}JjQ}zmd=_W zN~o_CoV{32`i|WzbaGfCQu$gf;Le_$u9Figa}_I`$bzfC;Vg|fosGuxTeQ@70t~#J zfL8cx;_xf0z%ibM4eRqDt6PTo`;^BxP>jMep(yBaxuEELJ)xfsVYlWxk;>r=0jGq# zw?da!4Gp|UO|z(Egp()^p%#anIO*@H8<5w4LB28x^;6cu8k0A|+AuK;8C3><@?{u5 zSv2D)rfjy8==7PFf-&dn$;z*K!e>MJh)r*v5-?PkmUTxL=P9aTlV)`snyQJnU+T*z zQ#eJJV`DNr@n*m(C=T5itA$UV+W_}R6Ie941m@0^y`HTyj2p$c01oLBTk`hdOA34dms$3 z6vLx{LQuagThnTD`9YgXF>il5h^8py3S22htobbS_nsgzUUA%&%h_xkIS5~#Lyxwe z8oWM@%h_-RWxRs8_y*KAx`Qc+M^8Uc>y|znL3Mm4%q=N`=*cq7ZyCm$VrD01a-oO~3my#@I#9$?=>*R-7j zvD^9$(7R6p%*_|DI$oBuF_&R{Ddto9Ska7&tiY0Dw$79j&pj+B-UKQlPNFz0pGvI` zsq(H?F6A5F=7$v2@=aG$7SwxrC&-LJzQj=it987;5t|8GeEP0Tae9#(YQ1RY%uVb$dlC@T^0ODB>=6GSm1d&h|)Mx_Z7&eRi}+$4Os z_Mo^?eVBmL4oZ&c;mJ??@k&U}5Rl7t+K;YFGV7D9e4L^gz?FQl8_5d)I zdkix}UqHC8Y@e1O!|bIPv$9blHsz+E?sPp-S#KjW*nUWSx5Y)kX$LtUsLOO)&gG#w zyQ$uteen2GR0&B7Y=mhm2`0Ka@UYn+aQ}Ii1PaVfcvtKr7hbX4+ zUn=f*NfvlhjJKYtu(JD;2**Bk<+OvGtJQ%96~3(WUH}zZXv-vubF&rkVre2c1~L#_ z6oUpg>SDV$fv`-N3Agu@f&O&a6fl%U6GJhs{-&a$!-;|`arMOSzZ=5N&nv}Wu&zLz z{`Z_m*VdENrH@`k6ulpancGUZUoiDp-L8ml&b-%e~TY@DQTvzUf<1K5tg|MF^&KvX zanuSCC+Z7bWym{RnwM$ej9t2T*-AzJ-jnkk?3tSch;~#kI~s`&-_XSa=d6SYy_sMc z{Q{&9WzWV<7ELC_d^R-@{h5DAU_mEz#GDfGFS8wDqbH9=haLLjfwZs9f-q_eO3N2( zv<6|14+^|_*0g)__|^Jr0DBQ_?S2(?{2YW+BNl^F9zAFaXF_K;B2UsaWcG87s8YH zd&u{IE`G1#3-0=lLARn1pj`Hmo}b6B0>u=w@tw73#;KixP4s)S{Ny;H*P~D|p5H9u z?mb)WjqodKm&eHxhR)OD)pnej3FmNm^|%77)mFe(JiUpMm348%&V?{=xfs?j8qJE9 z)Un(??QuSjsiv5pQF@}{1DgcjF3^+oNh_u{f0o#{V?N6QptwY3gS001}&u)Zc*EOp)bv}oAeNp|LFzcFfR*uOcTZYxpO}A zaMnt}7W!G6^rIh>`CU$8s(3ZCHB=6c+!}<>TPoocTEzUD%6K?&66Y_F;PDkA7Y~rG zi?x#OPCA5CbLb=w41~2G%b_~MSh{Mmk(9%9$fEf~G0l_ZGUE^I5e%ZygvLE)3a4ub zedeo*wNJJ~#-#qZX1pSgQOwZC3D0_A=h6PSvZW4eGi{~s54cMwkrHG|dlt-|v;*Gz zyoIDpq4e?>M;;R+}b7_P9vH`&jdsC9(-Ew}9S8 z`I1c4KK}`HMfGF^JA>V~I#+V?lfT3;;tH4rJqJ%OYCcbOolLnNc02eDN;`5v;qx(= zzF%3|wA@7M;B_2Kokrq;1yMj&E8ujZD;;%Rj>r7pDxgX+-7eEa#fsK~wa@BF&lVNQ z9pe)5I5tV7Gkh&%4vvFt+F_AX5UYQs{cy@Vz;i?boGeB#<5B{dHnxy#S(*qj9~|(a z7Z<@NNE2rl-yx~@Lis76DH}8$ieaaY5fz;=6RgXsCwrcqV?H&175?~DE6jD!f-9q^ zK!E5AaBc~2YzE=Ib6UaZ!c6$`UnT0QJ;CVK7_;ZECBmVRws_ExR5%o9f=#C;ONLl4 z=Gz|pkPVtK#n`S(&$QbyMPNWr1k#Hm(cg?GjObbf9n(bn140iM2ukEdOJH$DYUl`OPD+-l5aNp` zS^khfm#%4B@ltfxxPUQ=&0#cKkD}!AO2l<8=iCy8F4e`(84Vy^PhEQLgy>7YJcv$R zLa#k9!_e!d_!AMsfcLKWyJZTxs?@_{KFctU6l1KpMdJ=Z|81rkS7K)3% z&6xf=gFehHLR`Cd?oL|QUKeYRu7e%Nej>Tq^O5l-Iatz`gw{r~FkjgmGmB_Fju_$V z%M(#|vpoOxl#{(TLW&9ZN_ABZX%g5ktS9?B4A`-K2O*U{519G8Md-ul3gkxHh;j~> z+=rlaQYADlSB6P7$B^lWe<--;Dq8mP4Gj2Zjn@S{fZiqUI6mk+@!7V7tyY+TvTxmGOqH9Eb?s-QYFr1LDZ@W{fggOBZjRIp!8EPp zf31;yNA$pn8TR;c@m<*4H2Hsx1Ubw&+4*KB#T=frQnb+6UU=P@CWyBlVQVH)|Fd05 z%(%s);oG-~@KL1_xZ;cUJrtu_1aB7w!Gkwb;ZkKXmLzP(wVL!kr(*e|tSOko^pT~8d?;q>$?qcVn~Q~8l;lruoW zk1%xMSr=@dF&MA0P65lxB{*2g4))Bx$j`K8vV7VGiWwgFSk&(?Z6ms_j&yh2M$;#& z!-Lb*6m!5wNSoipV>mevH`B~^XY)Oa4foeWos$6XG|)n~IuVHSm~7gIwrM)Wt;&)GYhrBhZ-n1Gqu!vX8)7PX*Y$yC0qz@fB`)AB7=u zd+`}nIec-wtS@fGO@0c*QOp7FK4NPhOXk0+wM1wXkDAVELT}p-lzq4knl#@7*RWRi zpB^5QsE3{19`OwXOD*ca-Ygt92ifDL{v|M0{u$8L=rGhO6vr&+hF=R^`9W(>;W3ve zCNCsZloBdn0&{Cf;Di_A>-)-4_|0pmG^!eG{(b;M^B3T9)DRDwVSsIDa=tXC7t&_b z!7R@xoNhWC2hC{*_lr4j;kr9SDF02+W>2`gJ5rH z4QkJLg5*EP&~MH&2-F+EV@hRmo(B}8HS4?Rprs$9uUkXXLLAxG3kQSWyCmdVQUPw7 zozS(r6pqxH;H_7U@UhazkTsGvvMp(ZS#u(B+FCt4WAPZGeL9kKm`9R#XMah~d`^Nh zGy3tELYX*;rI?G8`-}CCY-Jj=tI70#=IqS_u_(I#aipqJ0XDYZ;iG;jNW`W*Ceb+q zTC0?ClXElV8yv#s`U+TV^nv&&>Pa7s8zeoRagjWGe;tO?av(YSGrGhNS}w)J=MEN2 z6ZbKP1FA`y`#TiamW=FX&PN|NmxE99Z}8L3g;|}3c=#qgY}i4qr>QrG!lJkEE+8DI zt?vSx-$SG^W|O3u`je$P|GLTGx*O1;E^8+2eUZnMQp~Wk<)Xpe2NnXkou86nb@SDfr zU`T)F`J&_O+3pi;u(1}}{o@T71X%N!^|ENXDP|T97q%K+V=j!TB-x^~Xh(n^2-j>y z-QVfkzn{*So-asAWg^TOWJG%rS0m0dg^R{tAsA~nABO94YN*qE7`w4oku8mwhkDoM zK@e>*CP#m>WEdqMYBcjOQaGVJjd}RDf+Ww6k%Z^!KwO0d6EnI1mc8kN8|^Al&jmBk z{P_}nc<~Z($rKxl7MN)eiqCD2g45pGP}#E=-D!(JE;lvcR^}bxHvH zR!%+wk>B;8U#LIoejR~wZfQW`z7x=y^o!rwRLT^@`V=$Z(+c4q<^}Uut&%{ivSgf! z5Dsh)5l6Z|hdtgZI7G28IMH$u6~SHPL`&c}LqM<8R`@zSPvl_dI;h#7j)5@xhyNj^?~29h;&kw0Y& zQ+HcKb>VY#cefp!YBs=$Ds6B-?g)gNwt0g@oB1f#ae$*(pm@pSPIVn1h!d2l0I*v$T9j{a9kMvgv$ zjK{Q~PhE1XUr!di@ue#6`M02S(G^gB76X~|yYlQT?MT}D3I2xd!TI$KC?O*r94yu% zr@*Js{<0Ga^0z^Y`aeDz1sMiY%xC!&p~F=L^yFYAH9S{i*Bx?%wg2LH3}>Wi7FGxO zU!Q`_)jN=|>kYIHABv~H?}U{T_v1$mCFthgTC_K*7ip``!{W?%{F#=?yUX9^F=83U zlVUPn-xM~6tDrOQE6F>X@#y}ZKA@|hOd=JtfsZ$m1?Eu9kD?Iay%06z>RmH-wefnIw)2X34?heZL08mknD%QJjw}BPvpoFq_k(S$^SW}$ zydAXCtJ4K`yVuw;l<+z5X#*Zd8%Xt^sW3++~D}HDL4Qq)=3&$6M=jEs(h8^@c0! z;6=9$c6-t%@>$`yGBp+ryHw9(Nc>JT( z7=3Zi9+9+N;ZQ&RdeEiM)`Ch%B&EEYSrhOU0=Q>X$ z_Q969AE^Cj8H`zNfn9qF;nNcpsnvqH((qnI7+QV>jO}#s+U&FVb-SNb^2L_Nn94A> zDMq4h#pu0GXU^@aAqNWwvzlW=$zPo)*3j`GaPmiQ;g$dbY zu%C99PhhpJ&OpBZSGY&hr+Md;abnaDK)t1q_Tmc!riVjxM<1!T&J-!W@fbXJQs3LP zW$xTJZTq(kVDL~nYCoQZYApNm5 zHvXLq>$ZF2k-vQ<6IV~+kGLwb_ok6zqWAa+@BALh_*m7Et0{MwPzwQ>xXxGdSWSW^ z6@EZz{_U_PUj;8?`{D~GrBL#;5k>D^jxvX7fMw$$k`u-H3g6J7IggO`p7+4{r*Wl=X1`y+p(6zdZ+w6rzMyq# zQAg3b-^bv7g(5yGX@Ir*8*rM(G4!oVhN+QZ{!&b{_DiAL@-(5oT^*^;Q-QhFs${`V zeP)j90I&|pMrNJO&^wh{w9y;(j*Z1|W=b8pl->EioQ+OJDAf1=31v3lpek|e|8_Xs zD!}gK-y4;M@^S~y{1Coee?WM`ypBXnJA>BbzG5@Ot}${0+~J$nK=4`D2y|8SeGeIldD-J?nw1Sb0NRxPDF`^iYQyNUa5%lo!rt}r~k1<>Ux&{bcGEwzt; zUY)FzYx9(+iGW}6xN-MZlKZpFz8pxmq!Rt>N z;@bYjRDje75f9#hj`eZofKeveEaw0Xf)?moQvy4pX3!-6ejIx603Qt_!;GXDv!U|L ztm7v{kxOdH!hC;{m3T=q;F~SdzSj$0t6xEkO9jMN>*CNVBYq0RsJ#WZz8|5eVJVC` zlmO?#Z-T)E1$-lmK=Yq5I978gc3knBpU`h*R$#6aQ}BDMP_!+MHbAK*4r=t1X4D}0 z9q7P}rz^8hP$#&xy?|C{J-jE~7%P_-gXfSo*zmU<<~>^t69&Y=aqDkj?_i7-H%5Zn zCkG-LJOgAqkBd5E-*Sk@OGiBf~P1eOQTiXEF zEj7iSawR}b(BRsy4oK^?!Sfww;Suf)K$?wk+rM>iK++2X-M+!+NfI7oE1Lq-DaOHh zq&RQJaY6jT8X~dXN{*a1hSZ2QbUvXEPAu&LpBW|aYX4yTYMvPm>n?$=xNqS2xdXx` zjl?mI6S4BUc(^)T8@I}@hJCbC^P8?NsM`FH$GC0br@(xQdH6g~ynga%VTPod7@ulm zgBEGSx2pbN;HHTER(%D-fn^X+2ZfQhz;R1n(lW(gkdV^>d0S1f@31j=k4_le^N_>V z{|9|^8+gnXndzJ##l)+6h|~Io38!gR6Pqc2nd{Ud|EPOCdX_Jb)4u)S zr$CL%P;7sjZfYqey|4!|7kvhsAo{$*bevvomgybN<2u1jQUk(TU*A1$^RiHl501 z$^L#i;9RMHFGe=1?_{9$<31WW$C$qP{6F(YiKOOl%s{*m&9Xhy0_ zNBlC9&bwJgBtOh?TyHCnnIOZ2P>lWTG{Md6H$v^63X*xR2Sun{M-iq1PX^GW@*PrY1s?>DY5Mk%4p)$N9y?3 z9(}1->O|?KLO1E*&fnx{fGxcwE95anGRy^vnRIKA(Cei+Q(Rg`?noTjetKodvTq+q z`1Bb%zscj1vzLLFumBR$vtY-;VxlUR2~IF$n3xG=M1PAjIcr;t#+4Q#81J#pY? zeF%aQ6v4iyA1*FwgOLM0@Qj0_v740-l#(;)vq@@m779~NK?$T8@-``8x!+IGgpmuN*k3y|kcJ5lVCFdRFA}b!VMTQYm%xL3qv8Uz?=EAX3qFQ#Eytw~} z3Gekmo}1}8^MWEay?!3`6gYt9oiC{IVG6o8S_4O3`3P%T*JC*icl>0D5m?oGqv~U8 zQND#9UH_!;_|tQK1Enj&Y(GlX<&>~Te-_LXz*Mf^<9~?~` zc*1{Lfc4@$6tYi>o^7L|WSv%;@Y;@bdnaJ$Dl=HpEkwRmYmv@uJ;?ZX7hqJgGlTZ21OvaOW#j@Biu-D38Nk{09XR0-3z_Qlb&o+Fi+R1YO!V;#++au?rOVF0(hVUgb1McU@>X(-1pnmcS-&A#Um~hhw~x;Lq0< zG)BV_QWu@0If`N+A*Xmu!Wuprg++7^-PkK`T;?pi=vzj99lF5IaFDPwy9N;s!-7<>dS0CD4^;$f`yRAa2i!pyHze?ry7vm`$HxmGUbXLyKVF zk21kFRKdOAr!GF(@(i9__oO`}N?{=L0yG!o!>%=*u+*Z5kEU2QXoD!GYsxP1ySJT! zOUdQr&ADx$JY9{|+onahD?E>e!PwKa5xAU9aKJ0zdJ}2Y48_@tpVBlcU5IAgg|2Ht zoGNL8y!~c)uE%IR_xg9ZnctV+r;T3451J{(q&{6C@>()V*uJNNObH4AdCw5|am0NZ?qaJ3c*X4qk4Y z3YS%G@zDrm7U4D&6RfQuQhyvI)Yw-^oD?^?4nIEzbv+6sk@EC&_Q3=j;sywe=m9P- zU@ZRy9$v7Yzbw1eSJq;xK6xoSZa@$Gr06qj91b>kDF$ zY3n)Ro5U)Td{m8{9aWBI99zL-HZC^93e#Rgd$}AA*xCZh#%(ZUfgSERUjT!BwXsP| z9!y}}@Pkz>wAc;DR*JK*gXISJ8Q{ue>X-2tL@|d8&Wqxjp9pUzRg+&8X_BnJd(huE zW+ccSvaz85Wa6Xl?pK< z(bz{j`892^FOQi-F-J~oiZs{;;kS)7q%}Gp;UOQMoxI*ycZCy z|9~XtsY-{Y>0`aQ;UFA46t5fZi{sW>OP8o9Njc1R8D}gtd{g=mZaAbgIX!gjb;jX?eYRcZb-52@!tf@4VP6=NmZKHRirVH#q{AV0~FW8BruPm2t%9iD9 zG8XfgO%yX%bFpwyzBzMwMjbI$zJzuhvPBWIze#*fo#OWb!K2;+clG@-`49NbDTe{n zNl`~-FFdtUm6|`8DXrPi4C3+5a67~WAAKH-mrJHf(_b5peLmWm`O$`?vsmO|6hCVrn5vGOl0Sy2Moc`u>op&fW8h{>Q(OX>J6 zZ7{r82wv9XuusiSyxUb*`hD(6ehSF>@R)FlIgt|~R8AYsOj}S#j*s;d4byC8Y69Og zQQpdkF; z^Az^Lu2KAiPM*(Wj!{hAqC-N*abp>mA$8$m4mz6ZpqZ(K zGUe&O%``w~KGi^W_AAtJ!4k)O+JFa5oQVDlH|19W<#~KGi4?;!7leOSjbY|l*OH*P z)u?V^i6nE4I+XM~fez_?MTxbq;Hs}Np0%YfEDM_%A6m+hRf}1Jk{AE}56EB>8><<_moQ0wX zDdX6Cv+?8$%Xt)s>6y-B@+qdN-(jJ=k{a`@tCD<?j=Ru*C|9s}>=QIKRc9v6>32Zgjx&eSmsTF|EpYDc@_6aC^Lf7M*fVT3by zOgY84Et)Hw5FyVrYE_aeqND8o_g<`Cw2*3OvLQG>8C>ZV_?t8Kyar0)5eu2yvf<;c z=kT`AT9`1;3VI4Y!ETLg}~`;4ZxqtzI%4-A2ICl@H-X zY^<%*HS!o^FCO!OV$L?33Z?p;LhtS}Vtplr&AoR)xKFYGT70Q| z*QNrRDl1_9o6&e@jv+QQrwQW`uK}HT0}bPBF>*7(YYZEprG#G0{CW-rv~N@z{kNfk zEBHanoyB9iD8?wlN^~;+hj6b^8F9CNMlcyK>EApG9RK?ZK87`r*63wlK0&R*CwM786~A+^!O8or@I`So+F*AaRt%%fxIV?hl|Jo!G#g}?9*S8teVKSy zUXRdZeJL5)cO6mi_Cz1z?ZJ#@kxFqL{gjn}{32Hz`ob9d#!F6$Ic3JIa^?~CYG)KF$o^8jQ|e=0_|$F*qr`+W$%pz#q@(q;t4_eOo;glvPtU@ z!dZ5bkZ2JK_}K*cw3kikz}H~VGD-UI?{Hk%Apwo)|M;2q^->7F)#`{l5T>m?rq~2 zo4knsaA=PW?(kwE!$g5Ut*r>%g(aV@aM2$%>BDXA(#rV$QYUnqlzNu}Xv!2_8)S>k zIEvZ!J5{{%yDoEhUNM>JG+DB^a64=F`vm%EQV%vazd%~rGjJKh;4#Dso4rowb2gdd zUs3a)K)g@a6u$yn=|!D&(s`MarQiDYm6m^f2VTyG{Gb_4<=-1Oib;BRT>N;&K<3Ds zA|ikAtQh6B3V%3=Q4?DY+Rwj%c3lccRBiFJAA|9>(j<6ht&A_w!-z@QZhY;TEq?IM zR@!u7i`1%YnY3b#uC!%IHDs}xJVs{gvyY)>O? z*9uUW{R;x<63S`SPh6yhvC;?_P79aJo>c?;c|Sg}!5N$RYfA&yFOurm&6Vb_SCl4L z7r>`$o&4+hb25+drWos-o8mQ$1~Y7U5gFqU%jyMBXM1j#BW+q%ZKM7NN`gEf)v|>@ z-%O4D4~E?9hhtnT!GB~JE*jy41Lr&^SDy`+9yntqy|(ifvFlRoP)tIr0MTD7rk9{BJ%4q7Vqb3EKsPFR^LMACd#2%VmpOOf^&WfO0)*sgC;?R7%6QAI>a&WvnA^2FxOT$Yn1od2ebLq45A6E5h1+@%(zQhyh5 zSq>j6!d!bT24^U{Vyijka7I~x;__Tk*TzA}^T>P!2kO;^P;gGH!3MHh0bYS7G$uhD|eLD;W656-(r;eM9ZxN4j= zRBo|C{TJAwwoXg9(Xaq|PCVnI=_7kKF%;9wOqRTeTq3+vR76S#43*4Do#pFxWC0X+W6;Q#GpRt84%e{Xm50i`rqf>>P^ z%{hu`i=H5HetuREFt(WdN!y2pn6DrSpL1B(Z4%(TAI6Qaf|8dbVa|Jf_^@{x6jc~u zZ5pYZ#y(mKtnoigQx@$gcj_?qEf>II8`(_T=*~ZzYZRkB9VC-{V@2L)ipj%WS3u9; z02%3YhIO1E0nS=KaQP9iDUE_}(v5H-^%CfIn_%{FCTy6y48M-)gs~fsV)R@E%U4~3 z;#uKPTDAtp4wK1wF1zuVyA+f7(n_K-bDG#n_XP>oF++QEY{@vA@2p$01m2G^#E$f+ zn>sBQT-Tok?#5%~Ompn@^f7!~JRL`j?SSp2S)ekh3)KbegR`Da$osPw+?@7>e>U4> z(PUCgQnZfb=i4Ol*_SWKAlz0qQJ)FKa(c8rC_t61h{tZ=M8Ld;)-;$rdEQAsdR6 zEwD}VYw)zHgVgX!P|f_uD^s?edkCRJE1<8tKWwqE!|faYLGZQ(IJ$8T{;B;C3~3V~ zIrMFpp-wK_F1DT)$gU?sJH^AZk$BYe4fx0gC&l1dIQ^n-hkuuYTz0@ zuiQEc=X9q-V|XES+i!*wqm=RVJq2(^e+N$4vhAmC>gs|BgKRG`irB2w!pFOt=d5qi=dAUK$ zHHD&I)g5*BagkM#9#85pCI-5rFm}~OC!Aq+JY@*-8upl?AO=a+}eAcjT z+L-)g&9JwIJU;T$2~Ybw8H?|Th}1ut@KZp*V^k^Ti(jhXTGwjf(w<7v_m`O@DX9FHt?C_>z&F8| zO{&M!1-O2nEFdNNd zgcLL8V5{(iUAyqoh-zY3IT%^Gyb)Xvv1X);b)eMqHlMTM9LL^0{s~@=C6JkQ9rV*# zwC1fjnXCVWtgk-@db^_FlLM9bm+iy$+r-3k_*#~m0ykusi4>#droyPZe-J+VRYex~ z|3xdWJF!RlEJnX8V$MR7IE+-reuKaWOzU*BR&jAG!F+-{f( z{`mf#-S|htX4dS>DgM3jlwoF4jMZvmX3xnI;hF1I#AMh&aJrYunpho0mu{~^7EX5j z!GrU;eb^v}o2KQ%j^Lqi$tZ)la>og#jOt(xN%zoZXzsAP+!s$b+lAN08l$dFHvD3f zFT?n7&&F^xv)MdZXl7YO)NI<(o*m}or&2q@wcF9#B30-4^)ine6uULbNOa`FZX%0MQkZcO9pcrs=W`v<@gjbJN zk}bt2gvXuSNy+L)Bu%@5=A4p)rqh*>F-;%u5vX84t6Zpl(TjYyO+sG{$3Ssq3xg|f zfs^VA@OXf6xv@8XH%AGblpD!oHp$+b4HVNd#F=p^OcKQORuCm)MqIZqj7*E{K+!X5 z(4>Tah&xFy6AtEERk|*H4)eGFLHg(7_?(S=RyclYl?TzWYv9=W(Rdg$@qb$oZVI@| zFgqybd9NK4`SqM=rbh))fcxyk+d<^dIyDGa(1h|Gx)8jokk<=v-VcU(IS{2j4C?jN z_?%7b?#cMv>DTZ;vIVMgZLq#S)p8s?&!aeusS`h;!ziZjLNn%L=5ldTTsavy?GoD= zw}v=VK~7M>W;l6tIT*gnftIyH`8sKh(>ahj_aNNv3Wc8B5!fv|23pnLL3Pti@J%(t zPIx%pTR>aG&Wy$!MpZTiq9`V@-w>wk9}(}!FC&)09;|ZBT%uTK0RdWR;4}FQczt;S z9_qvJ_zpeXm6Zbl!Y7b;A{*K_*ucg~zTovO2b|7Q=L$`IT=i8SFFhUzX=P9OXLC-5 ziKCdejRTp84S&Ugno`nOw2x{2B_KXeJwd_a6*RS_gB$w<&hECxa|ak<8}V~Ub+3lF z{`79GXdG*mHXMu(hJkH)UwC)T6pyH4caA&G3u+r{Jy6vaV&dD z{%oI2{2Q;ZtcwHG=KO+4>bh5&mjzn2w)pBw6YL$H3tb~?!PEF9EG_zq41JEmlNnTJ zBc}}~JWO!bKY85iVTU#UuH`XXWznQkjA-p0;VrR&WcBM3qA92&jR$73P2C!xuF?nF zm^VY$MiyS!jlfy8L;3e6IJp@Ts3O8MVh7m8-hr#stJC`4J}_SP8w}gef>)P1zL7VL z$ApdKr@#Y>`Q!1Q;LNuH5>oYow60Mkd0C_3CUp$sJW~RyJE@jd0%P7g;!}DSIKMRy z95X(G#mtsMQO$uKO%Xev$=ui4Nf zwn{H1o-6K?fM1^QecF1kr@jK26F)=t$}AWj<&3v~wZy7}3gFuLFYs4V4V7QV;ZZ7U za6(NMG@C@hZJY{|SW_52dpBIBm;D^(o(z*qF<)B5;=Cy-;=zZDNZa>SY}{>q*qr1I zT)U9`)X%g@;B&Zq!WAFTwZ*Ql3;0Se?j*fibt)cqAOOeyje-Tb-f;8gR#4bK8uC&P zLzHBD^g6-jbO9KgMp$>> z2tIkgq2v!Z{H%t}`tJBv%RGGBPXz`kM5;G$`iVd^R7^U^2c z5u0m7i+2`~&dF=g%r&Ec^#TaH`VTUlY1#Fm5}5JG4ZEm2;zX??C^{m?-$`daaK-;6 zc;elz@E^k14 zbPd4ua5wmT{SK}fFW~g833&2+M}E)_J1b%?nz9lGkM?uN??Qi)$2W&bE3{Rm6PD+b z`qbN0u`jFiYLP|rg<@hhpA;KvDhhO3^N7*_B{X1ZC_)xZNa5mlFl+q(@il; zuY`-|_q`*SI4_R~XM`ei@B3)elpd58_64#B{Q*b08z8SS5*MkNVeW=~2(@j!u&xqr zFLTCBw*WV(IY?)H*eu-|=_g%NJ4Bk{S_-eVWP{d67LC$UdAY6nE5+Y_sR*mma>;#* zPZGbdB&1g-4_+l7L3?Wt`2356(Lsj150szI5k8q>R#6U9@PGL9wP{$Z#ZY=mZ>7|K z!~$vM8C9u^N;WKVkTz zQ?DtY{opTLTlx{o+a|-&tNrnyeq|7O#RuP%EXMN_Uy&KdT&3*D5zKX@fYyD$1SyIe6s=o%mvR;_4rU(wl#NgKNE~uRS zi_X7L=aVU)-)_S<5;oxMZ&S#Y>p$of(`)iE{4-m&^bm~kkd-Uc$}naW^W5gM*hf89 znDYBMxiMxmX?x!2{Bdh@!UVq{BZ_F4vT;ZW*eYHB^GgBs>cSu07kqQ8)dG? zU&s>l1rEq#}!PN;u^AY7}BI z3NFRcJwQ!3>PJiF^ZORSoUuFb+CB4e6dDQ2i~FMOr*x3@UprWT#Tg!qr|Aj$+b$b4 zOff6RkCxW?{W|7Dt1?0>Mgmk!gNSIE;PR~u<4G~4%ST9D%yI-%P4dX! za8t(fjTQNEPr_G499XT2qZJDIM3=SyJLLQFJ>rU%_WsF&_)$Lihx?fS?PR)IV)?)8 z=FI|ip)7eHEW^y9m?vLMCHh;gXKuTgM+SJ8q3i}15^%nQ4Q|MRH=ot9$`LgPx-cHB zhYo-VhiIJv)pEFLNnk%a85^ZjJ%Q~boUuItvth3M-^-3ogCU1>_*J0ChJQ9oDCV-Q zhQ$58oH)fPpOjm+L!}WS$;O{qvl-7|a;g?y5xorp_Qb%0kd=@)?>LOlG{dgGk3lom z6<=|tO>BRq;9>8@VAvcFQUfL2x_lxex|{Hrw&6U+pJKwTd&T0q5V2ZQJ}J8N7`4O> zB=1v=iRz-Kz%|?IHp_&_N6#U%A|8w*pF>KJCEmL@9S)U`#72t;;olW>)7x+uv5z95 zs`oiM{nZrw{>aKovut@xAjKRz_Fk;Cb2DD^H3&m03cR+S>F3fZ%HEsG|CV(#z8;w6R0#YTBW-8_=?6gh$M4x z+WtVivT+Bf7LDbfjhze=O)=ib>I7Lw$BA!zF8+T!oe5M<-}nEUG*KF)NP~omG{{uX zJ$uVkAxfFYOx4FwA!JS&G9`p4WJn=Xrh1-xuQX2@siaAfD1?mVf1dmN{@-V<&svtX zK3?mbyYIQ@?6dd#&8;(f2K!#0gG(P43ppFhaVD59Pd7`_WXe0*X{=0(Fqe(O)SQQa zuGLU?vJK#nIfCI)MST*4g+GzKIQ8#24D^DzhXA?s)e=;IPdvs@~ReyTU?T=px zfoq0B%^H6J^Sogo=8b#-wMA_Z(Ov=j9KJyF-f`$TK>|OM3Sk=UY8mJ_31{wI0c)lP z;_kA8n4xZE97?rw`HZsS(g7)0Eu(!7}9zCB2 z4tvU=DEJ{*UGhNkJObJ-I$`|T%{c$VHPSEfy>Rv%H&DPlrWo}tb4C8yA)?z)O1T%0 zn_0KtqafDq7pv}(2~4RaDvWpup7sAw;aMGYGjBkC#AGBNiy@25C37cDX3>2X_8+_p zk{m{1`Q%^}PrJpr%~-?Hl~XRwRKTQDOu4R-C}PuP(K+WbPSq+!($y=C=mwu=a6>yGdEd6d0)tM_q8ATktoC~+)Y*8? z0F1Cs2Q!}zZu3ri-oD>xoHyG6!fZtN_~|Z;4qVCaN-!5N2`0j5UQmq15L;14ceAMY zaT(XyJD&WkZ6;RQHIn`c4~U!=>gFj>g2`C*8B@k?TnHWR;gAEd2wtNDdv zwFS&WBLUM&F(EofMQ7#uGqx3FoXwpVHDP)QqYhJ6K6KLVe7Z9<(* zwfA?}?oU8T+{n#|0=_d&6TjMqkW7pD_<7=SG|?NwPxj`85YUv3<{QOKuYM%z>SM{= zxL?NY8KX?@Y>Fm9yaKsCYdBaLJO;-(ui!S-<80mb3HrtF%2qw zR~1#idOn6E&z_H0jz-~;y|1{0_EsThGgOA@rWhr|7owg=Ml$n!%ed#i%E+vLKBTbW z7^&P*LVn)}h5jbAl8*XDNfTZ3zh}c=ek1T37LZJ(y<}=0$3EMwfC>do;?=|Ef>C=(sEd22jknM?IN7mq##xFX=_T zwhC)FVK@6}Mlta%OCaTK3Q$ekeRn)Dlx3hUq{CRf4k8r+y0di*G}o6f`O~Q#&&4t9 zo9VXLu=W5>8DK!fn!|&92P>i3NGLw75n0eq;!u9bT!H&E2k2S8XB0uY@h18IA zvAG*%jPgcGc<<#?p`6E{=?2;U#t|Z-QkXx~;NI-xUrCvV32G|r{@+eVI%(Z9j4j1{ zf72$i%2sD|l8ZTe3ngw$St?t-p$Ba7=n3EKdIFWlgx8(}aa5-=Cii^`XI5y#Nk?TN zXJa~XH@;Xf2rZkk#NTi9!I)udF;F)~KuIxM41^GHq?r1Or=l0OKSZPTi@613{;<0y zvTU?x36bVHCl-6dJ$lC}ts2_eUmaua@$jv80Bjtv1#BIn(BkhS2x_;$(@Tf5pKkO( z#bwJdRObVX%ai47O8W|!i4@}-a#@u0UxjFK&~wfuFrR&TDvFi=PaAX;ZbF{PDWR5Q z-prvWb@r2D%p`Z9);$e$Z7N}@$3e*LZHk>^?Aee3UtxHHC%)P>0zTEsK5O>+0>+(U zGOgB#l1PrI{7w0g0%UfAgq-f z8)O5~^@^xce1Lsf@fKpcr{jTh`fxMyqtLoIu%CdLOEG_%-9$B78KOP)h1~d*{Y<0X zai^VMtcCuYj@4yC|IN!))>Kzr7prTZLPTB_gwh7UO}0lQJKE|=N>>luJNX1VFXtUx zGM$7Ezu2Q`;TDuW8^itr#)o2>JBplo)nthbEeg4p5n)`_hAkxE!FM9H5e>1cfGF1z z;q0m1M-Qc=aZYXoY1j9$+C_LRVJt=u5TWNcMbWWicj5CbGxSdmhH!n^iNH}dnl%(- z{B@96d*y49Qe**_(OSx7H8zs-mhzBj-UCA$tH5gibI5JA$L~k`3X$e){f-I(e+8S; zCFu5U48E8+2G3^K9 z@=x-Ema*l&kryyhX_mmMQK<33K)?hwe}H?5U!le-7!!L>#Du$=*pREl4qbN)bcPwA z_xvOnwQP_uX`VX5r0u4dMENsfxm8+Bw{||4`gD$@d7lq2c2Mtv2xGmBgf^e}1>azHzYfTb4aUGD zHfUW^1Z(97aJN@HgN>h?!PoF2RN2a;S&nH5n3EK9GySx9x$8*Ah0o)heHb21rDZN*7YJipBLFgtj?)ePT1Ac*2LXR{D;`7KMDDR@lX^En_90Q5?wb5@f zJS-Lpp2`wkZ8A(8#WbIc6x&Y#rpNqT?s{4|Ymt3~L~jZtc~`zc_3bx8BW7mYc>MCr z6leFyfDVgpaJ%>wuH4;*iXkKL2bD#5h4S}LVA*c~N z7~l9C@m;u(pA~J%d*#$|dt7OAX1EOFCBxjK7?Z;ZVmYS?Ou)+=&Oh=!37j=cGCJrG zi5m6^BL2OH{$n{vdp{i2N)51k%0p;=ry!^$C=c6=>dmy|ZQ%&s_*fu6z}AzWY^u#) zxgHBcvi=Dlf&ns&m|}+XOc1;7p2XxgFG~6PC0KZ|8j4 z)A`#Lhx-5Je5NzJcHAib_^Ad?$La`_pOsbH1C*!hN-3)a`3%4YYH&2&Dq@Hr~>-kn9On+wT#ZSdT?{5MMg6| z5%XC)gz5*W0*sxJDh6RIjQA6YjaCl$a?ML7?PoBn^X>pk`i>yAumomDRSM5$o($7O zF@8Df5{K?F%$lNXuFoRtHnE8K$fcksnv%yHXbIk}^Ha#Kz^3||$ zVhfy|7L6ijJ9G>|(!1-2cUm}cV zg$$#xjCOs8&XDL9w}}o;%Hg8#&ScZ4%;4N-eUZ#x^#U@7%Of7{AYpk1aNt%oaagAy zNE#(;)WHYWGZ;707>7OT5BozFkvZdJnl>LCb4j7`8v)bUTUgV2QA|26kW{B9i2Qcs zaJK1#L}S+abHA@oVeNZYz`SBbj6A6eO^#*|@I?-$^%?|HY5i67FmiR^39Nk3>wg<2 zoe|!`pOfBvBQ|?w-y7qe0;Vs;#BX0HVRac%z9fgUc2X4`c3jAHyc@&jy()tviOT5Z zwFVCRt%JGSJRmqL6#7xa&2CZ-Lwg*>mZ&?me$C-Lo;@R`+B3M{qa4|YfHHU*s)jM~DbWAg18@sE2J1wRK|6&i zC(%rMQU62uv5tNa4x6KW>p~d0b0u7yqXynjvq|T*o&rX@moOSDiUI9OlB*eK)5zjn zZs{r&vbJst=W{Kat)|<+u8qAgkM=~XTfBwIQ*T1h_ZljwrHAv=p2PR{P)wx#YYp9s z82wlg7n?i56mul%lS+uyhj!uF)MyA82Z}L{rxjhHN@8WzJZ@UyUl?p|$EwVF%bKmJ zfLm>v*t)rvu4|Q$w=*3)pL_$UTj}Hxg)r6E7d0C1Q~#SYxYT_S-n+aXcJK>e+iVM% zecezPO{8ozgkt=zDoPYC4iwvm@S0kLybAnUB~0;DcjQdv-Grx)Au0#@!+ z#OZMc7&0~wV)p-sitp}%h-wcgEuePeIw7!9vKqV&%LA{&2pDr2#)V=sbkB=(f>p$? zZ!-QKc9_h1(^tS8mSI*=Os!^{V{_dpQ9wW;ceHjl z+v{f-3|M5!bS@re==g6wun;9N9gupwl%Fo^tDmZBkDxtvUfNcY0#y83u=a$zd~BqzhYh zHQ8uFD5hOilBP$c*4VrvE@y=XJ8P~PjPCWBmC73)d_cV-n&ohu6Kyn4Xr@P9c`8#t zyT9rC@`H#DL@=}bW?DafKF=p3W)B52g#<1Wym;CxBd9z&veJ>}l z(tgj(ke--H6TlCs*swG;WOr3&^enw2nAW1oe;fh)Z_)@&Aw!{Rh6avO^Tu8JbNE5o zg9Xe&*=WvCjPKe1(i*<3VyrETx%bCPh{dRZ@L^LJYo;TC_}+gYk$MlrmiNH)9<xN%eJ@Cb+WH240&-ZqB<3(CcaK_&l?sn_q$mFHi^4Nn10*m@`;&l_a$cgMYhxSq1xx&^oFN#=TKSsnCqH)T(3U9|&@NNnhazI3BLV*94B_ z?Zmb4`NcOfHs2U$6a=Enb4$Kj?Wgc;7RW;2CdDXLA9DKj;Sh82ZZVhfu#9{lUF3(^ z8n(}DD%SMiGBi+^i?jDtu*3Zg*z3|x$s3p8Wb8y}HM_-Om^^<(uLctAw-L_V0yPfq zLHpqa+*D1O)Ul@Q**v6}y-NC`=FZ)n??(mkw|PZoJ7!5L4QV;A_X?2esz3Fi zyBWIJEN=V;+Z(1s{l`Bf#_uA-zuC^p1y{n>YkwG~a4>2N+mBC_UP^}S3KRnRp{DTO z@Dy`gXR)ZZR~$32zL;wWc}G^K=8>A39MR8dABp);1E_kgg3`2|^QU@RsMG=CY3j6` zha=cElFaDQC|QtM1V3H(O7vnZvGVd^G#j@nEin6wkQ%xm!{kxSSItu*x0HA$B&C>h z*w~Y7sl6hS_b+4&ZsrQzM1FK6(w@TP0SypT{28>!Taq(aLQ0f-!Y{9*L_sGTY-Zn) zOb`#k>Cs2f{p%evZR}S8vrvX9r}$F-DN-D+Us;hOOyD%C=(Qw z=jl^J$E#E_hfbQbd~~kS8zR+*ZrP&-xkHbW$l;3kQn!(rZlHk|<@RCm=DQ^Ceuseh zEQ_>Sig{^sOH}jo60>S-F}F71IP>=GPBvzhGl^9BNe;NykSaSB{9@Kq2!Z5Y?Vx)8 zBdK)yK`MHw!l%v?WY$kr%v(8$c~6!8eHR_TM!RJ4_}3$(Z>QY_rQbD6Z`8oflu;BklWf54y5!IayHVND5Yyg zxZ19osl2X;e^2cD-%dx0fgVB#bWn`d*HfZ|uVs)ib?KsK(z1UDW<~uIrlBwnDzQpF8N%OLwvqn0);2hP+_4c7&=LpPUFxI z;M_k6q!q*$e%Ha2S+n6$l{GH(ej)xc>jUgw5{^%L1VY(bnV88$yBBQNJB_7hzx zIKh0nR>XbsG9h}?LM3y9pXqG&4_XrqeL+cVkQ?JC&5<~aT< z)q#F{=Lwkoio$66Q_OxYT-2p>ikZB)kkd-P$sPKs&Dy5tkskl#Fv*uT#oVOc>$Irv z_rG_-#mZ>$SJ*-8JOYn6p*++txyFn6Tkmb`3$wo7RVhk59cG^=K&16OuaNCZaWxdnN znFAJ|$ZKlUkUsSd=)C*~QbQ+c2uLx~Nt0rxj+un>cD{!Q$uu0jet~%9bE=2yx)1ZP z7`DYI38TrA6Gk(ZV%Uh0PS2PaX7amyZlump;(B)}F&3*q$zLi0{H_st?3EXsmZX^9 z9v>j)%wL$)se-}Rrl6%qE&QbQQM>z{V7I%zfpsnW(e73j47xANa~vzE~Xw=LE1>!@j1 zL)|aq4~{~U%~#oL%gf=^mvHPcggVULlkK5%{zW*;C8bTH7*WhHr|5}Sn9-?u+>5qd z?5sRBlKS}~k(TpFpN-UyK4YqHW=OfP;^Kt`A zxk2KqoQ1~>*f3TmF`+MeZ#GiQleO2=l%C&aE>6$oF18(FLplc&ZFdc_a+fknGf<@; zf5VNTN~qkUMwql?GZZoWwhs2ZHyb~E&H>Ho!}yBNz%TmGkoQsR#s3&*57{QM!f1BL zFgqz`zE*m-k;Crk6lK>^;A%&>K%0$c>|?J@4?+Egt+CG+7&qMz2M@!y>H{%bv&IQXjR=_-!eFzRvOx>F9wCG_s8ULId zj(>BGB=6cG@%$A{q~<5mE&tP&}D%krbKvu|8DBP=nM;df+i2odvPq`1?e~0pO z-3Rg84Eyj`N9yq@@_S+Z<1zvBTv>QMqbMdT>0Mgj-|LKfU=CN&UB&#Tv7a5UHb=mO zyl#ejH_yY)pa^jIuobFTpM|q@gWJ4S2en_##g%op!13%aZvEg&E?@Z>H*R|g=REZ& z{2Ev)V6@Z(%z27=a7A9MkbaG^8kfVl>kg4zVunb9Mw<$l4&5eb8t(^u@>sa?b)cY` zvLILvm-nNN*$Wn+nNbSx!5-}B<|k=4Jz~VamUc<5or(gtOS0mmFxkQ58pUKE?@l{& z`wEk!p2PLHeVZM=HdxZ_t|&a4JaHpnZyUHX{u^<5#uMLwL16Fw4;IPk;ET4^xZ6tt zU&230whWacqmDN-J=eYyD{kKnj~iYHqnRYz4&I@d8(9Oz-Tf{x!`@|cBZ9oxvKwBk z*PZjs7i|^voYMfsd>>fatB@3{9VTn~_7oNyDMlkZ0PlUwhXp^6lMDUSV8qUD@@D8Y z@^RuSxOPR>8#P{*Oi87fj;_VxxZQEgQHl}!yY#pu7VtN! z$i?x8h{#?Ok{Uf6polcq^)a)af z{w9q55D1b27q2+R-afU0*TDY$P6p4)$bGz5aqZN-~8um87^l5VD?|9yVE z9U{GC&&FSNBB-R8#h*@#Pd$rd)+yz1)4uOy22j6PXXtH8i) zB3wyY3oo92gIEV`Joa$|PMKW|HoO1BN$Q6%!vL^x?_|s^*+;#Ex`ff}R22fckz$tV zM~HXBVP;wH9B%f>k)&%_3fsWOOZI$IMdyc9UcV>_LX+ra$?Eeok$(%!GCJU3u@=4@ zunecW(+Y{Z@lcg_0CHWAKzza?nEBxhWN-f?i!|A2K2nU@#$)2scfy%3E;(G2p%VA~ z5XWxyJ#+CgMn1ySiu5VR;4%o1Kg*2piyq-7?r#oako(0Fw(Y|1-BL?)9Y zUt+45Url>pfZam@VKZ5hCb~u=$gW^-$aO$@%xP!G&?^6Y>REl~&z3V9;i(z6+f`C~kdvD~H zQ+dOyPsBqX?_kWka=2|bkHLb4>RgnmE9a4NP5I3Q~P&c>_g3=T=&0Bfa$6^GFK~2YcZ{l{ZkmwGo)d1E|@P zCjJhhhJzz{@Nt!4R>>BdJ`{8D!nd^UW?yE}z+5iI#RH}WUu5^iIk8`;g}eQgV!_Ra z>Zf66WF54&b*AYS z2b82HfkT5S&eSx=PdkTTj_yI_Q36KKfk;}X|{v~g)HwFqg0O*i#$#yXl8*g@+$jz1^f>i2|0p||XNBchn# zbaU~jkonA=s60+T)iH@Eqo0YaX|6o|5Rz z_j8iw$w{nQP(O@%R|r?f(5*-AF99PpLR+O*4@P(NF{7c8lf*u!dJ*p+WwbWF9!rh5 z$1CBtckSHSgg(3!<0gA=W>QSu$HQq^WI9vLSNI5Opu1dWO>Vcz|lnRT@wGtct>#DxI|F0StLeD>%V|1|GUk#7{FyxItISZIGvQ=O{ z#W-h?w73})nah#+oI!>S2{5|P-afsOm0G;UXx;^>vtJ|A3DOOeq>YMeu6YEnCn(_C z!LIyyl|ejwehpuBG;u|bK3HI*j$0j!`BAZM0)~-|W(CDuI%=5u>&jThpq}31IvA3u znq2n!+`a5?pC3>v7X{v(YUsA-D@fI@W2qQmL`^hAP<>UM6o&t8s>y3y>42n%I(RUp z58mh0P^Y&XKX-+lfaxp4tfLtDbU(+RMpjHXP3gG06fkc#-)4{Ser#!dHcb3C7pi8f zWAsvbK}t8LX+f80PeuWkyx=W4bMPK} zWm$Dv(^uz$p*DNitVmV*PfEU>*l{kd{9w>}W#w;mPj?_mA4HW;Vd4~@UlME}eb_&nw^{!wy3DJDXe7hoyI z%KNC(VTJi3vb%ue%2mm;3sn+@n-WIn&|d1;a}G8&>fro&uOP0h1oT3v*v!+rV5W2u zcHVdlk2hCA`BZf1@Pwn+J7J+=KTO#53~nvjg#&!%3zG)2 zNUNckKLgi`wnY0mUD}n;y%@QO^*Z!h^i92n@lm1I4SI5Dc%3>d>AZjtMk=3UMxFb< zLCB*bz_(_2$?y-1{&a*|y>&zSg&~;p{R%8I_QbabYlTUxmSNsf%!f(eoW69Pcbc&{ zpPM`7EH~D$NOC^5SRA^5YIaYN!$sx&(circvTjgC|JuQ5)!6~k`y20OL!7#%Q`;TICsLitXi2=c`%@-u&RfZ=6)_}lGu`?b{sM`YDM}mvrK33^ z8ID8tw}SMV=!?}r%=M&p@bNPtI`J>aoBV{Q$?r+*<<0nRlI(7+TK3*3t&o=svN-58 z)a#Pd>99QRs?$EAws;NOa|3mXSNsV6(ci(+!dw`Q)GOlGW?NJr`4-%J)k33#I+o9p z!v@11@S~~}4C_8a#=4*6?XA7I<@+!p1ZK%FniO;Goth|e|s0# zCXi|asxjRC71mB0iuXR02?5=;+5z3`8-cZX1Jj2p;L)vLVZFVWbaxJbebXn=hA}yI zR8%OM1)B*NYZ=CXV)8GI7b!HYby950<^DYJCucsyOAe-uB5qxs5Oc8uVtZL(MO^uZ|J69GW{@;9Q>$SU0E{ercWMV(qNBl3C$g_V@~JAw7pI)S97`Wc~{B%>gkd#a{GwmuD^oWmL%Q^rF{e;(+lBX)oAQk@*30+(*;JU ziRRUEA=SlA75e%LZa{ zZ5MO3`V?u4p()iqpJ3bub1e1Bfg~#yGUKcujE%m_T~pK`OB3TyYsez+c0~!mhfyo%kpV%6f-p@LKIn~B#M>G z;eI@cX1i=xkzq;qh~B^+D7D;^YTldEX4o_5M}b*LK6I}rfta9wa463JGaTMQm?Oih z?#$w9Esk>TpLBTF!VpxVUE*@|S0)>c7sbRUg^E`8w-EIT&*luqv`My_oFS7>WD>tK z%INdE9z3rlfa)MaSlV1gVl)rK5T*!L>M3B)etjwpbOVV)RN^g5dGN3iA2J zCekNpBt+lKhg0+})Mc_h?v1a974kg$ChsKKpc6@w`LV3R=}kDHRCba+BztdsDds}T z0+IiKC8G0TS=>aE>&$>7K4iS=9nui1j!}JR23E@v9v^u|0uD?jTJ3*HM_4XY{Zc`- z8NJc&T@y@?;+egQj_}dX3^tBo$eLm6aj%I?rmbGKrUg+QmVMY;+>8nvcL3YDlC;Jd=r1v1@_ZZ-au zgK1oUkej3qkF~A|o?fL+SuifBH}XS1L%TaiYj7k?z&b}-Bx?ar<%W><+6{QsMV1{5 zlC(3$_%)l+WRK=nMJ}VhP&Hf>fv*{I)vwuY* zN}maN0oR`C5bb&eR!`mjzl$zu&c?QDCr*o!)u-*2O6WA6BE0%n?QG><99qbXZd|Jj7;Ov&UtedvM_ks-;LbS%v~*c>|? zvmwSk6OJb-qEt5LUU)9(&|+m!9)kV59z%@cbr`tS3twIa9KJOOJ0=*RwzoYFeR)N| z+?B1+=@hdd>y$`&s{*q;kB(+|G#5R`nwy=pjkTL>fe|WM(CVKDC-UVnD53(SegtmU z(qUAx1-9(C4Qi&9kSTG&HC5Bmeb*YiJeM9I?-<}xQHiisuaPaC1r&3kVzm={?5${( zTo&hSev=iAOJi$R&yyIH4#QN;g5O1XwE6!JRL`mq8e>Y=XF%fPVYu9M35;ktK=q_& z;27;$Xd@qldm;_6YlJSQv}6bvMcIYq3yMjcZkT3uCP$QfD2p@L7{R4~^x_6ZC$gE3 zZE=1VHFc)S$}uyk9(Qz^a7QpdCkt{1+tS26y{{>n2&a@nF`{7yI#D_5&fn#5Azc|= z6X`off6rz2H}w<~WF46nWp+@cVwlZcw>KicFX*%KI|p)l?V~XLb`ee37sA8*cE~$d z3J;&tLJPX4O`7O{JFb|3N-qaEXg?Fpn!Qopb`|oLw65^T3y8kZB$OrO$!?=sDduk3 zpVS9G=ZKysWpf{fq=3e<;T$_Vi*;Q@JGazIg_8IV=T-qD%?>8@Er8>D#$dTtIJr1O znGEu<#if0x;-d+xaP@=Un7H^MX$rMxrK7pgC0u%aqnMUzJE!PrR-*qfhkNl!muytc zU~RVMu;Y#cy8SGNqy<%AeE2OmpDqQnFJEDDSrIgUcEstT6wb};1b64lFsvzo`a_$NfEYOhq@ z&{%^?9nwjYYIg_K6u{uYj;Nh6k}q)X$w$l>i`S!Ppt$c0{O?Z}^ic2QdLNs>OEDjQ z3mDavREfM_t<#)YlblYk$mPac2D7tC6x(kw&mPYoi;V`)1fdz7n{<~+Pixc7)*!*)9-)oQ+|4?TfelzsIiw_X37kz?_S^arVW4(YG{!75=2vz{Knz>; zT^FTIOC5TxFnZz(a854=qaqblSRDp;Y3+^j!{z+QgKE6J#{w)}?vHh9x_ILA9q?WD zlhb^%M8Hh{E?|a8F;j1)-Idc6XK&5p7U~;wGfFqGTJAGhv#d7Qh@&9XrVUCxO9V`y zc~8s;6+uU@a;QzUf+=+Y_(eq-|GkcZ&XI?>CxJ2__W9ogj4j2qB~BAB z>9P~Y-Ol6WAB^VOd~Dgp%RWgImfQr3#v&rMry6p(5VAg%!>>F|9IO0}Jp6YGKK;w* zBEuoff`8v2XB!VoQ3_T6Dg*4bd8uPv=+PO<#A>=hH%UNtRZ7ponxl`(}kHaIwYx2 zx6oNEZIZP!)yDw2jU>fG0oGsm#MDJNK+@J3cy7x&)O(Z`Zvq@Nu6U@lFD`4tmkv3QQY-ab8RCtAs6Z_|J z!|r>q=Ih6SoB|<{apmNILL?crR1G`RGQqjD7&cJ(yvIH-iBvhMbLD+TGf@P=%|q~P zu_wA7cmau$L*)5g0$)vH1Wb(Vz44)#=B0flY;Rprn0+2+IM<(@*R~Swzp*BdS5**; zuuL-Vs3tbf$%L3Uh49DC9DT*AAgzJ=|F=&@l~n(B%M^s0FW{r6neg`sgASr}(!zcS zk+z0n%nun#bW~4^O1pBoto47{g$a8gWaD(g%lCjj8wWt_ak`P>G9Ywj9t3qP)_hc)ng0N==(dXvaJifx z4wgg=I6;l*Mv{!eRglzj2%2vhpwxJ?T`3zL%(6xu&qQdl_k(opez+v$6mIud!JVz< z`0sup%$(UG*=`X5`j&fzk96=?VKlob#@Wb3a?#9$8A31e?RQv_qHb%b{c@0W48KX+ zNJ`+zLSyXfnFVpzGNGZv4mFjlA*k#mOw-v5z2=611ND%au~`EvPCNiR@4@WzvTNjz zO}c=2B%8Ddin($|NpiAd9CNKBhuhR@4ttX306BP)L}buL*n$?Y9&e7)R(bcA84%8o z7IHSf!*9dpb^9?U)f1gf5+U?SJw(c7LCU^IVo}dp=Kk{I0%q$^VKgTxCg^mP_`=V5 zjNxRe{m}3VOr{TlutHUknxf91_z9N$vcS|`Incf38Qfmtgi>Rg(Y!Eo%mCl^ZZP#Ggv#KQU1Oc3&*VD}V^&~wKtzG4_T?jqFb#Y6Aex7mL- zhIo8}zYqfdhq+EM#ZUXEOH$H5F*2l_^JhJ78*ef$(gm_`2{qw1hN-ZbOz{8Gui2=;DwK zeLzt;ow?k03zSo>81?$4_+h|d0b?k`h$*J-%yN-m>NIB6uuN{`h9jcCb^F*~&crKc7Y%m;uqr$mA znt|IA!URl$ECjMBrY2&K=*;!;%$?C0oTl4DGGlrOyRm&Zv{EHy|5dfnqlv+t_sSq% zuL!O-F}$>)EUv8tI_1aUjq?WB@OLShIDbgvr7|3LTY9Mv|f1yEB%}?y|x^xdq0Qp^-jFbpjL=beF3h= z?9rThuHHG2%AMpRxv1!;+-*lS{=th`I8`L;DHO?;&T5KL=?fyKS!0=pC(=3NuM#fd zr9Ao1su#_r(Q=V6x_gB*F-(r4Xx+I{%=!AKoc1C{VwNzJZJa9y_ewrMXh#L~ zHWuNvwLBzu(JLdLN$BHM2hvuO$5egPYeF9s4f5x=l@8`5<%9X6VL?3mi@|O8)(V&y z*_zf)F{(~=PW!KqWX4Q<%1!t%mhl;sByN9QLrUL%1_i3cRna{h9Zjx*+m{pYWP)t5 zk*Zyv9O{N=H_2nn``vu}cuU^usxe<1xQ#!0g$kS~?GZ3>9l|Q`lVa+uhKK^+*fV?6 zcy5vUBeJC3UDCPsIq9$131&gXuyr0asOQ6Ac>O|nN;@K?IUD!XW>`EIP_N(>?7thr zzZ<5*ho^ONMUKn(_giP;!Q-+I!T(_tR>{jv-m+ixFn=V|v9F$qp6|Xn=uyrox)}K zblGuXG+#dpqv=I4`eR;*qFu%@MqfGZ>xHf0`+7Dh_f;i{)2VHkcRtmDEC%1QPTJ-W zPC8l=p|qXWJ#~GAo^gHg((?V#isrme%^WRTNZ(X6(?HdJdkFJQLIFs2k!mFU8ZwVuZezQS>Bx)G3_H;ks` z(j-TQ(5}104DfQ;2&U{h!cR0|wkPOA(Jmey(p%j{qIWbmKMNjY1xv<-E`zxmBDm?2 z#N2e*h#Id?3Yf%C!lYSIjDg!)CfjTW)AE$#?0PJLix2n1UNdj@L8b<(f8n5|hbI_p zy+Gs^rZCdJwGisZ8h(S`dotxz^=c)kD0xXVX4C)gG(fxcY3Ap|)tI-McIeUHB-v;j zC?=sGl$qjvhS}JQ=OW#{z?{3cLHoxE);mN874D|O?o%#cajc4bKIKGy9%~?tU&SDw zsET8D^04;C7Wk)gP+~oHIjrt85va-OsN z`H`&hp>5XsM}^B`^^E&Kcdn4KQUg>QPLu2Z>PTou8nmTpV($YtVO+vNXjx?SzZ)p& zZs+<(H>|0aEjF9mg-LUvm~7QEOsmH$#{NFfCDF#dw%m{4_V58a-hBXi-oFX952u32 z(*@QfX@RuVYTxoS=<%r!7G1gu3s>HN_ihr1R*3jtdPr`)HSRN5EsSPmtAO#Om^^Zh zS@%bd1RFo)W_de^U6#~ASN%QqZ2my3K7S3qX|0D=omgRyL*Lhg=`i77i8dWe92N{+?x#w5VJ#UCAJEsZHCwbd)Jbkk#m_7a`>}(pF1WW+M zWX&JJTwqK|%i?F;yJl4`wlbWpIQy5aXtc+?Ke3>&=^mtR`VQ+l&qIvT6A-c-cdV&{ z%o?z=xCqlunWD)0iGW$-YlchxyNSNFtV#BHqksvanD?cTq8iNsNVurUpNSpIck7TaT;>K3@<8=aDIG+*wxT@6gSo-QJRENHW zdE2N-dY{Ww8LkW(wF)8IQ-mY(<3Z@+av%12uZr!`JCnllum?#@WcLw_@dYI)r8 z0y)mFCV(4tH=a|R;LN+(q`>d~wXjuB4f8H1!{qrbAWaR0Z=8fl_w3=_FkAS0{UK^z zU4-jdE8OVoDLFcJCZm$ST^P-u*TQJxDdx@AnUcFh>zSD6`J6+5DK|cB9`|li8h84P zBOgD4da6*R%NfB+7=89Gtcv?A2x%rNxZsqkY^Lq|cZp4Q3f^y7f=3euNQIl7f87_fyUmI+LH^tnoLD%S zUr?*h2NoQ~VQ25NkE$!K1RsjL!4!&A)HCOyf|LNW7jLNPZzCKPT@ zbK#czZR2*t5I$ZznRXDhK*X(Y0%oebBE|e!ku;;kDk|$QH_C* zFoHIVOGk6CmoonDx&ou74#!#J!}u=>mb~xDC_Hn?2xrhuaIZP%z(&cQx6IlmU`k#J zm~x7-PP!#N(3Qyi5tVY|@+Xo$OB>h~gNAc~9>dUUuLmSOZl{&Q@4-+KVOZ^4Rcp0XaVvNrui`V&IW-^S* zxS2@{S>@tp)^ceF`|DRPbg+|y`3FD42sv64ec~Prd(sO(SIiLXck_Bq;qSDa<#@MP z{1R${PVF{0$6zmn7!`9DZJY$mBN?WJVrt3?#7pbXGMbmmxb&|^-0bcmwyEtNTdGkG z#W}8|v7rN`)elEk-vy^vTDaX*4e}((aJTR$r?qX3q|x9iF4;ui8Lz&0+I=R3L}_w^ zr?v@^Hdz(|9TfA=tVRs!Y6BAk;MbA?e{tb`0#EG(}?H{s%f+N(9WWzy0ufN0?B~W7L=<5*JN{ z48M3(`D=}G@*hCH=`?ALV?gK8CE@k#CyO-Y)l}80Y=k8D>KW$D#&YgRfIes2LmoE# z8784}lpq%{EbSD%u2VQ)2>vB^;Fg{V8cc{LTYi5g8h6u0ld7k|0+X}I?;MPF?XMwl z%5Y+HWjuU5yi35Wej!Af7R8LOa*_P0y2^|^P|mFxug{+MvxQaOts*UtPsG%_oRK#B z`PAis@rK**or=s=`sa{;s zM>GTV|8q7fg-3AlsNU!+DT2wLyCu@UUskyi<>+sXY&7N+v;32vF!FhaqLw4!qQX)*+2#RU;4v|>VJ><5t<=pb|$Jpa*ufWWEOPvCictM86T=09) z7vqLyK$gQbV9t+3vpKP_vB@23(q;&orWw-?VEmqDc%6{~J+~&XCn7h(vPFx8y+F7O zGnQfurtXzgFP9@-aphd|kArM{O&BC?ydz2vy9|vN@4?#c0T}h`8BonC*tB*mNzTq9PgZ zJ(naTQ<5=KN}7aBrM~BNU+eS!t>0@c|M=&z_POVtd(J+4KcDB1!I*I@Gmvx}+@3v# z*AMl0jL^zONsdCA%iH0v)gF zaM1c~nb4S_wEMqT*nGkh(izl7odzd1!Qlb9ugL^zvk{-@^86SNQ@v-SEaO24+e6Nw z8)u^AOE*x{Gzx7v98P^$_Y#Imo~2i17eN~mz436({cP$WC4 zECF`k45m*coB@-ex;*A|F^}0mFggwS+2&fZbU;}pZq*!#oXfTF_X0CoC_O2Zp-%Fj zMdXZMKzlKn0xN7ep_ZypgV;yE2qv5gMz5CD(qmp<#Vui1A-UL^Xsi{$n4z&e=C26j zMlf@tq6F?M{!tM(DzNKjeRS<~EuNP&1rnB*5#8=|cu;JOmG~nG@ID^_BxHKhW?O)NX5_UIODN)_@gkUGsdCgn`Fm=4csZUE zkqYC(!tm;wCLmO@Xt|pOga797*}=HbG}t%Uf)mQLzQkR#jJ*Oj{5g-ydZxIZ?jEFFLT6gq96!itT?oOv~oKptBPdJj`T zMSmumD83U*+U&p=WD2m{4>4}jiaGybEDQNTizXP4VbYX0olG6`e2HD}9K$h{412PF z76^-z;uNzWv)%@++mi>CKQKJ_IhBi^&<$}d~~RTq2mm!x98-&UdKV`=l6F_X2)=TM0)x&>$>Mvdm5g2l8Gx#XkZ0 z=6m2rS#jofzr(~KuVLf^Gc>K+3sw3r zF}U=~vOe@GRYr86tS7(62NkQ?G5zB~zTy`o;50B;Ym8*JU4s+1dJmrU8;O6rW zaf6%;)?H}D%TR0fq{7y3n#i_47;Hw8;?d(oRneOWp8M8=v&|MHH)%iWuH40u`#Uar zrWChP&4-JyjRBRfqG%NIcuW?-q==>FJPrw`(tV3Dx-$*$@lwQ3j}C*^+G0qE`SnB^ z36HooD<%02)W<1}kf_xNx>2skV)|C3GXX4FaX7q3$Srm7Yc-c%z0F<3TizT}W+?-E<>F!d9B$6QWzRIJ|A4u)`8&ypE z<hjV!~NXT3^j zU~xLku=fL1k06?xFqYZ1Xa?9BJcogu%|Kmw4M#IyLw)3R=FSOM7*tvYo{J{uXgeAF zhxvo~Xj%v+KYxp$!E6@g6IO&Xm$d_(;>HeJu#8>1Z%sd>XE5UVQRnFFLGycQKiK6*RFmJbf6HKe0McEY; z;p(qhu+%M(4)r?CKB^r>W>qHKxo-m*mr7}_tBE>q_l*{&AHKVOg{0Lhh-;=JP!Y;( zW5#~?pt=#h6z^tc)>-_A@e)PTLojll#?f`<}a94Yyx+}C&7)ZDgSLhgwI56-1Pr2*I9nh#I}4ZDebqCx-NT z^kHBe1z%E<|36G}nKnt@r|?r?NH&j=Cm43F2jzVwih6RW82@e^Maw%sg3k07#vywm zl88i|S3Ck4XK`(ibM>!T7BQ0qe(o}n! z$DGgPG3o>ptGk<8I4hAFa+=7ry>G@2sWA{S>wqB5-2??mKLXRwM@84Gm$PBhx7&~q zmI}fq*-J+AVAu|#+`sE7=&Q9bgKjs_#A(E&TZ)0Fq0v0%mk6UnFnNiVRPaAcNna_( z$)}&=m{~!PdHEJ)U}28hlanD~<$2<*(hX(Kt>F{DKeLtZJmAoh4MypG6+ zJ4^$g8ame&iri*wgSGfLkNNzBkH&~#9LDqu9!{&Kj*NVPyWEU8>yjf7nyEteZ31Ex zkOX;QNx-;~ZN`!(L_i}Myl1Dw4sz4cn?T%1Na?lZr!nY}{tc)bfcD2-@&==S?HH+K0yi>5fshE8+%m&4ge$K?7`LMc28RczEft2l; zVEif*Du(K#>V1zuX-hXa4NONS3)0~>sT!igu7g^C5Z-Me>hz)>^B4ia1T~z?+5Mx6 zDmqkxW2AJsZBZ@k9F<2u?kzg8b&12NW7;5H~Qe1FZ9uFp`v%e&l;{}_|xVja25Iy=C{M#>wgc##m zqIy023HEf4sH0zRhj0?e(#I0e*_oP!Z ziQk&<#ywDXXFF~hWsR=}8*`q&iXiCVGm<|enIW(&b+**Gw(i<2qywsP#(@fZ?Y;+bu?X*?~{ zh)Y~pO7_czAm=2GOy4}YKL7NVwb&G|SI6m`M2_C}mLD8~sg_9BcA!T4BI=KP-i zkUF%b68k9T!dmN%^xY%cq`AzD%c~}?utY>l?`{vd=(-DaYr3Fd%wu@wLVP_WeYn_` z8QhQ8Vd!JqXIPpSiN;Jag(5(vx}mU8K@&;&`f-Ijl{kBei|AxTGnl&WMdKGsqwh7EoU+qS9&`0Bk2y;) z;uo5-?~c4qNz}i>*Bjp8=j3~S^}-o;ZMZs$>5zgHQvU9AmUQEr+<|$`QpjWfO%-hM(O7}g#ujiaSVIdf#S0u7;dtL2XpNCWA+MxpYf=rN*)Gd9tX#uSXbW*e zq(-Xkm8Kts1!s(LVu>=3DH3542_{>nJm+~uG?n-F72fb65xcLAXIyhF>B@r_L2Twp zfoFL$s8Q9hY2{s_JEV*XQ(|cOY2je+@|MlLTgT@IvP&%xyFwAA`t;HoO4;0U`~{q1ri-s3WSQ zj*|=MSpr*7P&mhGEOF#lfqw?p=<3C9@LF4xD|~R-MttGedN{N` zotE81ayDD9QE~fz!P(Exd5rrzT@(;}i7rf40L^DAjBel>;>7d>MKlm=-luQCE{bB8 z-r53FgD>)!yP{|+31-FdV~lgpW2&vbl9<=uWdk>!gb(TG=`k`bwBxFUw74cQtv~S$ zTsPf;7aI*wNL)3&GFJ=&4_sv!sco=XHVIJ*+Q=)l9lXmD_$eVj(7$h>AncTn%>kY(w-I*)IxD9dq8brLf1(12M7<@v!9ZkUuu zUq$zPRnXepUU(6Lc}&K**F0v;4Svu*63nFC5zK+qZ&apzCGI$Kfxd1_DpF*;=<@j% zFk?1?+C_?J(aSto7ZeXe8%$74|6x$|7QmpD$aB4-@+`6^okjx_B+=c{kL+|(^|gwP z;W3{QcuWVuymdOkoYfmbcmAos+v~T|jm-t1q-IRF$De`dJvYJcw;GRWS$%~sfDztC zeNfvA+g4VC*`p9Nx-<;68jy8vNE-xr$>JQRA#`n-C}(3Y!VC~h%(ETLm<7XVx%(CP zc6E%UA%FWPzm?KPJpwdsyomXoi6@Fd+! zHn}qEpMi_yB|c}9{O1qQxi`RxIQ*>eyNL?Y7NBX^h7G??{Ji>fX{}|?L4C3o5>9Bj z%REMzU@ioelNFmd%SC{eqGRQ%MD_w#G)bDMs6IeJIVY?EXt9WjB&91>wP2qq})e%7a@BWTZx zQrvczQ~+yC#s@AG(DG~ssNKj0D$@idmz02x?R6O6HJAHIG$Dlwmq{t{5L*$9Hot#I zZ`*hlC%x%_>sO!B?CTw@V~-Gqen0;WsG2Rjxv3A#Y>!VegfLySB}N4x4=N} zQ*y6Hnqk7MkkigmkkGvcr+t7M`D{3^a9LAi!v1?Q61gU2uul>f;@#0%Foj-Edw=+U z=Np0O*-R#w6PAbynf04$DR_ZRX!SXg8BB?pP~wzsgdO1 zQFfJ-f9`pN^<9p`raQ#HgKRlM$?o%`CIg-(47@Kk<$P4Fn81Z{=b^W%|N@!95AB$zUT0E@9igE0N!hY z)V|z=f#_)XsWOjfrb?jdj55fLoQR_K)5!JEcJ3U>*K9Ev$I0&t=G5kYg!Mb)dCas+ z{1n(uFgnTq1nV1;s2Ot#u#@2eV#3|V1jXgicDkgZ`$8dnqjZs)2XVYiT@5>r7^4M~ z#K6;_0^)y~ptteFygqC%msUHPOPDUld9@$m+|YYS&AQ2BlH+)cC&A>;dMRjJe2?mU z{|pbM-?ARFJy@wMC)(7KlvI&Ef@4jxX!7sXaOtBG_^GJ!wS$LORKSitUG#p3AsTgV zGiPKrh!c#HaC-U@Zg-LxLia^STs0BKpI~C&HVB4$-=U03pW(!_2~gzh%<5!%GeIFg zK<(XA&@_2Z>?cSMj`9&YtgZ%xX*(h2DA9*Xjv!^&Q_Z;DY_ZgviZ97f0)lAOccSa@ZCVAmfoSR8x-J5 zpHld;ID{TnS;Csm`wN{B7zPd>1KG?|wAfo$CRo`9EPsClO;SnZ)4mwIzr}%D$rski zx|;5~Y!AI(GX&B-OaH^15Di)!!K8OaQ<@$RD78}s_|Y=bBbcrXlg3Km*VZJ_bu$N~ z4z7ianHOj=`fZMe>rklkeFyS;tH5Wf62vQqLzdfA=AhzQc-L+Z@zGBNN*~tzhoLU= zgLZ>p6ec{Pdh|HTam;g^Jn8|I)kcG(^%yMFvvF$90HG1u%GHH*fZrj?X!AdsPupn| z;W?c$dWBsKJje-RHoI>E^Mg*X>g(Msm-=P@Vb+NzbTYx*)Ob$qHLRmg#7IPvqq40uUI*>@FLOL@zxE+#I zM0z$J9`pahM2J2F83gmD<`wlM<~KFPtq=#w4AQ%MKY)*iELNga(8M+Oz~s|hxU|{; z9ibxWZkI@b9>s$PG)3{I*@-2Q80a9^I&+AZ#dY zr&fgT4{m1;TF9VPJn(AS1@a@RAzHGR*y`2L-iLd@ za@u1E_Qw2%%02TCO4JZ}vkNhYVtGsn!OY00q=p#j)4F#^_v%wQEapY(1BSe0ucZ%1 zq(Kv^O4kzUk0i))JqMlIC8iO)#E2EGih7WQCnx*50SUx+WU(6y8CLaWupodknT>_2BNWi0obS;om`PG=>P$p2=r; z%#co9bjm%23O?%1V=jjAn0A7he&LINsI=0z-S%Pm7|K7o5#^IU>LWxcN%;69#CJhv%^%j!L6^r=p5QUv z1cS8PtXhf$^j`Z?{6Vc>Klq(0L| zJ<45h?6n0-&?|!auQo8O{{~WY(S(e!LRROfsME_yg!xM_xf>&LlrK!D{RhghZk`&K z6`Y4#Z|%f`)2E=8YjIF))dSP~HIRAYbx5FVK|a3`mMkzr$K~@NjIJt>M%#ZE5~c zI9(Kt8o@mMtjVnIQK3=gD?D~#h`=gHo_kAF$pZssp-PuTFfAkUQj13u)qWNZza~OW zh4n-&aTdxRPzQq%&p|5m1X8=IjBM7*pqs8awE8q1h%lVaM{`$%8BH)3w6vI9#X;%< zaV^PrU3NgNgvo;8-o;fo5G*_ zpRnJ}@thE27|uT%6M{JvpPTb~Crd5$t;K0acf+y1DuV)O$@r@v^7jx1uf=Vd~0bbVRSGCBdwI>6%k9 z^#*mdstzZ{%!8PaNW8(^2RBZeMeO$Ofu&&w+@7w6gpD!6;v{+=N!t;-y~xXZxRYxQ zxT3UO$mLENY`QlU6%zr?-G7ZZ$;kmcCh8;~jSa#4`Jt9`*e-&~AJKr@s;X(fx$)Rk zIt(|Kk}k;Iryym*cR2Y*1qsDWWQs{0_~BSMIYJxhHt**qBWe8HEye9)smcfmg02pw2nMA}db@tlWCd5rHVKAM#T zb8y?=EV1K2&GUYXzil+7kK_d6O5*cr*U|{VlpM4WubV?k3drSVEwqxW)k2+qTG$og zovXoFwQR(OT7gI{`!U=duY>X%^Pu~x81|AK%41fY<}sTH#%I@~?AQ0lQvUOraQayT zymNyQ&OG~>jXM$tZ6+bKi)I@L6_te|K<=bf!Le*H9XS{QiA!?XS#v|^2`f&at@Wi) z6{3PhEQo`(##Qw1aliQ2Gd-He>>`+b_G5E?92BD@aTAWLYGkB$3$f+;i}3aTfhX!(Vo;6j5W>Wr`F zZwk3xuPEYG30USk)w65{teg{xKHVb5&zs09u!G#qH7|mLuvH+$xQf1>0R+R%IhE5A zUo6b-pn7ilrXu=5QZ~l#(;*-UK%b%LCd2mF|8r64H zOv+qZP%jCxo9@#=9p7M^z8F7f3yeuUje9)Z=hQ_Hrre|4XHcM%dkjTuGhnz&4n^5) zg-fR$;kd>LB#cH`v`>p682$VCIU$$d3*xUg;X_)oY>9R*ts9?4cNa;+{KcKLaIx_` z{)ZQ6Iy6KL$v*o+H;=oTP zQa>fAlIcyjNMjn7Hq?Xte+y_XeKLHAT+Dw63}^L&u(Oy^8;)kRtc0)O_KWTmAHPCp#_)r7hhQiL6{dTUCN=W@TfDUJG=1Tw61>W5 zp^MjqL!u;UNP5`^GF3f%dz|=84K(q|T~ON`4n3-6V0wQFDpfv;P|iKLneUwH4JyH;|;TgT`d?X*uDba}_hhRP| z>dv`YIG>VLYQ&pWAJb1dHiBu_NRZd405|Ese7i!lPB;9$Sq2v#>7bptBo}>|1MM|L z8^v}gib*5I$vQ_t+DskklqkZ1R8w~Rl_**`1+Zw>SwJv;()~F@Jaco{Ypg+?f##4FYCeV;$tcUcLk5dWBtH+$h( z4bi^g4t_UnRCR~mud;C$E$BYr0=6(daRfU_$s~vgC7!T zK?yk-JpBQ-v4x;?Rv-POhoTYO2hhsfiX0zIKt)x1(XP zP;^D(6Ljd98;G#ANThFNxzo>Sw+*}BA)25@j z8;D*<3{e@|ItTS19f0x~W?(-zfPUJmPuB(Kv4;P805nA%l3Aj~Mq(!s)qYx*dGX5u zs>QP!e|`R%ZCXB_kv6x5&c&?|c5eXY_76kCVpx}uBCv3oiG(?uAW~8)Z!s4M{Js-o zdmAiSE8m;}ZM=mm6eI+ti0a zyV7S+JJtuU-VY-m?6*#pBTi>kN@J9RN!s~ z)xi66A|;EtqSVj`f{AjA%)XQBMdfr=;k{mdwD%;#oG~%~=uXng(=w$OKKm#mryWGY zhExy>)7_t&q>w4s4UK+QIs-EB4QZ0{HR zC1p0(GTsP%UPAHFl#9}KGYIBlpOHY$#D#jAQi);uYVe_4S;@T;Aas>?@%qVIhuK7I zhYlNk&~w0$^0FU<(L}A9jQ(Vt2m1%w9DbdL4@!Dsr#vxE;p`0bVLI@btD>wrO)!VW zP6*C-t)v#pR^rERro$d?8RHh!Nf*cTk&MT8(6f$)hz+A*`;=_D_-+6sp6rI?6~Dpk zHyIqCeGn>H$R=dS(8^Jkbi8pW3s>i%eGBLFm><{q55atbdH0JEJhoj;eQ~S6fr%sG zhEXn69`>0I`}7;ybH9K_vI`VCyrMU>FQ%oY7=o~MQTgs5jC!GgI^Fg_$AV~9X>uTa zGckk?G3#RThAu{jTjueYrMGyD6Tvti`6L*S+Cb^H5D&>SAL!;~e)P7R;k56*f4rp8 zcKsP3=FZV3nUnY|N6^Txpj|G8MyQWKPsx5wuu_?3iJ@csS`E_v<4RWzUySrx%y>-T zZ633RU^HJ!Q47WQP=*)E@qsjP=<6H;Q6{5lp@E=K(x`BU5%`oe&?fF{=(e{Fv``H$ z$wd-f#j40KFcPM$l&ABKOoijwns6y>J-tfV5lz@k>Z8f8SagNwN-)Jin$(9)$En}D z%5e>;u+Rn>GPr#!5qt#yQ$?_glJhRx9iv)hD4QQi%N+4r=1! zbm;485SykAH!YUZW*1ygNy$_mGedM)yoX?hoS90^7#2%Ca4yGpRGPq|a}GF`Oko_f zWKc?C9qf5C6>cbxg$!5XVEVG3?tJ?W+;7Svb#-#mx&PILi3UJnI z0)v?fXrQF{#s+z|`TEu>uJ^eu3?cMpnJHp075W#kTbU~c$+IDK6b z_9Pb)^(13tIr$CLjd4T!4^HMWD@4&m63mz1J1I1?kU|aRc$C~j*1~=Qye(*8lLkl^ zo=yp5txN*V-Q*TGs|YsD%!kUN1`x`(ixU|Tjh88;Q~wl(aGzWqWgtEpKD8p;Uryw7Ngi6y4TGlTcgQ+e3I+Yo zAbENNEFn^cr49@<&dq~sHXd+$wgWA(HwxJ$ok5d=DKz)JXob!b4O#-hxXiJnY{i?Y zeN!tj-SQCMoqmzcNGxV!Pm+fJz0W}CR_dGa2Pzv&!TA0QNDyy;#t|AQ_nZr4lpTfa zXI^k_>k3dVKZj%v9YE_1m!kM!BYx1zMVR{pW-UAn@nLn#>j)pPbwn-izniGOE zH|im~7lq*4*bV(e>sGV<4Y;svd@^OqS6x(pZV&7{C5{3z4A7_F-2@_W41 z*3~;H->_P|vPuko_l4kxjk~d#`DElPQ3=Ia190t|G;)<`VM zE6qNFFAp{TPam4`l;VBZlPw0|%Fr5KXl6r`0q0Ts3y0r)03UZqAfM0k$jTs({KY@w z%W3+Y5F?w+e+W7W#L3H9&OiRy~wJSB|uR zM94pAcYFcv#Ul_co@a0JRZs>4gy^xDu7cJm!K3^M_#S^jU#= z+Y5nNMFTz=IFuRccLmdO`j{cLG?jLw%JJqunCmWv+Gl+Pp%I$ALmIDV6K1rH8&;yv z?Y+|ka;cM$B&Cn$JbMQHof@2Z+)5rpiwehNb`jeHm#YHxL|eh~^hW&Z_%M9&@MBCx zO~u0R&8E>2yr{O*#^2zv^)sxsA=h`MBwaMv0$sEtcl+%SZiVAWBzMvYC3i}p$X`L= zp4&^jT4)~Q{E#0sRf3V(V%Y~QKL31Y9~^-Cw956j%pqBDbF?KBOP=ukX0Tb9Q-JmN8$1e4w_ zWwlJxIY&pW37;u*!;&)RaLxBDHd-|r3Lo{+zH9pVzBQMCZ*Xm%Jc`6KOb7p2#bZiEgJw)Ha&d||zqW`mp2bbrIn9EZYi^3S>}qC6n-8t}V=J9S zc9_L6Fs(6LPc7k^a0xmu$mgnWA=y!&6;2=uD;1m z+&Px9C#j*C)E0V$%?;N0nHy76QbM;~xJSFYilge??|4jRzd8zOeNP*0drC+AnL#I# zJ$LQWJlOxw6S3!rty`ZP{q^4@2wpLg$9RaURP70dnG=*<G2=;JY z8a01U1HFBI4PDeDL2P&5Lc8A&Xgo0zb*L*q-{-RbZlF%ZvP4z!AaX0yL{HxBp+q~J zWF$s@!$r|J6AU%_YWA}db4FLJ8Cy_>jM0;=tfxgSH5#jdl>Ky2A`6YDaXoBG`3B#L zN1?B1HF$-Y!(LU9=Xw+Iy4iQxA1TbxLMOIqvVY?5q1lh*dCW=Cgx)|fs#}_}?`#k- z?nO=bS>$eJ;}L0={d9tk*|;B4G%oOZoqB(WnL`HI)P|2ncJ_&2w>AQ{nG}KPRdu9# zFbBF!4x#alBhiBu3G6Czw{x$1HUA-aE1Cjs1S6y0mOW5BkMVGC!rjvs&~J;f*-VAU zbljyxNXe=OcRyL=yN8_CMt_462>enGK+`gmP_CvJ z9_zXmPK%2&P$i;4^CB4kZ^79^VpcNW+u!2mt{A#${xQ~J|9a{iW2ERYA1xs88_BQwfO^p?SLuvcn|NOc-W>zGwb| z#HV?%b^icVJa`Agce;Sm?*Me-{6wUqY>J&jSE1>eB1?*F5hjFSdRm9&MC2}GOh>=P z^L5wa4a1wW1G{M|YdJ9l;1p4#tun6wlXAM9Po@Yl!XgXb^G3+wf)v_3{uX?SKZQ1D z4MRz~@%Wthb|m)WG5>7xMS~ViF!_{Qj^rsvCbY8=&v@#_Ixi`sJ=%Mz#CM;d=!^oY z_@RQXesN({9eMxfP_Bu(_ZgD!OmLiWdpA*rkY+&eN5P0;S-F*2ex?H0lOZV}`t{FuvB zFKWa`avN#Kkq*@GMce4Q3tvH8MHX2s8o^_P(NvUA;k)n>l8FFa3sFoAQ9?_PIS`R& zUu5}XIC|T>2WvMSM|(d@@KYdOv=?|tFk_#-$v!y3jtNp|#JUB>q;M$B#nRg{2_$TdOFXiWaT^1ksj6kL$+|kQDEQZL3s3z2hc4igcz!FaKbpf+LW6 zPzN7Pi3pQLFrybN%zk0)z|15cX|>W#lzo>po3UgxU0K}?u|yFu&`k@uOfKUwU-Zef zUiAmwDB$~|CWu$+fw4#mAD2sQ__c+uE9e9FVKV5N*l6Ust_+TAwZQvfCdk;Xg>Q_}jr#;8nStjSi5{3V@|Y|Urj%e{sH&xw|8mA-c?14?{t#vPTa2AixrkSQ znY%?A4VsQbE%S;XQMwYI%{M^pT}@y|`r1#Vx51my{czRXj(cA($0i zidNjl6^tY%DbTeYJFh4)9a-u0uT(KqIqM(f znZ!cWFdHz^)qt;|Zs7c@62fk@gU%{7)U2+AByY8_PnF+O^YaQRrENa!8yt0e!!T$cH$K+ry-8y=lp@fYfB*NkUB(NDWg}W z$V1kwaxgvf4Q}68M^#Z|Q(JzX)q1&*mh`otzsKEU411%|h_M&>LGut{L~EKl!IZU_7H6m|XT8dZ7Eh2l z-?t{Qv=7S9$ifX(4dC2ZdY0VZ zVSaY@g;yo}1l9FFoV2YkV!;5;`XYgT0#_%(|n;>vEV9>zxhCH$h#O7^T-+BG;751oarX8mvdV zP9>q72WdQJg(w3hAeg{ul7a;qhnO#Y#F}mIWKbIE%&r`3NMCSNKw0KpP}~&(L2od) zJ&p$t+i;K}4swGQL~D5IYUr;@1*we=Fyn9{8CYF(+wTetcBi4UDkVJToCsq}Fd3Iu z3F-@jnfD)Sa75D<_UY*h>@1u8IisSKP>NI+xOk_4_30lVypy)wlFfJFS0kpXS+?zT9R5w8cK4piU{;$yse2Uu+(Z9nF-kWW+)S~`h%fNgya z4%_b|)q7Gr=7q6IGC=LMQyTEVffur@U`GzuyHHeJ@N>u$XpC{1e(S{67N)t22s_cjgVFEh0HMIuIt+_(C z|9mTG77U?t$(F*-=^MD{I$GX3I8AQfHDI1Waqa1|N;3 z|8xEr6<0d|${Rj`aYY^^9T|$u$|WH;`z0uv5%KfhV1x^75k4b{#FJuCV&p)M5OYtI zfeIoR9lbs)2D>vqT5GVpoGwlakf8^wv{>ylE#4@=)ba%gFIIxcE>oyMJmS(b=(?_s zR=k}Iqb|0AYoP)(hy|brpO90EjRhaCW2rxr^i~YXT6vOT{U>+ z@R{@&$2shVoZ;*$P6zq={e(Eb3P?0;h4wqYi8^d2oIP3yQ_hY=n;-q98?x0P_E8I5 zeHMsxnaPN@Cf@Dh7=|Xc@W-eyQ6Irsf>}Rqu@$>;ACohd>}e=eT2`3*$oA4R#R#-pO#Y&g@cOdlN+ ziiOdP7ey0KFxv7VR{xG2WM&_z#m{RKt+eCLQ7Nrk*&Qu<$nJ9j}E-B{jI*F+VY~#c=V&5oEa95Sa~42ff@-d{R=A6JkIVO(MY@2&%X8F*w5f zuBgQimvD64H0zv2$%*V-A_uDHKzasxTA*%yDkY9ce2C7LVanuK*0Y&_A zlcmta(95u{;WLriC(+y=#VOvn2lM{zLkowFM!(WuLc&}L?t{1}1NBQZXoUo$Y%oEP z5_^J~Ctr`g1I@cch zxnD4QI_f?f^fwfOe_D`AAtDb>#OQ^CCiL|3sv?~%9p2zzaUVCLvAD|j4mf=ELe{3E zP@GRWym}-{TP#fF-y22In$|!t3dhz8I*ei%tATp#uzf3iG&g~@`Np!2G2@}|b~mr6 zEVMupVuYSv@iV2tCS*9wSUte#4-TgrTh2qnSWo2jMFaKP6+na5DmrxEEFLpol?LN7DGk`)WH^;^ zi(z9&jAx^oZqwVp6U?SQ`1rmNuK9_f;mZ|~e$)^c^E#fk(hR2`hA6@?!_DvmdmyuX zWwiLz9k_j11?-K3dCV)(u5*B39`+p*_#5A4zBM%9=BdW)cCYK~4>uFG&G#l9qV z()|s25e<;mB!;wImC>cs+HmLQWx8nXF}lrF1?K(;gQ4U7k(iDc>boBV`v+Cvp~+Dm zQzP2hNO_2hZ98i(P|$zCc#v8S_F*D>C?Jo0HF7E&pO{L22$12EkXgNT@N6P+_dTGB zRL@KYqk%{N;dKjo*ku5`ZvsTPaoxFXxD(lTK>ruXg|l({?4}F7O+t>UozT$vPNiO#BMR zYRtiK36U^3w;TyE^`d8^K`?Wc&$o)5lf^u?Z^RS#$gwHooZ0(Qf0?$ME|67w0g~dx z(5+cDJm$2WI*N|X22I1G;O*K3x(_tb+MFA(VEIv0)%FQaE>wh=NrNC6d4>Oajut%| zJ%X8VPseJRJ;VH1*NCO0{pqDyH0!C=k~4829)t!PLO*HGe{Y~MQXF0O8iC?=cEFQW z$#Cc5dwM}n6x}4f47zpw(c{537@4o#ZDw{eWVdnxC*SgrNuX2 z2vb9g&%K7RHl8pG&4r4hBk25E31t61oOZ08hv?Q+9&<(%jUB#EgsV^!YmVF5}k4mm0e)=63pG?Z>->=DR_KSrBYBg>_lql zSE4eHskZqI4hwbBVVgd1+Cc2vK8;7$6D5(>q$2vR)FGreq>2cjT&2QqTO(`h_dMpi z=oqz*V5$!<$eG|0#pIIrW^R!e%+UBp-wEia^vrrd>6|KBps9vzXTAZCp#zX+I2I{8 z_VB5pEk3F!W*D)uJ~1L^X!vS0X2JlRlYT&7@pMETQ-AT8*`n8TJHc#DZ_K`V_!zTd zMkC(Z+Y3$-auAX&BalDU4+~OM&}X8}dF6Qxs0H@H-B)@j?`JodTfBySqkEyB+!gpA zc7f~+7A}2ip!F+8(%hW2NSYB{ukIG*(>w{LDO<+UV7?!7*{~7I8_ojPOONR}HlbAA z+(D=y?bQY?Ba!v5I*4=W;ibS_*e(#Z$33>Lg?nbF!OqwiziSnzZH6tup4B(-kJK$l zTy6+Ip{qsNL4Sf-l9Xn3gW1hgkTvbirVdzGnN7d@GK_BBPU@d_k-KM-f%0JLLDQxK zUIvXrBceMYXzp9^KVJ;WR3P-Nk>t|fp2SPvf5Cf^F880|At(}Y1Bw6eL_cj#>YqI~?&%h!eM^$ZOw8mlQ3UgM`f9EW_-O1Zixwj~w))0BVbx~NKCM~asJg)zM%50YF2YY@F?!rJbmuu zJ7;dD^cM73U34e?J&VW05lmOj9)VKKWM-a219oWcrb}**g6M2l`e(ERD!NF{pX3(T zbWJi;y51s<=3k(6|2J?-{0s?BQfPJORq%STntN|HlKZ8o%>5z0k5lGtNBSRn`I&Y^ zB>!l&NV1CqO=-%N8dHHQn$^C%GyYEU+bC~NaS*mGzkta+^f@%?w{ z8l9K4&`h{^uow1Q%|X70`XDVhkoH_U6v`Ki!+~9wzOUgahX; z(H|x`A~W|(Jf>JQXw3xk#<0vXDCwBh*>&W6GdGg95gQFpjwbPmE@746;a#sWHWbTjPVAc5wT%|at)H2=4g`CrbaE@TY~B)!yP}D@2PdORPYWP% zMj%Q!8qe=?ZdzSL=dSNSKicbgjI?M%cN5HV1qZS{zBSnFl?lB6m_mEse8%U~ z^m4vJaX|n`#3b=;J~BiNdy#29gkG0In#2cp&;B?#850F3jvt0SGxSmD2q{#5(GRWE z6Rl~VM3}z>qhXvZFgPD6xUX1)zXYzQ?;g#dwZae4O0v?VJ+vLNitdB(rchWi5|_e} zvbZ|9_D=?>rf8vI4)-8==4@E{e`LLBKuzEK{-5S~Qc031$xP-tXWzGER)$D2yv=1M z^AsXO=0pmij3p9MoqhH`5z5d!kAyVOv($g>y+6P2lYdV=cv*X|v-Vo|y6)?$HxvK+ zxEvleje${0J8{N3njcM$unMT|AXgEsp`ygrVA1gW9M=Bn4XUu!o1M)m9Rpu6IN&|g88=bxu|eRg6R0KY&NS7*@}^;8Ew5|)Hy9;c;56K z4$1!jEmIZT{;LMIzxob0B1zoNKTQlAXMo0bX&_S5#2O$4{_9iF2}fi9y_+y&!E^qh zJr*!y2*xR6ugE1uBC5QX%|?%jXL@3vN-1fG*oRns%^CayHV1!)GdoF+bY(S6-1>{i z7BgY`108fyGr+Wp*O2|l5)V%@K#SqFn2eB~!%qQWqW=k+i=?0>lkYLe4 zCYyZ{_no25Qy7s`v*R8h2#XV(|9%$Gdotgtymuy84?w7Xa(#Yses(QXQO)~ ze4LvDNg0M%-|(Ief7pk))j|4khc!U1gFSAt8-QI}DwNfsek`}xxC%4Pm0)J(oD=0a z%@+kI=MdAl&(xXj`%J-LirFMJK)0A*5Y|=$>q_M@=vggHoZUwJh;yL9+X#;@jAru; zp0n~H?|>Rp26fXB*YE3xTjrf-kKFmoWBi3xU@gJSHhL&hiq{hPuE=2*(0|2SO_CWG zuZxVB1Ulu9A>KlgdYC$obPtgY6xXy=IX?sLkLZm{FAS1dh3d+TiS0-8_YSzVc07K{ z(8USn|JcjbwlZ!s8wAI(tpt-F8z!0&cFL|jJcm6dR*>GBrpiVtA7+w_iB&7nK&2mT zgrn}{9w)N_jH-KJt@?Y&`mTay6K2TbFASBP{9FThQ&e$kmlZZ$C+V3#jATEq2~A7? zGd9~tFeguhiiY(6757Uqmz}ybjB%72vBiFm8PCpka0`tD&K&rf1?h~iX@XvKFAS-E z4Bn(!X6{`F+55fbGBtlWOqtdP^@w?MdVK>t+@~d*adjp?nquKYaGYRzQZI;BHp|iH z$O?V3|7~V$z);qpE0hFre+8Sx=Xs2GWf#U115-Zhs^4XtP4jUEQ2 z3_<6;eK7S&HWZLRhtf!)W|JdedV%5}7?IG5dXJ%;&Du{T>%_mt^;7XafM z9U$aQ1ChRU5N8Y0!bmDmi>nb1m7ju!2_M-swJofB|Gwy3WrJ(})5TwDNsu$%g8iu( z%};^Pf+3(k!R+2{E*e^WhraHb$2Lyf%d9-0NFqTKnVmMXV3u4P73bRkT-^Jdu4cG8 zSQ*Ex?x9w93DN6;CNJ#JmY(@gnxd<0Dzp88(B`_-oH_Q{aWL7YHVpifkj1 z=Jy2pSaKe_M@?7UvN4(2vidS(?xzeMjS-Z7bR#T!)dXu-xA4(ntJAZn)Wd(M#DVr!xB;YYnA8w=_=P`di@R%rq*=RpN6#ufBHr$ra`d#pou06Yssak)Mnat);<;x`0 zuSA(KEovhEUM<)B`W_Z`?yG z`ov>sf>|`P&92Q^Ug|B&XZwB{%iO7OW?Vm9V#d5Jqh?($rQUUP05iFUKSoXMuZ5XK zMxfj4>;Khk?uE94nJZ%Z1TCDCP zgm=1F8u$P%tvCVyx%b8v(Q-`5R>8?N^RaB05+2+;0&FBYc%W?DYMsO9=e zwA{6%^Suk$+wXlDYjLf#xJrrPtd8G#zaxc5Ih?cj4?m$_mh0o8&H^}88vzewb3jty z1~!3}aJuh2EF39^yOR2VgS!o+)@|T1svr4x^NV0oAM}w-o@pdqG7LhsfVc=_D`tK<|g`E&~0&n%)APUy=-&`*dNx&yvYQN_D` z#=#xcq12_f20Z48@NQ}erl;c36L8-?88Y>R9b&^>hU8rKDIi-NCTy`B64+T z?sxO>BDvFv?SaxQUtrgAD>(8gOnT2&3ZtIR$B+5FF_G>KY01tQ-zl7=TLery!OYoF zC>f!pC~Y}Wz)saa!;VPGpe~8WGPWyfA$EZp9zCmstxBb^Ii!J4mCuVNABAhVpuBP- zI)5-BVNdcH9zzUINy1FXCOInFs~F}Mx$>hqCSc@u5{vLS4|-N&9Ub_*fNfdzL*(Sp zKn=7HlrHjW$@P46ii@Q~LH<|>~JLVc4bTFRQdsV>7ZpbqQd&;R-Bj-?lVNI}7rhSrW9>`DQC;Pz=;1+$Ra_>!}OL893ZaWIt15v}_`N34t zf}Y>vLF+qsWr`M&QOC{s4%{A^6OQF4{DaaDKcQW>4n~Vx;PtmK*yx)B!Oq(ucAzCJ z9%+xVReAhqW(eAZpIVLn9%_e z>u_V57eUT+6VsYebw{wbljTo1Xci0Dxj5O8)7t`hx)vhmg6XV?N` zx;mgxIf3mS>A|MS#j~|x>axe%#^aw=ANkSTNa8UR!C35BAo0n)Nk2%;XP;|iQ_mhG zNjq-%^QW~nKa_B)nl763FNW4DB`|+$f4-#p`BELsW>UewE(Mq+Lu8YS8`x8O^<@bW z_Oedj+2{;{WF%a`%p#b`IjwO6ECT6luY9)9>pdkW>LblByFx7_8k;3AlyJjrRX$a| z+v*FPu-3&@&)Z<)$p$!c;}eYd`4Ix%ILQ{QHIXfhvXDI(;v&0J;*3SMzxdH;f8j^7 zh+smEpW8m%bBn%Wna|oTzDeENo-GQFi`zfxGU|>lxBhI46fH z{JT!9S$~_#b5=sfV3HK~_Y3IXx(UOEoq^{@@lYJl0NcslEoV(3Oif6EWq&5g@)pX; z4CHdzvD$rP!J^fee@-Y3`3RVe1Y`Ok)-HGA4f?cm9_#!nlTLlQF>ch!WNPSECG3Ur zm~Vdv7T0@#N4gk1&z^x{`)i@>U=!T*tAoAPd7zvoFFUdJ7Q6Nf#k#G0$PSpd7L`aM zAosm-|HePGodnan+RN_BfGf1}yIi*M(M4wNv?%eKNj20+A0_NxEQbbvSCKNSHQZEb zqSm_%2dCmHuqA$Xa8?C3S2n<&6Bn3kAwR|13#!Ebic6%yFPCCW!e<^6pTc7f5scgv zomkzX%k;S+x$JheL}ubzBk{@TG(nj%wg=kZ4CHk-s&~`XTsM))<1Vn?t;A!vtZ&_IH05{g4_u1xgax!V-W;rec8Vvd7uR&bVU7ZL=-r{3 zA1=ky-Zyy6zYHF8iC{WhK1hxl9Hhrj%V9$f>>zvioz(JC0n~{u(xQ006TbK91%<@c zL-#LBeSaz8d!smIiU!d@J+D?l80$lgI;sP2ZYe^&dl2>Gg)8PyxyED03h4?r3FfBc zlVqpk4tjlIHajELn96CNEKT+erqaHsV32n^+?=fVe{!Bgw-mlKbP0Rlx2*z6?`itK zoy`BM*%&A7z`=2Xu5+J&2_cw3OH!m{VU24JvY|vGWInPfUZSA32SUV42g;FN8$Idt=y=5`HvFY5YTb zMlcJnoU^O&ai_oQXS08!hJfDkIPvfS;Zy{zhQo%pfaTWRki7LCOk8mW9`!yBpSucR z(?mHumCZtNHUj}3IdGczeBa$?i{D?g!}7_ev3!OiaueEFz(f;_eZm6K>+Of=w`>+W z-fJHiywhRK^sT7tq??OV4VB)13by0(`3%W!;$mS%dT?gnBx0BgFJRHnX!z}E2~*7< zQE{IFVBqsXaC`3=+)uXb9A>dF1!M$6$ITUu^glEA;`mejuOSuuu$iuMG&Vy}Miny;W91fbrLeJSw%GWGLIy3n)HD+Kv^}6j0Zt=gs zW9%~dhxVCZ_TCVSsuu2|*N0@WUF!mvK)qK~$&J6_w4vG;OgZF^QTi4o z{DJ+=7A35n{S4a9rGbCsP@ME?JZ|2-0q=BDIQp?KCRP67F`>d}G70A0>64-)Zx7n& zP!{`h>@0}Gi&SFLGU{TBHu^=@5}&Sg(A&}rJ5Af6oBl(xB{PA;_>X%8xi$GP?&)dJ zJrWNUW?~$$r!T%#zl=_K!uJM*cT-F-e=eR9c}eEct5vet63xHTk^>W&^utcn!23EV zZ&eK@emSt;iS*S}wn3O_CCquB&Wn={+}=vGPg2-7w;beGm?HJh8Cg9mJl#T?$|fcA zqlr)DA6hxVbT0N3^;zvmFDTDsO=}(5@43Aw?Jp=*Gu6XJn<_pXo9kHNcAcC6hQn~` z2cNOgpi$5TpVKWcAzzG#(#BzE9npGBKZ4R3n|RDXVNGi!7=!-SqAjcbqsQuJu@eV1 zPgYkMOwC&|oH@6=H$R#6IR!I5Wwz;B&g zcFpc#G7b|hU@QryJ7=Y+((M6#a85Q`R5VDcVzrQY_WU5T^0h7=l4TKF@ET&u)Ct3W zx5Lma^2qomf{(W{COXZNy=tf+NR~9mF_3Y)aF?kGk^|0bh*PEnr4Xgv;SM;Mq=51(U-H*PhgIjv zF6_3DDMgmUh`h;||JVZ8Kl=u24(Q7E`OM)l_QGf;6HKszgJ?=u=E79JE2l|3o$C9`k+3u{J`B$;Oe zul%p%u~@#xmyS$h(Z&v^$`9Y6Xv( zbE1hKjna7~bhx$>%7T0$!Xb}6bL$Fg6yF7k6CLn=*8p_h`Wb4SJy<`gFkkoyusSZVdJEW5M#W zHp8eN6#o}a?s#&iVaP&DygOC~6We-I#ZPAO6FNlrdb$wI@UYRM(W8u|kDYSaDZ^h= zH~v0lCN^DXxZWs_=P4AI>BTu&a8uxDtO_2VR>}89h3vdet6Fzc^S%|s*z;3Sd-Py@ zTOxx~LE7NgdWNrZ*b0G8s|jZH{yC!ksTR^vPjcDy$MnPzx7IWI4x5=P4m5Q(DVERl zic+rOFh~v9`>OlY!iHYZW7%0@_ADstImkDF4ZgoR8sJ&BRCdqZ)7PHR9ZLq`nem| zk0SEyPn&Sh7ELTz+8^F%jKvf!VXMAe_<8yf%n2osq>iwcjyajfzK*>t75~tc%KRos z7p=Pv>Yftdy71Oc`N?CrShry#iDPW%eNg#z9bRP|hna~r@N?Q4jP%gNh9$ZruV4@C zyyeb+Z{`aV`ZmG5fvmW1Pi9CBkLIyM%HP4$`zlPfoFUa2lR&N=>UeR|XT_h8f4YtI zK_8p7Z zeNT46VeOeDS$-03*7Ak1L}(%@9?!pzVe17Ed4Yh5BN(r<_a&z?M@#SRCMwm`{!+DHy(z~z0~xov2Dloij`2n0#P+fX zNgV$d&h_-%wm!2|?MhaM^r0TCN_48_I`+N%wd>^iSyV_#$8u2*y~a zOHx**rc_pp{vVCFKtxNag3Nk42> zH^O0iBEVRF4U%3@JYglH#Jk7hc@RVvR>IFSnPAR8Z;>RXYDiDaBr}cPB;I8bM16WU zn35;I!g&=+~k## zmCGCHg1@<}tEN=>m;xfAqLzeD!A@38In zFL0tfsQal1)cHVquzopXtm%M19Od|#)*)c33FhT2qqrBQ)%5%HT=v2D8)8cF2DQgq zf!by(haBcZ4+%t__8r#FuZArZLNUeu>~FYjSP!xt4R9>$2D`jflPw&2o87Nf&Tc<5 z5pNY|^P{;U{BBwarex`}DZ{dJ=$v!8tbu4PHP`2^czxJWDy^#*j~VE%g`9kpiueU% z+eqsuMb`ROWr4Y%+*Z=8X*A9GFvdb>6Iogo0G?_IL+g zr)S96xZbkww+G48rY@8@M$RT#pMo;QPQa)WOrL8n>@KBC=z==Z2Q)@P1!pXw$~X8@ zvn>>nYbfI!E`#i3FsSq`ge4MLJW+IQ@2&ye&v_79`3+Y2Et37wF_T&C=`XwZX|}9! z*+Sg9Ua&O!BVY^&=3;P#-Qvbb+SMIIA$!MJ*xh}z%Y zptp?9VKuM+6d&*2NsW(>;xSxXsh{%$aCmzZ){k(3wbw2Kr-7=ptOujLe?T(!J*3BL z$x32k*eUytv42iU*;yo2HXvV#pJ_$HDqu}8!yL>-j_RlAG11vB-~zn62=2j4hn<)&k?23E&2Ge4#7+i!y3Y_zCv7sPtkeoJ?p zUW_kOs`;6=qKN-`+7Qf<%3pR<`fi}-S!S~fOV2V+Z40R({j>Se7(SE3$*YEeYN&jvW6+u|=g#=4lthzO=- zlDFN**Q4nAM_Fu^=rr>nr>fQ~Sa?`Db{L$_3 zgY>h{*xwH0TQ5+rf;3d?!@Q@S|KCRUw@0 z>#~BLP^BN|;^1R~USRTf97dR2HR6$&ap<}AbWBxOd9{0;iS zW84U)<~D8jpnrYLvlE$YNk<{fH}|FTjjvN1juG1&(&;sMoFTlno(&=&9XM{^MYSgX zhUeKm052 zrbN#%{q$a3VJ(%ZVTv%hfv!$+@zLGSLK_Q4%LOi zu=ONv$1oNyJ$weXM@spc&9qw*^Q+U890hiUQfs_Pnrc^<|6+l4B}B4MT- zAee@RP*IHdhuy4G8EoeGV#essB&p?+P2z{XB+)mxk={eW|% zeV!%0!+}$uz{-77!S!3UIP?HTX)4{OI!7PDbDyL5ccUxJG;f0WRDMsi^?fb2miJ~)S^*W zsLRVY;jCS|vA}jK4rOzAOqKBSyg)D?T>?dmI_8PgoibQ+xnQa}&_}9iXi6QmC61%f zHL&(Mk;5-jMD9*{Q07nY9b3#}obJcKf}<=<@a%#K0ZnkbdjQ_58;-MzPZ0%pE04)8 zzo$JPah{zc%06T z*w>F86j33XY^p_l8%snjlPcg4@ff@sqJ$>zo55>w1&=AxSH;A(A~0Ot43fW^_&8hv z<2H`R=c}zzb>@1^8spE8CO}xB!?=fbWUxp!YpCcgo6cVBWx>Gt=ZvV|L?(&ktB0(s zEgQ%A{?v!4dFu+G5banXg{jsWpEY! zH1UjlFih)+hmEVqbp`qS<$WE4Rhg#9oZ5&vYm)fUY!EOE!Hkm*6kU}S+oh;wu$Lbl zq<$26F>lWWOBb#oMu1IKU_y45_gfVBhh{`Z#Q8%{I;4g7b|z8%0%+7B~cC0^bU zR@md*2M@a;1kWfEbBm3qfJr16Hpo?Ufey5LIy!@0d8CTE=V8XYYSv*EE+YvSuGM_` zfy2Z#w2<8Ib{?~gJkZ-)eb{R@TiGfvDYOs=pS{k*i4m<4=1o>+>w@mH9L7+1H|gBF zIeStxZ__|K&%GJ!nxj`JNo+jxv?z$jsC$$HXK7^dTmiX*hkn;z-qmX4EG^VX(vdlq z{$+i{NpLq@o+K>{!lT++nBkbr9=;*8U`Yi`A;GNud`eWKFfq;`ErV^m`$)R5|0yOs z%$KQnq>Z1o3&8$o6Kwh`kKBR1kz7V{$EdV&C7cYD>~gh*>?O&%8McM=OzRornJ3Cv zS*Rn6v6?31MsrQTlo3os*&fmTPr;IXR+;RcBn#%AK^{{TbcP`f%zPffoCnSDK~Ww# zt@>=WUKrLP;deGK$Ig;1_8KBf>{SiJ@(i(=bX58r?1YSRBUwz6ptBhx{5 z(IsDfI^}dG`(^Y!#z$JrY>opOk_?_fWi8Oo1FL0D`$38t{GzG(fc<#cFiCM&6a!=!k` zGs-5ujQ6ZZu)c0PbWU%A+Wy^qPvP`(d9=*k32v{ifS74uHIF=JrxHW$Wx8WY47@6a z%KZS(-d9-aX$e0CIs}a3ZlZ+Lh_mbCdY=A7WwA^51v3X-Uo)`>3Pa|mPJmM(g-QyaZq$D{L2f~m{}hunPefcf(n?%lidr;J%F!U~1&j%1`cfae6+O}P#JVhYv3CHy zCt(Dm>S)Vc3C^U-+g|c5Se(x-hw&lKysGw@)EKRBs`sBz%3+Wk#9nEJ6E@?~I#mlB zNz>+=SQQu(g2a{NGB|&~Sp&qIz`amMZ z?Lw)|H8&~ayGlUO3b>2}H$=Fr;lt+pV7^}o+{8jC>Y`u#XeJVj>&MxWWs~01F231p zaqb%??Vp}ladV?|vPTtV>7@vqrIGKbdcH33<1i5?Ei;2iNzVV(Y}Q7pqPTbgc3e@# z#_3o7R~m{yZVDU{rT`Mm2k*b+Oe~={g=MoHwS`Q#i87_4`dq4d-3Bagxk8v_Cln{w zz`leQkS3_3gXuw7oH84Vhk4^Ai`#g5hYmV#ScB!xOXFKE9pI^xj*k@0KEI(B7+{e88EEmVLh#7B~QXwQX*wu)fJz82Fyvu@H;g0tC}r8bnQS18rvt4Y0^P|d3!UXt#J zMGjTK#5cioLmm9KRuNsC^1)zAH08gvn(7h1f_3|6;O^Kyc+t}r8b(JFCoDrA(=Kdo zJqYISW=mQpau02OBAcBc9mCwLxkf1@M2fkZjo4WM^SERfBa-a*M6jDm@|45R-@00W$`2cW-!Xh^X%(nUioV0hqDqXzpp@23Ue?Y@ab2Pnfiev6~!-~}9Sb4?} zOTJBmg_C2UNI8HX4GN<2q%|!txd{*W$W)@Yja#L@-6GG~1 z#LUE}cW+$e)gRpt1;LGN3(<419vaUv2b~{%u((Uur>zz?w^sfp^x_`WqV8g38G6}paU_ChzZ+hL-+z(lH!TW0#h;#7O|OX`Q> z-zIR)XDG^1f{UV!Fq$BOITzW7b}a5q>)**@eLuP|vwp_eSuff~alKJv2P&Z9JF=Iq zF9Xh|Eo*xp+?6j!{H-ft>z*30+tv$bFp41R+Cn;98OmUfzv%aLYrOfXh<`UHg?ICS zVBB3*={FU_Xq%Z?ta*D*ahPx8`|{r1hsM;xxD`ZS zJHP-Rn66}1kFm_Mn9ZzBO%ywa7&y1heZXVHKlwH7Il&w>8%D2?x1d+#WwPH(J;V>f zB+|0+kEkCr@`z2&TQ(k$yB`20d5kR2X;~sHxU(t z+w2nXRLh4A;X3$ITMjyBG{e)q#o$0}^)5Qu%1*!6m1W%jcao-2hfh(8M3rU8gmF)xSnvR#W^=T}nl&y$;Z!6+vGO_h_N#jyrJOmy?7y4K3t(1O zDBz+#k6}*5S+I251|i#Sk_+QD;F^}Y?`Ocg$Ek4Xi@wZJ_ZzDse-N@CV9-H^0XC9f0YUhO_>h*4_Lda{j*y!wo?zUYiS zH{SE3Ia0@Cx(Oy}SBPZN-&lG|c`AElZM)R+$`JAMS7)e$Kb3KtKdJIXv{2<*Mo^v^ z!}msU8YthiRw#+Bf`PM};GDw^>RgjD*jsf_j(5VSSNnzu6)xwau z^QE|S1obqO$a(UJ>ajc!f`=zSloyGp>V5!B<}WZ=(E)YSu7dw=DU|6?f^p-FVg2JQ z;)#0_HfWr{KSyf#cT+8lW(>h7xQ-ANSihhPU!|~n#(!mHeG;S_V>6{(|4pZE7rfgL z&tI<&TJ{}mFJ!=@oxfm?K{t%K83mu;{{%1ll^{D1OikEtMC}TGC;sEI3!iETdgwpG zgtjFZHLrX-*RPN0 zyt_1&kn8&XxRcyXyA|`6M(YQ^f%&nj_-#rd3?*(c;d2M$mBqR^q+~y4k)JQO9TW)| zSAvOqA zG%yaDwvk-c5E5u>ZGs>6*`UULJ)ARbGoB!!bsQ#5m;!4FCd~MPo#}}^bojzlHfSCB z2>f2fOgWLn^wQA5sJ)F~n_U7clZ2CWR96F-Sr@~~0tHO_ZzGrv{sRLIHSkwnU!?C( zBsWq-pS$x2S`HRULyf}Hxs_m+Zh39jt6)8S`CBTR(>aha9l2AiFTBEQX%o2V# z`v@jB`;J}b$%C}*kTiBp>vgK}#&7Z4sLRZT5Bj{HO};m=(KR8Ll8-ydg;+bRU0eeH zB9-yd0wrkZ)fdw55R)K315}zZ6ivP>Pfeta)&dpM0P zbke0lUV1ZD$$re52L^(0OqcA>$Y?lABd(aTFQx>fM^y01lCA9hpowfRrFgiUY=ld} z63w@_!JR+@#%Y@y%e|Ys!n^S$nA*vzq5%6n^w63#R{O{kddx&QQPqDe--6}qRm+!# zxY2O#Je&uycV!9Rv~*~Wn#^(WZ+2(?N0{rY?J$yTFCMYgB!Bp&lh7)>z248PuPH_!bdeK$Rwoui&0 zw%&1qNe>KT^oA;sCjZYMf1rtP!72^xhW=CJ(douVU`AF$XX9+y#c|d$O~(|lv$et# zmWCJwc~E`YSoU?G1CPlTem74D#^-RJ-R~E->11&RJJ?*8$?A4wJb#8VZlT2x*ZLGV zp)#jW^9$$(u9y;~{R|GpegLQ6<7MML3}jn+eu3C;3`QprF9Owkn6^(v7B+qqj|mdK zo>2s&we_Bzg;E5qbU%ZY+B-0;#%4w})t^zn`ivwioCMpKP0%@?SnBrbhJ_{y7;HfV z%ipepiiW&wO;I9yCAke?v@KS>B1Y%B>5w%wicL{&;io`9;j=~)OrV8}oq{n#kL<`` z!zz`eKL^ZZu90pcgP~i%;NK*^G-S{G1^X!^p@b}rmX-)l#>@f@O>1Vz{3KfB)dYtB z>@c7o2^1n$@6s7d#VOv-e9dNS6aT&WNHAfc+wImaN~X8X&t#KywutU~$TO2ucQdEt zb-}uziQ+0y#eX|M8@k|}fg&dMDDhg3@FJErniDOyEhcF)KPF+5uQ47ZHm`Q0`ccx9 zOHwk?tU*8`6D*x0b)7d^teTobExs;CvOL?ssj(4U zB06{t)Yc?ZSYZ0)|7teIHi#|X8E-1`6BN^$RIWFtSCc7hoja$eF~wTkZX z&Sa(Y|1tgt--yL^)V8d1T-N^4HchU~>v`G0EeRpFfYh9nqr1w#y?&Yadl_yUU zd$xP<|N7RVm{zEYP(v;YuQbOGid5U6Z(IcgU6jM96^k)vhb~$y+YaBN@4&n#d-)Z5 zzOWb2BpBP>I`p>%-|6kcGTDkRA=Kj8bEWlK7b*Sv7+AE71k+V_g6)5Gz$qcW>1Ysh z&EH@&n+9!}DilvWCAJKffqtGNUcGLNil2_c1-F3^>f^{`G=-n15y4zHzb(1dTtXMK z8LXzq3u-IMQ<<%gDYt8-khP!G0El3G&|k7rlP&B4b3sdcf%wCnY-Us8 zZFpAhfE^CQ@Z+@rVEi^i=hvq^rb_sEniGtiU((xZC{AZHp-Pia zV7B>P3_4U73@07omcQyD;gK75n%Lm6+w&k=t_NPN6ix*5g_$;Y_^ z;Wp_=>_2xAe6%vbd+mavYpC#UD1wouS4);Z_otn2r?Y|IR#T@81H|^F(Nqw*Ea7}^ zuM$lMhv8h}TkLiCVhZPTtNd9Bjc;_qOM|kgYsEw$o)J=2%}j~Q4)#Zt1HQToweAi$eA^H_ zZ`4SYJQ$53XUq7RrXjqW6$E2hpBN|ZdzBuxHH|&}r7yK*%Q$+c$ua7iBJr~^QpTag zHK7b@1n+L*YPE&rtwnFGf*sXA!7;A{bSnH|r``m7XF3d(k5^N{H?2_Pw;)T{AUw2< z1QVJljjNgJLod=zW4kksQ|145N)}f5Q6Gpdjg#|mO-rLj*1;;Mhimpmc!K13aba8C zYz&CRZ=mL>2fVHrjWO@cu_GpenxioeH+l-^o7nvkI3h!s*S62^V$&Gw&6j!#hCr!-@>fREsj%V=Zv@eVi#X&~fE{Hv& z11Abcp!*Bq!0yn@FP(?Dca!wRR_96}?YSwH9rDje?3!>=-P3)qyLFhhLP(OGHAA(Z^ zBMX2jnLlsQXNRP+P5!%?>@)dN%ljj!q3cy}Lz)^^1ZpDJz|38*a^fT|Abo8IF>DSY zk)Z_Rx+af(lyZX|`8Ju=7^^AENHfQ$lZCDbqjr8Ymk8#Of{tWM-(cE}96Sm~oMbNB zNW^CAYQ)?T*T-EQ4@Rh>=dyZW-dFNDg_q}($}Q=?Da?z8zV#9?wizyy9Z-?Iu_i&B z;UHV4Y>c-HPw_KtKnIVxNianN|C7iHZqV={g$+@%VG`$Q(~&DjQc@Ll42)7oEr32#vk_bNiw zqB1J^p_Ce*F$vYxgm-gLp2uVoOnGv1+b-jc}zLM{Mz!)cKX)aw2eHO z0tZ;?Zp9PvgwONDAIL1@zBgPwEn$HTSbLOF3*NHSu)S>%XWs*Qp7F3|UHt!T|Nh@L za96rB9=P{`$CwD1MuKtfA7Ljy*N=Wy`;AqLrKy4QUWjL<8uFM8^5g^{GKH_ci=aKq z3KmE92EN~u%(TqJNNBf=hLFGh|La?e#_yR=(QM2rTya_G#oZ{(v@U`v=+{@2n(0j| z=6z$w<*-zX&J1dB&nxk+f$C`ZK%RI#d4b={UR|-AHnK8Rz_(6oQR}v#9emKkPiWV0)+`}LNI^I zwe8a5Ea<)CliAdmCMNLPTPiX1xRk?0k$z9kHYe|oGJ1~x2i;YbU|&!ROURd1a-^I{ ztkrP3sUjw%YvPfeq$9lE3d>1%ehSHM=e8UU0>+YHwvD@Gmv?>uy<$!>TOjj*dA^0;Pi;yl`-fW`a%!muKu>iS*97rIIfNOzu|0*)&vgmCv_z{~w{-Lpa1 zd)s=ZZ{~o`=Zq%O3GU;+g*0wGBQmD1!)!aa*aQcJ7~!Um?r2Q*cHC%81n8vAQAoIY(1adqQVL!5BTYg{+6H);UJxdOC&*v!XiN2J~>dt>j-DB2C zRW;7>Q-H$+x%`F-qKX`q)y3x#l(|*#??!GD4Zm8uU}>u|7WUS}-9)=Owe+@82;^&-TzC{u{^KCzet+D_i)7#^tTKrFMb# zsV3ksC&&eInaML)8{G>JM=N1CnqcyFLo9PvMQ52SZkjA?)pZ1n3&AXESYmf6uvAi^ zl)@%vJfvg}Sz?bu73N@+CXY!cw}KpoD-G?_ZRIf&MkwH_f_t!NK`$(8D+E8X>8+?S z!dn??m@w7_H#rMUvO9#&+G>KCH!|4H|7D#-Iy!}o?%Yb{MBSE3_PH=zBc|^NB2reY z;W3;O`Q~&|wv$xCNnb_ONW2Wzf9jxa6LBDO)xkA6y>Z@fdEE7C0bWly%}?mJ0%kM8 z3^h7r_t3dhGInnYdpO@t8Zh|+Gkmut!x=Q0Shw>{OZx{aVM}j095uKLLL!I*ENLif zl-mvm#*~tT=6dkDZHN(Th!pt14;ZU78y`IQkH@qMQ(zClyorzxL;FtH1{Tou0&FbcLn! zEWzCWk{NeF&xRiTBZZZp^?+GbG=RDO!b|F7Ylz;Py1|W0C#h1#mP(>spF`qZ-;xWj zTN*fNrz6y97s9P|U%~fAZxo$N1`UgwApgV~Z@DG#RgMh;#*bj;47?zDtb}wV*>&oj z31XIwab>DE&z4@C+Xo{O<*?EFFI*2&LGc(R0>?Qp_Nt9^Pcrcy}IJ)4y(R=<9{jn zAb%h+NQ1+bk<;0P9JcDn49I%+758!qH&T zRrK^V6%+OXRt&!nL&vM&e+glbFn*^%1TY_0|AS37`Y4{~Lp213fMWd}IJ-<4 zBQ47&_dL!f7hx%o91Ik5LU?6eATqoxbm83IlI5F2&jM>i5 zGzP0>$}f&f44Oh{@6;65c;E|h#esgzT=Q`8!qeusP*)X;7Ac{|Jq^qV(?Bi= zZNn2eyrW@=k;8fzh1)V_ck)>hyx9f$@6Ur~ls42SOT_Nlsx0>*&{N?t$prJa{F)@_ za0J~qB8B~SELJ+SL6^xhRiHLinxlA_3K}{pMTlt2rw+H=WIZO<@|aXr9+OKj6+dDn>XlJ+@tG8MoT;I7V##so zDw}w*((L~H&StC!nan3Nae{>wo|~f2TOD7lAStrf#>qS_&19F-_drW+7koPC52F%0 zsqE)!vgL~7WZY=33Yb!YaWT3p`Pux6p1VDTeg2#k_fiZK%g0|7Pxz&WhvwD7!fq8z zJEe(Iinzqy(MO8x2cAw*!T{m~@2@&RmYM7Y6KZOK)(wKd)g!?*%}Vz6jU$f<5-`;S z^WOE0cy)@s8CvDVaQqQ-@$;DL*7X`wAbg z{)Rr;vt+g9BV=_Xn>ApWJT|32hvI2tK>P6^S#HmC9&=Qke`u`)^PnzJQaI`b?MX0e zp6;Tp+T7{Wr!UiMhbDvV_fW{{QN|L|xD@}N2Cm$thn@c)TW=m$)A#=UH`i$%RGJI* z7DZ*M&e{7~WXe1x^E_pqLKH=#IfODL3L!GqIs2Slgve7wTs%=5#0D}S@^%>|~ZAePBl<@7(a0q(e%$F31 z!e;uSH5w~5H7fjeDeeTE;R+^|@mtqzVVrUdWqZ5VE9Tz7YWvZPpb2lsv3M#0vAPV3=wl9BSx{} z(lM^X)H43+(6`*7>+#IP?cWsbs{-NZI(xW?SJ*`#0}>@QAcOmvkujay!G%a$Sml_e zTvG2SYt{1#yqjb}?u6e1ZM{uU&mCd*nm!Yv>Ji4mqP0TIZJ!tgV|$dlHMxu*92>9f z`|%{xJU)SGZ+e$ayjH?qJgJ3~$MlGAHI3hxlJwC(*iQ{gR`z=)({R6*F(4md;W<-s zOo>{NN5Ubf(TXjzIU}3`r%eTnGh)mt3KgUJWOHVuj34o-m#XSTzA~(FHnS>X8=EM} zW@#55Eh1lHp+_vbnhL$R8v8e~Ifskb_esy$uiGjhtfvEZ=RE|Eu!T@SKC+MMF9{f1 za{<#HG4&>Q6l+|La_bz+_$4zuRSO?|WK{ciFk@`v+2Sr2SbCYn0j2~hqe6ZjmzV76{ z7?$yI(G{wd*B#g~Zi8gSv-hyYYz0d@Bp0+o(Gq`c(lOtd=o~l2_L9BqYCk3G`tvor z`Qr!ZeFf)xU-<#MayLWjxR0!6g;;QzV<}){bkTfTbB9_da4&Sq_{yUms_~mc*`$nB z%rN_NY+~_uHvhH;iHSxLXA4czkZDA`Zv6vq60ZL@ct2{6CdswyN*rnoN#9$${`-2P zr$C5_fa!~vRd<58c;E5d$3LZf$a^5HSdT~c#I+X31w90W9^+F7CjBj)`<#dt%a zwIBxaUIc;nKdB@#BaPUY>5vJlyvW$^mgLm2Y`C?f3u*tTEuok+BLOoEG3PS_xO=hA zT!}#$Uy?UnS*Ww0J$vAX?DMh&c(gwYuFzf^EL5h&uywm6gbt>uy|Ej%uKx~3`%6GQ zSD$<`?n)948j~AYhhRfW2n@TrT(}6%ikNYTsY>p`V|!u7>A}ai)qX6O5 z>eHw&V)YdCJ~*>k(M_sJ=g(oH(uw@8^CvN{zrgJ+F|6U98w_2v-)6$1Ekw-Z`XEJv ze!9PLW-0&NFIN?HxDV_2{Jo6UbyBS%YR$MK--Y>}G|;8AMJMX@6L>mXNUbf%Jv+ALYJ)8u7yvQ-AL=jR>a_<3pshKCwUg@OS~~1YcDwqcaDnH zc5lQ*TaTEr);+oHp)t}wcT4#;huxJeyJf7#hl7k?hYx}^I|_cnuQs1iB=|Kf*rrP) zE3o|w&4|EZfrz;b)9`9d*CEFd(wC3M@)(L zAP-)6lcT$yLUliV;umQyU>Natvl}tjx8G5io_;Pp7FNnj*0r$z%$dtfd}zzI>Cphz z*oC)o?H>WN(dZR~AJ-)nYp~|Fxdw_XI+L;Aj7j<6cd#eRn>|^Ivp|NkMRmSeQjA2zN9z*?5Jwf>b63*Xo|3C6hnVE)S9Ko>L7*H6EIq+7VFc~ zo%C6TzV#G*u_bmVzq@xP*8Xxxio~{so2CM$oruXs%o=XJ;$)9+(odeH{O^Q4%6)&W z*;I$^!Z<`aq|SbI3)~vl2$O>9gj#iK4V7=V>*z^_eZ|&!R4J`m*^x{h;!AYub75hv zHt~NXR;EOY*V+ZdysJu4v~94Eg=3UMrrVCSUHVvg{C6lj?(Anc@kmo}ZvC9TK*k~* zvlnAPUR>89t5I*@b&WZhiXt=p*4_bA{eOsEZyaCUcnr!=f#imf*teD=5q>u+YK^(C z;@lifS^gC@KledLRvsP4-R#|){e=RWG&H0(L%Ed!sF<+(4QN^#65WZqBq#74Y`{iL z-K|d`Huf@jzO*O(V?9W^#vzD5ZA?~Hi20jH(HAI2O#2pp`A=3yroC0ouho+=i@Mt~ z=l2#d>%D#gEl~{KszZh>`HoZN>*0&ah+J#0N3wo=fNlw>UE^{GOa|t|o%wd;bA=*sLCfoJ;<2;G%UHWFw8p{49IIo{R^-$(qD?!~@|>>nASS z6U3|=_2}}+9WSK|d#m|Dzc#Xkf1Fg)KGZUAW5hn`iRf-np&2?%IAn?$3FvM>I+QoT zi}z*V-o8AgzSc;jWfYA^fyde zkNS~r!=OXfU)Wh7rin(28~PJs0>^ci${(GSI+?2ZF9DU(Da)QJr7l~TKO7d2w@8Sx z!id-%KwE8RcD)m~0d2&T zVLkfpqf20LSVwr6`U*~Z|G?~&0TgX`2Mrg+aUoMh&qimJrUr3XCOy{JOInDS9K*}Z zWFMt+l_CbG$r_M}9wx+XnHeeEBnDGTWLS2sZ$c(xAWQ4_Mu?s^5)4wT;8|`Zv}$?} zTRVSdB|BciS_?5*Tq1flrid|=CrH2A+ztHj`!>IOEw5O+%21VNZ^}j8H6)Tlro;qQ z6zLrHOw=0oZfQ+U+nW-q65lgsIcPuY4lPRz;quc`cv)Nv)-e~^MD`&>RqYkFK-*Tr zhHj0Rg>yDY@B5bolp3gcw~5nb*{AeXgAEgvZ*x!p!_J&cUTaBc*p5z&aXV#CqI}KB zVSQa9%@_ukPq%>^ffeknA;q9?^B8>A&tnZ9+=1r7I|PiIjeu!`m?Kvcq$?^X%4^!F z`Mo{#W%kDTd)W^SN1RgWCusR+E(6!wac(&sk<6Be+ z>AFdRHGS*^On1bbc#Rl#!s!p@&$1VB)bWiNrQhrs5r(*H<5an*qo~oLlRwU(hE8=uh#3U^+AcryUtdv`lP<$jl9byBaNq^Yb zoh;jN?gik#Dxu<;3#)G8VDU&Xy?V5*fSH4sE3y+(&D6JwUu#PF#okL4+jD}Hw=24; z#x89|QZ=ke?rjm1nSi08$D%c;S4~$Kimz))-G{2Llf*%B{erd|{m&32e4 zTvMBaQOpQ7o67~8Oci)_Cu~k)9(<9Cb)CQ51xzGjntal6r!^})-k0*T?x%AG9<}nH z2RaLwh`Az$ZUMSzsV7{?jfIxvgt>(DcJ_wDVIDB+#!&XAJ_m}GS0L!eB=%wd%OHK7 zCRmf$Uckg7#`9&0R4cJrG0>%q_e)iC+b#Z4v>T|W3jU`RY5ZhG4#(IE8=A(`k|wzl zCwlzGM0V#;wqHhz5#~p4)#VzC7dfgBw&g=3YhJPS=MK}^kl!E ziaCAC_%WS^DMor6mCek2qP%w9ibzAPgbm#})KJ*aVZ|;)bEEk4TvjsK^(&b@x zvHvwF{8R!v&K+l$KU9L_tK$O3%Ui&tA*N&MMrpcflR`1OjF0?$mFxQGfRvk8sEp}l zMPiOxlGj)odf+4`C(ZQ9U>xYQz`%lBP0=UYS}lMI4;H2#J;~M&EQ92z+h90C#d7_X z&|oj>b*6L@Fh>!S(rvx;O2}u$_;qD`%elK;ec>5dVtb;TddiYaHN`04Y#WsSmJquL zoKSkpncUoFPUwIQ!^g`YJS_-LP0we$^}Gk+Ywm*S+PiG{iXxc0_>y2vCtm@RgP3c_ z*GhXfyjL_Omhp`5K<>!e8L}IvPjG!YTav1Y7Q&fEL#kmvbVRAa=$NMlOrkZWgxduksVov&4R{@iUm@UO~q(^tXQ`Bz4@WWGorOP{a z*_bXDr0%H}#13;ZCh^uJ6QfYU({zb-y%Sb$nUN*VdZb|7CiwAiBzR~yvb)CBLe#Ve za5%b#^?9U((Uy6FHObus%oW58JJ(ZcYWzmwy1tC>^m>D`TkCDId**`}O>GO(_off{3x} zE?{mW=D4$ibXvj_#c~YWee+qQbZ5IU!(S&c%zSgwGu4bd!zl~*O7)0js1E59=tOSr zF(tVe|2&$02)guJ2tCynz_)r2PZvIhcOI|V9cc;(PrWQy^U+_x+(*pGCS_pLgWHNb zqssWs*NTGC+3uO7^!exgT9J=WUwQgS_@BA}}ob-q-bIgax z7ICNf$OKG1#RQGWACZ%;cz`jRoUt2~8~3C#Ul%tsv{wDC0WJ{EjM$Q-OU_qlk)#Ai zl8mZjsULJm^Xm&JH4zJSPh4T6b`vP})j+;WC0lz7PwV$$hP^cin6HR&_30tEdzPf| zdtS=(A>);UQev44`bKOcZ;CNz6T#)6X(E%wS|o0vBZ)(IonrP}&xalpW1;r4D-0U? z9jYJHLUr*ycE9W*Z01F4)FS3DV)prOk-LwarI4K~61%02g4ao{F~b`5&dLq2 zdx|F<4*3obx;)3}CHL87$rqtrsQB}A>m^_;5mWAZT5h@DP0?j!DSrwgxSTFh=98`^ zd#@LIoCP9g>~Yi`+ALz~sxVNDn7EfcT z2@)`lh}pBMOupxxu0rl!%J+5q!iChDGtqlYSehx+JtktP4_z?22gJMx^tp7zoK-cJRcTWSsc-3(o!L#B??6b_pzTu619E}7ME9pd({0Kd^L@bDA% za*nxFrpo^#wVnmclS2UERV#9Sr+gPB?GM22rPCR8)!@arpZ6P80*jXM-t zYLMx(s&I@L!)CO}1twFhwp%<GnR1qwHpDr@99W7T}T&lhe+LM&G>W-vpQET}bQ z=&uD&6s-w&a27Ch*7vi@LP%DxfwlWQVEQ=?GA`r^7(Z*rZhoHwm6J~kM`z6-0W%FT ze*^m~=0Dd^Bo9*aGrsQO9@f9(vL-%}#a$IK_cr~HH3_qvNnyOPaC^#Xco_RC9OZP~ zpzT^svM;O>N{+QfM~ybW`Q0`_5h36n7K3lM+ zQN*l3%*cMz6nWph6vO(f`8H#tx#eT@ls)Dg;B?#J3BAKu816_hbU^x%7b0d4cHx^l z;M}ekQE+9kBMdLqA|2OPLf?finDa$B@OtA(0n=ufU`;e)Ms=U9xR}sK@oBi4-}Swp zeA15A%G=jml=Qx#--f={D2ASCr>$K`@EBu4G2{DjaBgQLxVyT7ql-3iGr0$6t!6Q? zGtYpNk@#)Ciy2R0;d(wW}^*gw$>$Y;_gE1tDa2fRk;x1a!Rmf>TtoDU5M%Ev_fGu zZnfggay9>9UA5e9J5lO&Nmdr#7csvv(@w`zHB@N|uQkR)#C)EY2SEo{!ow;D=pof3 z=Tj@N=zJD4XwW&h;3rx$XoP?{h?q7vRw{JAZc=Q=Ko?o_Tbd*5u8fCcO0@xY-zOUr z-38W!%I19etVyPyaUq#F!;4xo_Qz$|=Nko`Mw){|sV>oLdmm;U`z1@6avsWOh?tk6 zHOCRN;qMB??2uH&m~1s~ywpd!|H(hf9V7CUjI%k(TxKl#X{O?}Mt$f5SQanAmebKK z7a%8d4QyOv2K$@zNJkV6{#NVCRO+3FaoXZeYbRQB4l#ZIS*AGfBTF&qrkc0A?kvk$ zL6l~viwy1h2*xdaRew<=?(iMe5 zf^lf8hcdmB|0wt7UsF=4^d zkUsUg?1zmU!gIw_VAUuAQ;wLIzxpb6PbgC?!2q#;7YjyTYOf5ky`ubCZcZ9Jjfqo* zHA%*avDD?Dn24St#>eIqOnDy-4|jfNmyM8+7_G-}qp2hFjaNa7|5;%}{~j%19wBC1 zypN)?<&mOCzfykZ6K7`BEs4@CvA z3rge^!&aeI-%v4Ma(^KGx-4WQiB@$MrKVfxo*6ND%XVBtInDwZ!z6xa~FcYEi zNnErKh&f{OS8nnBvqEomDgVoxW!${Xl&gj&DJ_OzZNP6M;_YZd)=kzXNfPwa`nZyt z1y~7jL5~>wWSNQ?v!CdTK;` zyV(#rJ&tYx`jYO0)hYC~Hrqc9g40(+!^~Xv?K&gUA*>DzHU%+vf0sdJcQK^;bgW>F zF=B4^43O(AFy>0LO8FqgD8_tATjlllcQ_?Z9{c~p1avYa^!Ajerb0j45(z|!S-N#I}BcmZRBnDlD@{JpwXobl;WzQ5so=9c*oWqey3&bP#Z z(1Eo~fQ^vFrPgd)=}NqtB_v{)9??3z2Y!EE4BpGK*>G&OIC37VB)_d;mcFfop$mBd z!%Y-0u81*PawXtVu^rcl81>%8OmA$#N-VyHg*N|V4OO+G7#e|czagTtA$7nROqG(+UO5a}m=4F*7%=4?LCa${C+5<)bF9VS3wkQEqO% zPSz7us{UOxilHYo4W`)b6)~HpZH1iybHVT3PSyZrckl0O1Pe<)=5y6kc)3Yz{NFuE zu%;_w)DabdUmO16+8!;%n%gqm~kK3cFpX?V*ceG~=)sJD^D=~O4nJi#fidkYIeRH!D_jhk8uX!?&alGcL ze5LmfQ$5g9_%?K>QA|XUrVvll?kW-7!B-bI!p_wTK(}f&J9xPPImP^j&GAc^>{Blw zdU>(1Xk}9bOn=0L?d>6LmUQFxZYL|He!}Ot;@lrH+!G+^3nPJlWfUDL$mH>_cLhi90QYQ-Chozt-fMxRJ59 z4G7gwYbc0?m>y%n$*Vtm(Aj{@ZEArmt$&#F_8(B1TKqP{ej1(iJs7VrirIc@Jsk3#0JF<`um_$R5UUTG z+>YtQjj}79(bH@@8q=<3Zf|z*0W`?jBi`{3jQAbvr}bu_Ia;|6iEG zG5>>kRKE^>bPWY(NoO`oZa{LAwa9`2aq_g3PcW@a#5jtW)rfg%x>Ne%#0c(T+fsg! z$r#z-a$V)U*_)W3#g@W-L#-LPN3@1w`e0!nwZ`{v4EV&41-G$naTte$K$8y6^lDa= zJ2ygFq=?xrVqy_fNcKv%t3tT|(^7t|@nYE%t1sM9{aA($-lVtZ|HfQf;zshPi{l!l@n%g10SmSu8$Tf zoc*tHj(0l=7`kZm_Ut!P#L$^uzD}r+fSC3E(O^+H2Ijh0u{CXsN!wStB}a%d4C+3ZtPnAAvjuA|A;xJ&n$)4|e9rhPKG+MRIlXF*^Ut^? zql@;hHFR1j{WjG&kk(trfCSvuCAGI>AZ^5W=q1%*=i$^Pr5g&HeTr3f9rXpm{lqiv z-W&l_fS8Y6cS_IRS;Sc=)qJPsIxc(OY0e;P*nct9v-$sG=%Q^KwE@l)O@#9CZfyM- z6VegojdzbsRobGm{PkJag`el^W-98!InVEnYDkeaO zwDrBOd@p|whNp@IYxai;);vYb=#P`78~R6Zr&ah`8||yi*uRxKv^0+U*BY8zqoNG- z?fF)}jqq)#HCsC-!0x%T;NA9r*m%?un!GY{ONbFY4H^S^IpWfK}=d;Z|SzK zk=)R0YF;C&n=&%|2)FOic>zOzH`Irwq73xDp_sP12ILyn6TYrafX-v)KnJ!rt5IP| za@S+|!ed)iTJL&zr7bR6h`4B<5wp0qgS6@CI&QuiF~%K~{kb*V>OCL-YfWakHKC#m z^pgJ98jA6FnFOgN^Wl1UH#VxXHBk@OBw2^rsG4Hmz{AU;%W+h+rWr9V879)JaWUNC z2WtNPd@p5sy97?+psW0M(dfgY;~P!E<@nzi%bA;id9@gJ)b(X|ezqZl=4%k&bABqR z>ucEgO?04Eh#0*!D5|~XQJ}-h?H^(zp*%?NSP%n=iM^H89fVI0@)gPOMu9;9sB zu7F#x(pJFGZesPp|Jaj_=bK?d&199qt>-X$r0Cqb&l5IuJH)tX?h5!>o5X=H4ci;%sviBShK@l>!J3Kl1xzQz ztSh>fH#>AAXKzx_}2jk!O+HLX{-%KFpsh?ldoP(FP%=rXgCsMzW2&?}EO7$xhB`?_h3{nJ-5jC~6Ij zKv8S#GVs9p4~FJ%wkUT)fJF=hUf;-iK5!&$mw$yGS}`imv5(+>XVDtX1;V!(jhI@W z{qiA!+qs@?O8M*6a&B`kP0n@42?fQ_Z}ave=5Ow3lAau%(sb2YA|JhRx7>ldZZH9vEcQRkK}8Vy2HjAw%up}s)Kc@bk!y9avU zcwU2tDeRtLXCm$W6^3cYsFn=Bhh+(3D&n+=S&o>GBdg`3J|uHn9ZUIl=LwfCS*95F zbeW90>T!LINfoN}&_$yd>e)~qn&t@hS?z;qO}GV4?q`p#btW$9O>kYcQuXO&Ihaet z-%YKES&NusJ>JMu9CmQ!*zZ~X<+-Bx;S>2B_u~SFMxZF>Uu!6az6dDhY4!ma+BFi@ z$TqVBA3CEz-A9;ycb;nOmonJuBQ9F3h)G1ugMioa0ggL3FvGZj@f_LNclH=!y(gpZ z8;YR;Vv6zA(-z#pe=*@N_QSopRnRhH8$0@|GjU$?4NR6tspi+*g~(mvnP#_0_%=Hb z^Qzx7`CgM9Tu;4HeoC)U*{Hr=(m;m>8GWt&S^j@xsB=5>uL03@)FqMq(%}{g)E`&u zWZT`fC#$T!LhtvZRXz2~Vdq@&zHwY4VD=-%vA$To;9W8o*sSKi?_4E&zg|n)x>$>$ zl_@lTL!;{SBB0h#SDn7rXw}f7wg)k+y&QBW#29=|9Rd8S&MmqEU~3tcF)dINa4}M3U#2U zHS|$PAMDhcS>5(QXq!dw_CW$`(da;8pEtvidm~g1uH{g`ir*%0rGP0yOfT~Z@~+O? zIj_5Tdyd~N)4u8@`}?y-Mxz{kEKP(g?!BQRhQ6e&)``}1F4%`NH|K)Mz6ADBX9u$V zbu$du*iGfUz6_juihkOpRRX3IG3J5o={GN{KvO{);vgX1YGTO0n@gEUG zUj)>e!&qlSqZ}#sbjb6l12AXXELd=-?1=B+7Kj*Yt?IVy4j7b+KD7R70aJ?@lGY>tL94CYdUVz6+wYL2oERu8KD1Is zBT$87MGSp=Qfp`g$|+Yul8)$*h3q~kikJpo6Jpp+Zg#}hP?MBk!;`}C4is(_pHTs8 z1k8KHMAzQ+AJcgYNAlHt|I3?YSN7kR9&dJ+(VoI!cXTRx3i|X%s_K5#6k@Qy&F`f9%)?VS`4&t&MZpNvCW`bQ>M= zRI^;!cFSEzSgaOKffFL86=Hg(?hgFqw2>>oZ&MU|Qg%+aMJfx@;ArHwN@+rL!>xoM zB*oCg3XOFx0Ufe=%RczsI2`V3PGcvc82v)bCPw-nQbt-+X3K!Y?kjqlp!wcLWZ0KtWG$n5_K0q@b zv;c;tS0|$A`OK@@WMo7N)a8$YCMC;`)xmNsl-TLNW`J_Ul}h+%FJj(^m|=+dvCK$1 zsVttm{#4C7TyK$$nV2fI-^6n?fAe#sDXB(Z`dN+>Fa6Zv-pYl1|~IK-4cvXuTl7|)qvx8u(YGwJc2p96pCE4aqXA|~vt zC84t-dJfkXD!OR?hGG_XNP~be!@*%h8@7L*9ZA3;_lw@ADYG6|!hX5*%5w}|z+`A0YpNVq10U~BIVy67ol)7dnafvNzeu88rw|DFxMc2rD#kG%O z;aEVKg^(=%hz%9AK25jMh`85ikrNAcgFZJFG`{<@8nq5&^(q766hB4TYj-)g)``}< z6fwIIqpSWAxH)|zm#tCCANtf^QTS{arx8*vr_z(2-SA(mg^*#V&E)|GPC`zaN>2u7 z?gsxAA@KcpH+Jy^>_WzVgC_}*%CNg?xYhnY;=pT#`z9SRu3bL{+B9wA^bn(dzf94v zBb57OwnIu2`Q2ul5$gbSJ+NMYV(5^%(^6wX)e>$>Q$Vsc1V*HdWqq_z;qr_DS$Cz6 z(%Yg8>KetPGd)_sWFzKx(d)p;pl(Ik)lF(%=ZU*wQ`&{-A>q_d+OGw8dVahod z)X?^p80#FePOzpJF<(M+1M3$ib77yXd)?0Kkl^tSLQ&t~TupM%H5HC{ zPXOn88`*E`ok?@NgdB?*scbGO0auxbDHSnK5c6xtmcYvkcX7@b=vrzL&dmwz#Ep7) zUM3VLT{I`|n{gZT(j~Nypoh5wIe_yb`mDpuR7xuJ<;TFcq3hWTCtS!6Jqd9;&|i6d zW(lw@qA$=z#Jobxu$I_B|KBOxfJbV6Qp#y=#rh;JaK<$mErWBaH7C|R%}Byx6hF7s zC3LtW?eU;OGw1H_gOcK*&|WK^y{T{`wY?3A`Ndhv4l}Xl_MPZ;8j3sZ6Jn-@Ee!Nd z+QUiisQLU;UR>g$1DtAmh3wjQ6XNY{K~jF23N61u!B}&<+MZlpYf8GHv_Y6>I&?iV z66QfX`?y^jGH{Rq39o*`1#d2b`s1QCZA8p3#8?as4t(0Mm%E9z9Q$V{aPD6QabudU z$u3^Q#Ywgx4aufL$4ba9?33z@Co#6Zd1`5rM+f(zjP79A`Fbm>HgP3$s<5}{ss5dOw zc$h6ucOsoVB_!>+iSpnCB}_gjVkT@5emAWVlbhif=ydr2H}JfgUsbnMT6flq``Ub5 z_VXv6U06g;o0e|w*CT6!^hmeXc0$>;CN?dNp1L1g8~VY8acS(yey(H)jvLLppv|SW z;y}+;+|cIxm*Bxi(VA0nf;C=Dw*`jM+0)MzymBqT$I1{frJ%V!$WMfj#!jKc3Q*b{grN+fg-tTxT1%P10Ys z_x5`!9fTHIi4Vfr7>JD0C$ur+1O>K-tW376h zo+!=`VoU6B((hK33hmG-8y=4e2AiQL+4lO*WTZqwycSGmZrnZv1-Ha!RGNqxKo{+M z&mMMm2e<);@glJ8q^QhwVV+N`49vu?I@)}ZpJycK3k+X|8tS}_(0oCalZ@R^aPAR6 zqRj=?a)c8p#r~Yo1AmyXB>nfYyRDe5j6lEZdbm?Xg=T0acP%m@19*>P*4 zyWWbd@BbHiSzm-1ySl-vfhzWKu05ITZa~;-H#U0p0j$3f;{sdag)J}#G3%Cg%r}ip z<^pgFY_HDaB8Dtu_G)G-s373QD4eN+<3j$GW>H#V6t{IN(yJEp0Z-3EzXM$$U3( zNT4;TK>3Jc)mTb3%77e*Y(@Izv?8V_{=k)w`S9SNAB^pFll>ZPOU63rlczy5Sy#6d z_-iPpi3&wbBx2H!eabJ=Oyt@eN9WdVDc3S;EhFppS#e+qmWBk|kiyRr;>j8c{WlS> ztcd1RYtjLmnx8Z);O`7?c)R%xYx^7jJ07^{r$n*xd0Sw}QPG+a;PL0W|HxR^3hU2FGd$Acpj$MTXZ(JdJ+8cJB7d8R()FxA(pJfLX z#lgxo;uiQLV$u-v(@QEh>9U0DaZ1hSxpkCf_DEqgczZ>N7Y=z2w|#9Tp)@2A%CRnc9z zV~B|x*_rFU=P6=t22Px%M-&U}NYC?l30Rww2zx_9r(j)-uoo}`3ajAD3N2VWTmxRS z`h?%6N$P@)pu?s<@S&d=>kJn$w-HnRHb`#1#FaBd%-;@66kp0)m?_?~r9IzblYa$9 z{ZO4}c#$bdnu))iX{Kb&BnJVb&Uy^(e15PG@^v8_!+OalQG=+;4XO%c;MrD8dbLdw z7VSP_3KkESXNDSarMRJoee=#QiPB;p{yZwpUxY5k5PMRCEu>4vnUQ^G4M`(*s~q!i z6fi26=TOrA89U+fPu6B~3+(vZ0vk?xfoV!du>K%o5=3jBBj(|r{_@SA>lOZ3bF0-b zQ2KtU1*>7OPikU-0t~m&VZyGiR0+PSYYmAn3jbBHzhTLZ7w~-FQ`U909<-T` zvd9~L!?vdkF#1m5w^@usOGInx5p!Z|Cpo93Qgp+^=EwUDGQ+3F?5FBu(y0kL#68%7 zc<1Vok(@cX=#3@4ZL!q%t&?C)H@A22AoeQz4YF;XBSJn)CtUp5?Oj_svjQ@5YkDZ3ShL>ohQbVIK$YlLYpv)CT`CeT0o z4frf*hTX~YP!On&y+2u8v`7(Suoh#Tty1zEJd5SC4ypO*5&6;yy3Xv`UfpGf@lk%{ zxg*iU9XDQ$g-T6EgbJPqV8tD^rU|w1%{-%6uWr^5^!hn0G{PZIA*-NWTq%3hS;Sb1 z7)!($bX=4F?(6N#Khp5qoR!LNS-P>UZC1$|BD9G2I49g)y5!?3bfkze$;X73=2kbs znnlJxBt^^=R){;z5i#x?GV>q#-V8L^t>#-7 z=W#!Kv}4JgH8MINJ@|o>pwV@rV=I!p!kBEq;uqgVZNv?|4E1gcd$JxH4)EZ|eK?x` z2@YW6a=70H_5l&IQFldaJP`Ax>TZ7G%0bcr$!h*oPBdqF&Wr8ZxLD>i9pxoPIg<)Z z3ElhBiX17#Tn=icgoU*gFu$-XuQIwfn>@cYs0LR6S@jXj**&n+J(z7DEM^Lqi#yE+ zF~Rz8^Y30fARV|F+k94nV#`D+JEQA7*`M1QWLbkBJm|+Oq}vTyi0YG3NZj z$(Gz)Y(jh^b;wS04*~PY$&}p5z0I`h>H`yi2M_Kw^v3>y$2KQrnH6H$wQ{py%@D-+ z%=DG#y!Dc$MXUJ%e6gb0X9!#VWT>poi$5^6iz`XND6K?oOR5zngpQ<`X!?(Et<^m+ zBZ(f9nS1?<*@)e3A+%Tq8DA|y<@%MgpDGqA7jF?TV-T}JA z&b~S6Et8*V2FX5GQnQTe4Pr(EG45Ehll<`?@@jZ91jJaA=;y%n?KFpXk@Vyx#xDF_ zWoN$k{$omQJF!-M)ph|h4Kc|^(QgG`)n6hbyfSHe& zH8lt2@8&1VKCV;qFZ_neEPfm; zy=2-qdKHY4`xKmi(5|5WRi}b0s!HV>^TPtB{Z0Y10x?Agi{*=7W(yc@WH{?_Ac-|! z#7n8Pe$-h!SS~yU`u3zFkaina37GZUet|5}ha9l!%y15}g1mV_1)V>1FStL&vtXQ= z6&GvtM8I?qt%*j=xqA|6WVaI8+okv@^uEr%cdKE?=JjRhJc7ay7h)J9hYVDF$=1CC z9r^?9wLjxJxBJYBaV|x@7#d;J(pR+3Pjg4meKadcbUd<3O8xfP! z+$8Na^NXzW7)(VJS+c!XIK!u35zIKPci6GzLq{_h9~bsQJMmyV;E9P|&*Bo0)bG<%zWI z$@AVO;Al#~|Be+5TlADodg@LdX}t%@`+0;69mzi587KQ>cv`vk*#_me6dm^7{;TW( zwS$0pC1Q>vrf65PEPLogrmel2FBn|HsBEG^V~0jSt?D7vF|CP@@&Q} z=Cai*+{y0y_0YL%G#MFkh;@Abm0b&G*gYeUu-RQSFz~gT)j=Nu*G%KLh&hLt=UorV z!WA2srEY5eLC`qX@ctesyti4oI_eH+cC{hTYl_)nZOp-S#3@0$o1STNP3ytAZWEb% z_Ya%pt^tFe<4hIz4A$VQ26P)fn{{cl5ioO7gbmFh=AG4f+2pPVnJvC}t=&4sz6m@E zK7n(T8GlNEDp?GB@l+U6M`z(_R93Qw%G#0A^KW5{|4zd6EoYBa>A>JsX>4ZVLAKzf z793l+m$gh17j2=4xsI5D7m8$eP4bz4da3z~GyK>!4q0%taY~yuM6&t;}E#*>n`F`MyoCrW`Te zlU~Y#QtmOGMqx;mF9*vG*pKF2uN;BB=r`w@5!VtAXm;-ho2OYr@e>x3Tel+zTfYXI zVMmGH_gHq~>nyTn8_tvNcv3*Uu~M^N%X$fzBjWA(h%Q=J3DbJOSLSm+HGi}G2kSg7 z7d}jX$H@;~0-7uyQ5_GX?RG$pejMC)KLDFr+LEQHvYfE+6d_;KOmfo;_~DtszF1;N zS{2SAuiI6!4abHG7!V&GFA?J#;lLQB>9cGIz6eS**`41Dz(3PZ)u!E9$nS4Nv}Rs{ z^*9v3ur>oSy5~b%$95!Zz-vLn?$hTccFJ`JU^Q!)jG|1z8bjxf%$F=D0drD}r+q+7 z1@_GJjkIPnuy5_Sc^13i<#H&Gmhk76WP=+jUSH9?4}MvXu#qi)Yx`7H zU-yrU<*1`DHBUm$d47O%b05Ml{ve!_=fcXJ?*GNS>2Irg(tj7^&U^rS&qoWGlb@b* zxgUZAYqG?W5v_IT+2s4msyaEc%^uu=JS5Jfe9JM?RwIt@TO|H&b}tronlWNzmPXu` zR2w!3TS?+Z7V?+o58!Xc{Ngfl(}4Cy(fKz6M!kkv(~b+66odAJwS6UEk~&|L1x%Ps zzE5aRBKx-?T1StQ!pwgBuTRc`HThuz#s)E6!gg{+3oTgJ-=%znwVb~>-Ic#oYQtoF zN(J>M6EYXCw?|LkLdKxeka6QIO0jqnDr`o@=VwN>Q+=Y!X`GKcnw<-Q zx@X{KO$TAd3dNl1rIsZGxe(n;7=T>YU-&jvw?lc$tBip06dPkYAg0g$JMyoLKKt0b zjL&YB1q1ohy>L_U2IlS#c^3&w-HLC%N z2dQA>-%tTFb7Cf=x2l_Pd)^m&qq-vIRs2F(-fms?k6js`JpKr*G|E$*SgWt9H9QVs zwl<`G80x9_#|fn?f$jXLdmAmSh0gBXbISx9rhYFa&*=P6}KCO5S z{3{SUy;#J|cK;wtn9#yNJDef;;u8FGqD)nAb%Sbz@-$q#W-Dmh(V1TIL03@wJ_neO zUZm5CYRKuhjr;iS1`n(DL(#%GNLoe&Ou&4Pf)j98z#I^p{rV$jtC1Zu<>e=4S8y4h zpzjZ*(kQ-gSG=k=?+nDOu^|~4JG+HiX@5OR;8*B5h&ts?*!Sho^nN?Q1JX~2@?kcnNz=-85yTJ_`dp7d|iDe)HEK(|9QtT=gg*Z zn6EtM5W#G+)KBSI6+kKW6)?}!E;2!TjG0@D3h8I0F?rI6Mc`mZ63h)qrx1xfNRWFE zLJ3FM)cgZkTzW^{e!rOhkuwMT>QXrMh&lL<-H8jeB1LIGVmKpBLmuN#FwIf|q4A`> zl-H?3rciwzQxsE2rZ$-N^a5|Lc-T$t8Xc2*PMFJ8TJ9+ksnGh13H1in0XtiUkxMNw1(dEB$PN-!JSf`n^g)={R8MGWJyi*i>|5h_U>riDjUpyAJ3#CqPd zp{T4&yiGj0Y>ZDr&-5zMa+MzBG$J0Ei8b*9Qn^hc(aBx&_u^K?WE5x8#92MJf+7yV|&wZf=HEd{ch%t;d%0q?BZ!RlBJ6H;D(anXPs%*4r=D`09 zX!nH6;6*m7_^)FStPDKJ{Y2SimHav-Hq7Bh6HhQ%!8XF1?{`ug9~UvSP6_&)oQ&GW z%%jE86m)pWg5QWX&R3naY1=nD7iJWzgT_7q_aR{axq?}Bu>DmF=qla-VTnH;wKJRq z4BX~0;u##~HNoKcx|DnSk5Z;}BprLtTeNq=e&ly?3B4uc9GGiwhO(#az#23eMv_jh zI)X7c2zl!wVEZ~Z?0HiOyPqk8XMSZcTzDOVHT?0Mo?j4fsT0`I+@H>2#00aEx|4F@ zS^zaqrkJ_(L6I7D`z8u(zA7sGmceC6rjfHu&Q=xfwAOno4>Tj5LYQhc7;9XF20ts< zl>Y#XH@t`c+(RH#{}^d;TmucvIu2tzlfz^ajNjA4$ywpSl%TtaDfOvBPCh>9M?nC^ zp4MD@ih=zQO!XupC2~jL*P9Pg#b3abOeAA?7PStx3dinT3t54=aK7gllqK!MzIRHI z#Ar$G71-y@VTuXnN)=M#><=g5ho3F=(A)f~!GUF2@I1j+7yXsu! zR_Pt_=3LkXSx@BgAuR{&E|`RaU2YRm#W%Puo&_Tkw_?{BVN~%sC2kea=j}f#3Ff&% za>^-%Fv_;Nh;b;_pgq3((8{(~M1RSS#^+xJiJj;tfm%eR(xZfJJc_`!t_#=>NoBIj z{C!*=TTs$i=dBWcY;y&TzcU9{otDBX&wp~0R>eu>WI(|NT}Lr%@>2Z?PS z5h^vsmjD}5*S1Olm#mzM?TO33&QUFj;2PV9=sa*fjO^*6^VCk+^#QVw2(l?qN zMc&5`BH3;!9Cx{iGj29>)4>OKX=3NGZ_Ub>4D5l<*U#}S#g*T{IfA97!{)j!l35$RQ1k6redof zz2(avT7TdkTD3z4E4}N6_Mv~^*C=hg9cki-GZn!05f~aNW9bNEeBos;EIwu|ev@h~ zzEm+zZ0aj1zJ?!zAl8_}9N;lF1hf7ABjFS0MO2+~Aye{P9%TmTF}DVS(dHN#F2|!+ zzY;!?OUa8j6>#2{55Q{G*-6XaO)Bk|s^R42DdJf+&f;M~bHs{cjKt4x=EL3EBOFGF z$Ji50=`=EF!=_NNHwu`;mot&3=WwPek4Br5WVp~EO*sZ!Pm=Vw*)33(`W)JZD{?Qi zZ{8r>eVGq8?u{4Uy$Iqx8BXG2T2~x;qaUV?i{miW{Lj;gU}pO+5n5UrQtCqrn5kzK z;YRIfCN8oTEfNsT(|ZXV7jl)$TeIt6Ai?J>upKMxDsYA@I>(YyVf;8%@rBF!;xde05RZ*C4CP&>0$!B6*zo37K#2u{p6=I9`w^AjsR^Mvw zh?`~^3>O#|Fe#Mhbe)!U{gAyk7o1nbF~=t}O!u>U%zEEd%)w)NSm6NQM=+gV)7%N> z`T5T&UFF{dU8?zvvri(WxmuE$pu?aao>JIQB!!pj=|ZvE9C$ay3WCPU!;sVDLVpOU zxUZHaEea)&ukucqruaZK`)Zh|r0Ou`O*X`1y?DDRiP_u=?MX0chSEZzPO{+Xm5)q? zy*GU?sgy=f9wKd5QdJL-=Bgae!t}tNDMVLWi;?mUdCV$PYDfa3r0q|rk@}7jN2emw zgJLAu`yG9%)xgrW=ecKN=*nTX5KQ;jMM9%*VS?38ADNTK6qvKI(#)!H|DoMP7NWRF z273mlqis8sA%F5MRBH5r!?3c1bWLMC49VcIhmAAw;A2-#$lp( z%wB?t+I3Ty`}04+YI0iJVPM1Tjrm0vJzt4zXAM9WX&EtADMI$NI*1c)B74Pp#7-J} zi+iTl8k>=eO8b*7$Sdw8y6gNNt({hh?1a*|c@vNE<+mKi2xd!bt`MzJ5oD&2q@`e0 zdf8-U=KSu>$nO=obj&1}cWub{^l-3$`3jYrNOR9ds;37I+E2hAU#S0YC&O+(*#D*y zUx;xEycvB8j|n1}r-xgF8*a)v{@S0%G)^p_P26mmRBb!dMEll?7s`Z`a`ot$j(<|@SlC8n^^TE zUh&=%mu+|fNBaZ7CQ=*EHRP-6wfxd~gJAqVvjN|7Y&NowaA4f#Jffs- zb^;q9=n$F=p(FF5?CL!TJt5{W?MlticVr|!@=66~+sDCR4hB(+Ep&ztMTQE)a3!$_ zV>eI|{9<#DU|yV;5}AA66aFOH!Sjm)L~K{~s{iGR`kbMDBhk=%=3b>%P%`AK_5Fu&{MMNu+oLdGJG z`RL+<(t97$4>})c zL{jZ58$_1TBS2xc9iC8Bz+po9NlPXe*M@lE>wzYr9!V(M68Q=i&3;H9bb3xD;0|D$ zmYilbK&pxaq?>kwiH8LKa#jvUJgkIqFaCn{U?Vgoeg|tJG-n3A;rPgnFh*k*);J-9 z**R0>znZ5mW zh2xIrF^}3uPz?_&kaY1K+U;07u)R@irWboCWHIb$8b1>u|Dtku{C*H5wG{C%N#Yb2 zsEQvF&8N<2H7sRdk7Jl89L5Z|#io>C&Sxt-Y>A5&iX=WV(f3~qeSsmRC{`O{I`)|rN4nQF@0Bko=GE_lV zwK86(qJ>Wkk-)E}Y2u)x3YZ?*2NB`l;p|J^6LJxc`AIN8ymL}E>NyCtCG(lR250Fv z-U%qivw)5>YK7-&syMFu7qI48w+@qZUxL{^S{b)b{RW}FktkvDKXTA-1GSGDxN7V_ z@YvA;A2M$u(Q;qzh&z;@v@U|F+bk_))CN*k`{y$&u&n6B+5mK`ub$pw-U6b}B;Ivd zE3g?WY)3weVHLz7cGd7><}PN0MFjJ1Xd~p4%gTYuL6AFE3sGZ(8H=Nl4Ev_7;xQ5@ zB_%XpDG2>n9!^mnUcjVceM(WH0|C~!H1WMSn5qX{Lqu<8kpm{{{ic2<$kmR z{(kCa;-;#JH(KR_8PP`zrR4CZ?E^5$N<~aJDT`UmdBi;%C4$MsZ&H>Fi<#ONRlw|M zy^f;RwxEk`Ikd-}N@)BliMKd(!r~1IoROwxe;;J6BT>nnxo}w7MEt#BlDI)W7W#93 zfs9xS+mvbIWDi^MEWObjrjW;I5zN)JdCBAZZa6+0QAmuNy8*@JqI+^_wC#)cknLCx zH8;C}RdlgO+2NO!Tq_0O%apl+zR^FlB8Z0z`-=V*dS32JqG{LexV z(N)Nl#wVhyleN(fgDbRm(l&@(77kttonWG(gg^O8;<)TKh)}x%0z|=-{21oTib7^m z;!RlpwiX5_*{B>gO2tEpc(fE9D|kchv||yeb;Yj{j>nE&o`7Z=NwhLejM%BbQKg8KY{MBDY$4H zh0pf96t%T%=3eMWJVrn;qLN^Nml_B%1Bw{?V-oOR%5;J6lVNn`@JwW0Hk3QCvx=?> zqevL{p=OY{M|4kj!;s;fG03hV0*O2KgTbD+(2|bup$Zoqd*Bi3O8Cniam#s(Gr^pz zPZX%tB7y1EA|_*sIxL~TiJpzkb=0^Ok23Ffpu*p6VA!n8nKHP~YlO@}Sr}imAC>=> zftq=d$f#~N=8T5@vcHQ`+6Os|4v$$#Fw2$}3Jl+x3D#UHVs0nyqGY8O z)BRS;)P)&BG`g$>DJ8eS)J-bfo2KSj51WJv;G!3T9HvRb$cNEr%eU+Bbmb>V@1BUU z55`v>-b7NIZzgKr(Wp;*rb3*mX%pn0?&Rtyj;JtFWoE&dJ-*T+G)gB(}0 z*%1|s%X@!7d{jS}thT^j53K(W#>ats({>Py!HHPG2T@^i-z0JJ}&{ z!UguW?|{Ov8j#$e${9D8-LC=nSHU2-;{%!_0`c;l^4NhG&Mi|JgpN)FJZ85kmiwxQ zAMc!t+0k^_bC?4J^Wc1_K%x11%C)9K=CZ|XN>cG6ZL#D6V($nvPd@^ETm_S75qUfj zDhI|^gOhhU^!mPlQ4_Dh;7K|7daMNkD@eG#w-FAou)yOxgW>$181C6vOyw|s1oLt8 zHG$nM1!2j-LS~xxUF0Dwqt`U{p{BRFpg+Et!?21j)`{FpjX1vbwE?jEI(;y3C5@YogiT9c%gb}0TZ-C6AEk+MB=$R z;2QcHe2Ax0)BZ}B0^|T#sDSN~s=#XhZ%BXp87}9AiG0RiLE1VA(DgbSZiY_AUuve} zv6DAq_kEkVN&Cc)CW2txQ(^@_(oKY6t_4i>VGkzkry08UP=tm|ki@n`8B}Oi2J`L^ z;TREI9(q{;HFCYcrum#D%V)gk0o42$g6Gfr2YnvKc=I&_JSCwIijvy6(NO%ei6I!- zeocX@vb^xy=X_?`#}FpyY%(&N+K+1X|AQ^E15mcU1Xx8^RDl9^5|)EqNiVS1M3%cO z@$M{noN!EwSRC}hBqCZ$_a`BbnI!zAuZP2o;xTaqqj@NY%&~FGL;HND-*bR2-L3&& z<%R;QXxvE4v$YR(?@!MbO zL3gnwwmI4g^*SHGLqP;(q4iMyi)7>!$>6AM{I2u%L=KZlF!@s^Bxhx433j!AU}7eG zMwj+oLh5=F;4!Wn{*IKwelv(`2q~s~@>IrtSIgn<3u)}<(*)=ClYp%UUt#6+P*mHi zi&kAtK|lN@K*3fDk2~JVJ)2zKzP*rOPHgsf@ZUFIFoq&}fzRfse)1W#?~O8tS&=V| zYi3r$D{Ep_@>UtUttkgpUs>FH^(Tz#*TWGfl3=*6AA@GZGKt$xF!8&98U9rkUmYYL z4D#p5Kbvxb8Qr4hX!2&i;M)0Iraig_d9-_@A~P8d!zN;~0vOfzdfcRC%aw5lkI3}j zaLPp&+eE$utMk%g-HPF2qZ%`z7>^RCzn?BX zcVUvaHc40fsQfRemGWH?pZU?W63jSDbw|ILhXRdFIZTZ7DeBgmP}HE+fttw1iH)k% zcX-Y1I@vTI+qzf4HkY#nVh9|A3q!Nv+b=8e$xavXx*d+<`QP=$e=MbNXd&O@v4$T_ zFTv2=RSpjhzZH1A%Vu_^PZo$CJw#f=C1A_qc9=%$Wyu5KV6>(T+%hsDAnIpuJmEDX~I59X&;T!+o@E93CNr@`|%BgPg)dKxV+00~m z9X)tF7Ok3>jSgk}hELAqh-K-yF!}Y@d^!(x`N#Do4C=i zH5;wAJ@8CF9+=`7#NT+1qZ)(TIDAA0RaP;(pJOrr-;mvYCZZs1F+?!@fFgvCn7fR0?N(D~N zVjyAyvwW-yI+ip@C79L1DzQ9{S&@h?95w`rmT%}lUJ80MSB=BGU*LC!3wH!v7Ki^mr%+3{$g`#F1s%Uf;Nt5NxjlTa54U^$gCFKfq%HeAx>6s3B#Y%BdhSCg z+;Nn{#PC}VJAx5i5(^dDw5jdZS&Yh|EYY!bsUpd+cf#8~RUq1|h{fhV(6+Quu>5!p z+I6uTv1vYXIX~fSz;3+dQ3L#Yrvf)`g`jBQYc_D`4IBZ!p0MlZHWfY-ADLGqSIAfe1(MNH&(Hk$}$W?F#IazVAgiYzwA!z}1SF85J%h!zuf z@(ZxNxNK?2i6(096W?J&PCxvcrHw0PYoI>E2fvi7h9l$M@X@SBB8iU!3-wfpb`OQl zQ?I$v*g0~)8y|wny0J@W6y6{>y)}oi!s>8wxDmbCdywp-KXa0i+vI~haIqJfR#%Z7 zXgip7Yh(RWTl!8R<3aqm6 z8JNfFW7S*fqzI;o4f~yOZg~F}%ey9kj1LWl;=Nr}^x_7W1 z%1CN?>LY#Jb(mZi#m~hT{)WQX)KPeB#6#l9V~Y1mFT?u6Xt0nZqa}Y6_!l~oV9FC+ zQ?{%&r;2yxF;Q8>CFD^Hl8>_DFl>h;J86fJERG!81p739!G})<*pKWF5_c}g&Ia*d z@?;dgcV7gV@8$5@Z7#TX-9|{v;#YxH{MR#N=74=_rU#7ALtTlV!36W zIQp3a-7L47JK~CY%oBn+Ip&~4WHUuAd`<)~#|j`MPyvY!FpBs;&?mpbB*mAEv6rg& z>z*p`9_kJSK|}D%U{CyZqow%gB_%QYZ1nk6AdO&TN`?wLzAT_xg!#;sli`%hhfuUQ zDuFIslMAd9Ih*fU{ZWNe5Ic-+fO#2OIPFt5?BA^@UOPyMtq<2g%|Z{@Ncwi4_<3Ua z@$`X55|Ez%TM|5#Z=6b9WHCJqX#e~CH^OzEX8TV1`9CU?6uLGnG@<(h zn*`ZOb)w?OJ0Q*e9yAqnk*qE?eCSmVWWOY5Ptko?x!4H;E<9rDe@KYeb&!2q-#PHb z>Ud4uYP|pEXJ*>XU=Aa}FE&jCV;I@$m?&6DnLI6EKDBw!<$p01BR?!9@v}K}%-sa8 zu^n)fG?=>{{tFIPRZzab6EZ{Ek-6g&s^#4g`jJQ;Z}$iRf6^WPe9;>0{B{UkbDi|Q zkv~fw(?KxW@l}qk%qmJfu7HuSNfWr9_>cOb6ic;I)rgI)?w$Du9xlK!fo84@YuuwU{3_2-;|)y^RA$o{Vko|iWhp5NEPGlRWxF43yjui99F`ot}TIOBeifw)!P44vl-w|Ya<>YtJ^Bt{JKl1^R5wH z9kmqv3#NgTVl%YuB8@RaB=PF+B$6^`C77?-0#`SO;rHJW{_{@>ejGlmdBD8_7kP{W z!Prcp9Z#4qrCO*wX7uDJYL`KSs3FCIWZ{;A{?K=jOm3d^h7IE~Bw5U{!=Hiu5Mh%+-;L9cN{@Q_+#ROx1>WOrN7J?R9SiSAJl1Hd5pOVq&S!)zfsk z3c&+ffNj3mc5f~oaY-M4I5idDI~@t@eJde0z!pCvjkO80_$@~cKWWPeMgpHpF}|{p z+NhMv2;O|7a|>leey8KnA<`olS@j*-N!s$Sk;Czd$HZfJbpaUp^nyE461hxVgyYO~ zvE_nkSfa=ue%4mOztBmzH~&0%7VrWXJf3?6ya>kA#X{Ixuz>PElEc{5DbemeDWZ4T z2Ha@;)a&4oR5je%WPqn$lEWd^1z;813r2Iv&D3od>}{ltrzhFqoQy+ovHLT`KOKjE z_DkUl+uFHFYZ%92wh_$Z^QOWjPv%gg-efan{TJtgeIJX^zTs`urn{**xtL>Ww%jD#B90-g}my0uN&%i~7 zO8AY127XOVgzv;UFY?-Gd|_5AynIx|ji$sNDk)zTE})kU*L%^J0+DX|2d_nF-A9 zJ_PRXzk+`PujMe~M-xIYN{8KqW-Av^CC!;k$0il#NZwY*TlZs-ltw2c$dG_%vWITF zY=$jJlk&Y2pMXs+?=+Ucqs*4znA=0K=e&JP{7oSCFTNZ#F9*= zcXTv87s}|CTO?1Fd^OW_`atSwAy6b;`PF1aTu0?WTPv}eAj*hew`bw3j6oRs(OmrZ z_s%SUKb3FSr;#gFCz!FZ%S5z2U4Qw;+d%-mBis4?m_H1SAAacUiK zXbSnpG$xTFp)xL+(MMK=BulWHFc^MyK8!1WA9Eys@vx2UHNZ@iAYYT9AQB?;U#>Kb@GXa=8lv3Yh+xa5T_ zHNrWAnYksLN;mGOzvX%$_IkDAp(LJhXCwHw%VLCb>%I#ft7I@U=p;eVlma>_+XS)Y zZdPa0u*d|Q6i>q0g&Sao^>FU8xN_DXDB0+WS11g^f{p-T=1LdZp>8JqqQ!$+S|NeW z19;Vt8ei+oCz$bD*xx!;dhV&NzyTqXY( zrIBhh4g7-H#o^_UcHqrctpq5}p-I5g+fc@q?QSbH!>q5H@OTnxTl@PTdM&tzcGf;dw^wzc`)--w z+{9O)M)7s%-vnc@LQk|O^sVEc!gOZ!g->+W$f-<3T$9kJz77I*D&UxvwOnb)bJ8ai zuPwoq?M9N;l3_9Haa@W9zB*qLHizCq<=Y=2zYRUeM~ZAqzFgu)^Nz>#5X|x$qeX2a z>yot_)0q_`X}WOM8fIbtdr`K_4>&iVh!xajA%43R7<+c2(kXhdXRk8X6_F#o3Qr^F zp8vmQv)t-B_y5QO-i+Q>0_wRKzkAgROa602&qthq=EF)b z>+*f-gLWreq#tw7Mv4Cr7!!0T!#YUtVP2^rI_TUwOnJ2)yyL3 z-P^=9UxWlU!iQ&Sxa>g@EK{(-TO#WqV@fFYI=vR3Ha!k--W{%8l)%v@^&DocHMc@r z5sc-(Kf;>t3Zj;?nM~T8ePFJ?iSB(CNVAv;7DKU;S{3x(BAX^s7dW>2FPwB$$2$V@ zz+OQY>ySmINLwDSX;a5{->!$mGLpPBUmMr|;_q+r$8eZQ1k)Q8B+QUg5jA#aG65T| z1AT4>CGvd3VHTy3ExKn7ypHVwR+%#OwG@7=seyk-;%MLV_yr0hpxrrR9H)V6@~(p(PXWXWON2*&-Yx#RFKH=)nU9A=7XDSbh4 zB|KN1%Dn=?ue7iiS#@FgY5ESFg~=PvDdO%g7y(`VS9=UrQE?6&bI zuwh$aR|bd|N}ZzpleUXshOhdP;&dm{aUrqI zd8cxUwr;kB$)(B+TUBQ(P`6*T0qbhTMpBIQ?t{zm`drzLaY|{o4PrnG8+`oUe^VzJ}vKY0-WA! zEM{_NiihmH3>S+Np<7W0Z+b~Je=f51cYI}98>4|kKeE-FDv;wUuh&JDVF6seE9KH)G0 z{wiF+Mx9&>6uP|x@!L6I7m>z<%gT$3voC?t^9SI$aTMOTb{=lL+{PI7#Bk51lb^KP z1T!sjwqTKDlR!cupNV)v9749OMt@>w(hn9}!;EEzpk2BfHqTb&lqp7j%}`u=7!+iB zkoegN>d%?ev^EJu3zohKXZMW8D_$?cS@Z1ahtY?*nhnJ-Ht__rZjQg;p=Gx~$ts_j zRR0cTew9F(@z+HSHYKQIuO+Y@E8|GhD;pQ$?9l-IlA}N@yoPdLO+a{q9IgBIDzxWb zfnzq7*yZ37d?;peDGnBIq`%{pI*bMhCDw#LXSgL0jmWgw~8FF zx*7#19_ixWN9N)Q)5FlD4h0S~$YY8LMmqGlV54-pz-Zw|rv6K~=>4kI&hZ2=4aqdn1CWq4&SAzApRS>^s z4piJuz{)YMc_eo4{vJz3_gmGdi;W2FT_uhA9ovklV-;+HgW-y674x@g0}Qo z0tGsUnI}=myP|jg|FUK-@*E*<+_qx&1 z013<<*vpodaas=6pvm<9XHL$O9ohnumI?6ZC+gTfV;r7#J_Y)`CGl@J(9!d6U>PYH42s|o?8{hd(2-{Q&l9%*2gQhaY z&k(wyAJ`jq|5FQbQ>p14 zpvoz5A4*Upm*e2vebbAEusgdbXfarAI(+$4`f z)<=Oaw8F7G;!xK44Nkt{oBh6OJ}dxlf)3k&)eS z`vU32b1f$w_lBHpPT}Vg*qSQA=>_g(%*913h(Os_8mp}GgNx(;K#ccrJYZ4*KXkjf z(X^X#7<+;_-ddcpeNCfa)xiuVa`APvXrem`uG0q7$z8BTo9xXJTN zw;xVPVXryu;Jn=dYd6%xqQhf>TKNst3|#}$I?uw`Nx$J%a3hC##bcZZ=6-f)N?_!G z;I1g0aWnTrS`)=+>ZoC0TS^qExBh`tc_p+&nP9^PHJp&}2~x+);N-7=AepkmPo|Q( zw3#Ub&;6MLpv){DZ$oQKG(meAFCvfPpUqr?$&xipaj#aS>eSO2&Cs7z&N4ehmvwQ< z6xp>BIE*xs58q&lRio4}TkEt`k;4vqI>C9CJ>FVh49#{m%&yd-;+vQ1nUBg37#D|H zn0UF28;z6&H)-w!)1t1KQX8XAEjsm{xw$%pdV?L%9o2ZmD(_hZvHs8^n3r#WMb6~n z>;4C>n8MaNwJuD>*~>~`T9T2ta-y@C&KoO!WF#-H{Yo}dFZs>wWqvfC1f%6UGR4h8 zk6Ntsp6PnAn|fxWiT1Akf}G}(V#*mQT=+!H)&^i%wB>ydpkD8(B6ug+4q(iGUFKi``CH3PAeR_-fD)i3ex!HJ72iBT?~Gc zpMzi{2|?{AitmFRfIqCmZ-o*#wWNwk3>hl^xnE9Pmid}FkW>H`XZe$~CBF(BBN(eq zTEgqv6RD0DZ<)*uBHGi}3yrs)fx?Jvl*Nc&TZ5gYHDM-(UkMwn;?Rjrm{&GDe*;?z;+XzWJt}E?5n*?PU3h2q9<^8N||o&7D<+Mh=Se^M*%+` zL6*{04%5glonZuHuq{@2#Q;%8Yu_>rJB*q6qj!tMYka9}g>S&>)7WAP>j1-+AA&-2 z5PM+vXlVsC6o~c6?Vy>x3@lE$j&dz8qj^s9;AIm5%d<~#7%%>_c7tI4d-+-D7-vrz z9evB_F8@QDY#vEFZIh+-A69^6y$n$WXQOfteNb3hiXPnhg7kFB&(x{~Ud0FC>RKX6 zOp%8fFT;_nLj;=sT@Ex}Uk25=XF1Gf9&?XiLYFiP({|cY?-SlKw+v;4&sq=CGYqZh zLx;b@_MvjPHL3|s(jNhtzF*M^r+!q?r-t+Lo59onBwnA?51!6SP!@e2nXe2-$GhaA zQa&Emy%lqqmptYf!K_&DU0Cg6MuoP%Wt^hZsK~8dGAQi#4#f%|%Q!VV6s}n$5^7 zU*Ye9q1fR;1-Mpk#l|lxz}D&nJbRgpI*S!Se6NU-+IkaoTX~ViejZawFl+3hgylVj z0tNYW#_Y2R9j5l0da-Z{hha^CeE$7}ExM%iT~!KYl6^4kvKHP_T>&Gk_hQAlJ@76O zVRw^0Ux*cCZhxr4FhqQ5_?HBk!FT@4?39v1HA$H5^1fvC(_~VF$7;3UW zr)?rPY5(zgPPTHrFd9*;jLz+=l3VAIx79LCsy8%-C%^kqJAcr>zG z@N`TjGj;tzxHEM>ikWB5SUoA=Tt@te>Ty6!8kXjN2im3`W(Ewy?JC8ve9Ihs@K!tw zKIw+4+d_Ew-&EWk;fbs1XK?8zS)|BctR9Dv2qaaGLsBX4R;W_<$7V5OZd_&Rg3hA# zL+3EAuL^)QqxT4I1-Ea5*!FNOwA;79`*-?SYFsH4l)KzN)dbI#E`hUm&9U9# zg*eSP8se+}a=#mWT@Ir}Fp^1;4&mqZs4pY38A1IG(F6}!IC;*Iah*{JpTdV=hmozI z7bS@!s5yFV?kLK0avn>Sp;+p`AGlU7jYIny!D-k}_4$$UESlMrcC%b#%{NX>)Pp4rV=JGIZG)4q-FLI)z#WXu=(ditoLVqb+zTVb>}U@0Z<>H$UQ~=1%y4s|f=Y9l{N1~e zf4;Wxx$zV_`RrSW>X5@_Mtz`NsEiZnE@0~dyGh5YM^_>|X&xrNkup!5bBJr{))F3&}2j{>2|gW=>nx5&J^KmNO!WNkW;_Rw}^lsHpJaG3tVR z4_Z=2ah+ZpN2_C-PyL`zZqZM8SVCsTYb4WYf(A+*==c5=;PmVa{2s22eWTXkMU&Tv z7JN|VYBpK?E3kuoHtHJ$KMkG8R{aB0dw@bEUav);>-VE?#UfN}Ajf$PJtbKl31bJL z>`f(H==hD;VoKd7b;vs&fW-Gc!mH||;PX-&i?coPB>z~n;XYqdt>jb6ZDAe zR1_moiAGmeAa?0oTc?RnwUSyiQ4M*HFGu+~vB+bNGSr2iLm8qfa2&N2o)hB+gUD6b zRd@wGm?Fnvp7LMMvjii!aYZoX`e+dtw#Qzq@lsH358wy1y{Ze z3$ynr)IO7pR@>q*|_$S;LHvK%2z#y znOOgfc5J&#M<{lnO+BN)d!h*>Y-@sbm0Da2R!CVX#70j5m$b>;j>h=c0esVo#EV+* zgr%f;Mt9g!Y!P^#pq^rO(tc`lznd6>k@pQ0+;!EUKJCk9E*Ea1v(k>yf0cSs^1(nz ze&P=`FY7?hSO>EK8>~3V)aoKg$y@2qE(M+8 z*>H?>O89@;2Fr6FAswLon$R+aN5g8#Jm%Ac+MJkj1Dx zczu2Wl-?s*?5kbynvp-yB&Uho?`8?V3eW^&VR=yS{#UDDmUbpHd}D}c>B-xo_0%L_ ztyylbYXUEF!NTfnPEJ(9O4C2XZ{^=mC~kp2!kh3@{~=gERl*IL!62hSE?olbv2?T} zR!SPjJ)5OGCX--JJ$~u9)uBnCyDNhUX^LXn59K+QTStSbm}G|>`wgakU%|q}fU^h>Y$}HA+oU6fs3VQcU9p|25gz zqqYG^Bdx)TcNSv55|Z>cP69JWmcS;b3Ru`@g7;LGL$W?!5g(dPALXy4?Qh;6|t zB=WHfGa($F_s)=4zxr$kyd7ExZil9zgmw~(o ze~UYfUur}MH>L!$AlFDJZ=y{NxTY~b*U?l!mpN@0|CK8Zy|*TbN{z9w=qBlSnAiyW z3h!|CADXs3P}Jan<>;TFe$!Yyfn0P+_&A6~kJQA{a}}{(O&W(;#AB=pX7w^-;lcgt z)av3?X5Hg$qNJRSRG92#WhjQX4aQJvicI$7}~ zN|yc!=d7e~sii%*Zis-wbHUKiIRV(L?=W)Na!K6{=U9@%j+U$%7ME~;m$FP z<}uDDgMw&mZVS-8TSts0ZM43vTl*+7ydfLM9tZ4ScJt&PBWoXArVU5+jXzyt^ z5PRFfu8D1k4HIVD<7WK!#w9))*uU@~W!5T3N4v_>erKi8l%^l>ocI;8ufSCP!0t*g zup~yfCr6HY{8!BQUA1B!PIaK&1S65upITsTb1p2(K>g9CP&(ls8b6SQ*g_ZEv{X;; z!$ZdD;YdFT*f{bIitM>s`rknV(GfQ$x63V6VMI#H^Aq;}~Y^%6E!B>+5BeZ&mcq-vQL`=Xricc7k_Ezba^VSPM;* znWU>%TbQx4kbHRjl+1C}M|ZYAnDu2d+J$t)3ptwLlX#dcSaOtXd#C|6G1p-0z|kUR zzl52_Fq_X9DF^>6m#wZ>(Tdd__-7sud6&Kk3hR`YFsDfyd)hGbzg{+A^6M#C_Ntz6 z&IV#5<}T~ac;yr89ayac9mqj)=Hn64dWROjJhWNbHvqbxY|ovY?`DA9m+8MbUG@1)tAVwn`Y3`VCJYi)s5CJ(c}}^?~Kst zbuOSQbj|k%$Mv1TWy5gTzR*xK%y^?(hNIqSiT~;3#piKRswald+l-R}SfqH_GjTMU z(&lyp!z`7gYujCzkBinE_T$v-X0q$AEm!s4-Ee1|!A#7-|)3sVf4SpsGQ>mcP? z6$B2I%gQ2Y3Cm1rVEea29qx8^DG0f!W z2Ngjpzsl8XGU>^-M*GG6?l-;H0w2yJUYx0?ce{Wh4T>^cHxo83u-=4X< zFpS@tM(~`{2Hhf_fS8AZrOSHm71xt9)IppMeRA>BJL-7UfV{* z2z53N$38;od<~2bsfP(+KiQ?Q4GPz*_b=o@!SMvJLMvReuMt?ZBBnKVU|EIh*nNUz zo;A!uTx^ONCZtQ5{Po~yng7{rI_#Dc(d+Y(j9>Ya7arQGd2O(M-)ESf!P2l<9zg)B zs550TuXEY8-k3?dNRxIXpRiIJjm{Rrx|KS3NZ$puP8d;xRZn?grp=Px%`1jErSV?w z_2;H+$dLQA!x#;&)q*!oD$jI$M@;E{|*qNzCX#c zn<`$=I^({Wp*y>k5<0z7mo-6E-+EYJZX;D3w)2pG3 zbxHnaB?`TaF>sXL=U&|USYOj0~t&W9GFC%D%kXLmOYSswxXV`UWKpU0O z&B3b9e{TSu-vu`&bi$$~qp)zt0979|$+-EAw5GL=U^P(hEM=(&Y`H<{ITQwMC!4n( zB9~2!_(10v*z)Y2h!Hxytd}>#l4~{Kkbe)VXD)&t?lrWrorB8M?>5Az?}oGGow1_* zcr@K&u9A;sg-+}*RKl1sOqt<8*`{_*oKI z&oGsP17%%Txp7HlIn?9CKeBznQ|{Z>q1>|Nn#7`fD1|<19V?ykF(<@VU%f>vc0~pc=r4)VVoJp^6nB@LqQi#>qZW( z?X5{}yc#N3yU{_^Z2C+y0AZ#rurtNttbb5tRRwrf6E@FUN46g}f!O-3WO{KHa7z}# zIRB1VJ$4et>`fv%BecX-;HtFc=*ckZu{&h?6J5F4vvcToK7fo{^-vi(;uuLzxh~e( z2%TQHH<^hZ#8DBiz)qu@s2R^8k=2H_~zQSH1K; zt=@S-meG1YubKUfhFz%fx zK4e#}|KCnWm}%D125J<;-1Lf(y|`n-S-;GtF7cooa&0cZ@mCF*@xTVQg;-n zcq?w9Z#FgfIZC-}Rxs~-^8>lNIt==(Tnl=`-@_+=c4B6ljZiXTEsp?)=R3jf=Me0x zCkO96t+2&xILw@BfYUz@$Jpy%!6)7u1fp@8*v*nnes__hhRqZ&#h{cJ^I*;MfN8=WigtaFGX`VAVo_i=Ki|rRo`D zEjqw#Ima;mA7RV4&oC>%nY_=QN{shDfVJ%Ivxx=Vc7xHl-~#g@st6Lln?&h+vzlQR zHO9-nTYr?@dyz#4UzkQ*!{;h}QhUQq7O^X6HbTeB#xxtr>X>OZ>FVD=DDdCks|^{G zG>5z^U|s`tM&KW0h(`PvG)m>rvvP>|&{WdrxtU>lOb6MLRc~eAZL{daVY}((_sX<> z>c5HhKQ#YpZa>WnUoK!X(6&GJc(es(t@sGvS)=)} zL-#=a5-&cq@zUoR#W1k*PFnTvI@zm;Od7Rf2d!49k&^V!q}ye6=HCAqyxx_IVu}z_ z=M`Nj+U5viiax7;FbgrlpvIoq(SI^5Vta*}$-QvS`LFOgN-Db!l18(SVIDllmY?YH zPiFQsgFe1uN|O(Uk=nCe#d012<6~6;F9JJ?5l8|?=#3H-C>5JkWfR+Du6{f0*lrBm z3Mgc5FkNt>OBwhw_c&puZIa&2QHD9+uT=iFMu$81PDLM-A)gnzhHSfJ4?;s(Udk8A zIcb7D_R?b)Ck*4W^B)MUBnJpv^e5S1bEOU@dzeCh<7Y5Pvj-Xu&I5PWqAg%LN(YZ~ z45Oncln+p|aMIO1;9NHj{8!$AS@vaMtp6NzI(`u`Z>0&H$}nStp2(-ov*ChwQ2P8)x$KPV za5CPzjHIyYRKJX$kjOlrf|fg>tF)x*7#!0)TzQ?A9QCU{%A0XKVQ;?&Og*n zQ8eHI;VwUf&&-}e7)_z1awr(4OY$Rm?*Clt_>ouZs!xBILV==QS6QC zb=(TW{e_?M?5=B|Xv zW*DEQU-E5Tow+}|d77f9B`Y2>NSS=(xF`+fJ^uqyze?blmGscuSl?6b09Heo)daZJ z2fwmAXU`)O?J%_nJl2+r7!7F(JYg91^g{WyQYWsbJ5OD$hLeU- zBe}l|rG_%0H_B_neX$Hqh~KUE$rRmrLb^1;cGgmQlnKR4Yur?hw+BP9@)Zd4FebdgTR~%kYvRC zg)V)8%fs1biJ1cnvYm7KPRq}XK)#9^n!6>p?#Qc;n)eKXs zlPs_P;L7RrQ_{`wR57l;KNy0L1 z$H(6wBT_?U{jjsjd7h1G!{AEla-b3-lBF`Z7U}oqGs75k4M(3TTZ zsonk~N|)z$3a=%vL6Gf)I-9HeOh9l{7BGUti1rf3j$ugl zN5wi@cka|$1$~_!=OPokiG*yTnH#oY$zLgP=~=s5sQqav_6oazo&Fq$h+UF+e_dK^`Y?=9 z&@)AP4@++BBLz*rbe+uhe8^k=XDl8H1>@#`j$5JX`X0CuzXqz#?*}37J*;;%gpJ#P zwaf1Vc>IU@*Z#tw<)>iR#v+Juz6g_i%}`hc`b#S`VVG|YHxw7OTV&_7m2~nc)~x4L zz}NlS&!4#aTr_CXE8@YcZJro`lvk4r=YJcERYSc>H{kf+MNrm~3T3g!iF$D$Y#LBX zDkdbsnSf8?OdBeVW+=m?48EaQV*WuE5T&GEiyq1b+U(=c%m0cPp*Ts{b;h$ou@g>t zAQ)+WbTSn&u@g6;chfV7U3ZMz;olbewX}u9i(N=#U>x8SDNlBMc7J@;O;Qf%=`#0$Qdb z@F}I0<1MM?v75v?!Je9}D-zW~A9hy|cBh$z1iyj?m+#P_(h`f`GJ(=I9E;yn!j!N+ zn3uuqc3J1K!HhoWn$wAGA?w5`P$tO_VGL6?Xp7vV)Qa1ms-lCmr;vtEZ^^;Nu2iGA z2-J5Qh`K-zrUHiEe$Dm;-ylKDN;H}Y>9+{qPe_B)b?vcgs|viV?Xlv(SRDAn9q{oZ z5mO*xwlU0}8im~dWLK{8zYKb?`VIef+GO%#yc%^o`b=!|(L37!T|O|cp-a_lm-7{l zSz4nzyE@w4WeOGyJO~~)^|1KjJ?LCyfSCh^VC~#U2-ZvzF_$IGZicBD(N_MMcycq$ zGHJ@_XXM0$)-cz!k`HSx2E#k7>LI-eN?o;3$Nhtd**=+hbMJiv35os?u+g08wXTD! zCFfy`zKYd3 z2|iFlDv2^g2MaoXgtL2J>6Lr-e^% zQehQ{l`tn5W^soR-p+BOxxa>4H1lLQnUj8nyH$09kLvzhRBq3QtD#WNv!t4t0QLR~ z;X|$QM0q7N56Phm{Vi2t2k$}g{UtDVxG8$fnuuRDd#kRjGFJ(hKGJt{kzvwiKKEYo zb23-BIE#i@EF)jyoJmdZUHpmhkHIvUTMXm0+g3KRAc*U5Ba5EOoKAvw^&sEO zX7h&wsTgJ^=_cDdd>R-3Ig7rEtygw1pUs61?JL^mG%dOh!f1pREVHNe z5PZ1~Dw&*JTd@N+wo+Fu$aGO%JzfIchHr&0Bh9f_*;H(IzP-vc?6df8(xo*mk6}t$ zI?0^Vg1AtdyEOaM4*tyfeaao5sd8WVVsP+32$vGo&|ZsKh0p#jIwx&OIRKlzy&-p4 zG7W3LhLkl6BbDWvo9PcXY!c9GA;mO#^_;bNHFS`T_v$&zKa+K>Fin0Ft-Mdk>yVx z$0fyP(VOFtWp_VQel3q6%MQFDLT*&3bqff^Nj}4V!>z|}K~!Zb6?mj1J3E|W)bp53zO*OE%^>1;>-;*FDp z>1i;3XbBM_kOVzVXp#**Sq)ZWUW&Fk2`5{K`rXq+Z&L&8&Io?QG9`Hx+77h#GN(&+I23B2YR~Mr6*MP)5bNXGqHEN zJ>Fh16oplwwWQftGfafdSlNcf-rNOc23_`~mY=j!gTEEe%ztc{avOdE0*ik@lDe6g zPyI1@n*d}2d8Rkc= zpR8#{Uv4yu&Rw$oI=S3p#P`y%28Z$&>~nkosn1!npOv}TBr9NiE?0q&R(eRjox~@Z zkT(_Yq2oJK7;gR>b_E1u@SPTt`|7GV1!hV=(%l(GJw8zO`DkA*VWf%<2rTBpVKukf z&=OcY6{gPlz%1Mw*!7&bC_<(zse*>a7BFS+K`M-DRC>`f|@MQo3WA8jXC`iT{r;AT{gd) zrgpEz6fAdUcJ{4ze>98K#Ws~3-nkbJIg@h1zx80$_A$gS&4%K;StuEL^6|g3;7t%>&L&EuFmR&Ma8$K0$DxR5&KIk_4(=!tydTT*&^vGy7bzk6jbI z#(`+{aW-UzmO?is-rFWbz^7$#;%Mebm=O$fc>8Yo^n(6ekb?PI5SlpORBvQ>e%UEXm50|34+rrb7AjgU+nK!1ir;m0nAF;?)bgBk{G`vg@?qSHNXDH=4*t$!&Nzzk+u zTgE6Ej@rZmgfdNW{!>%vJf;Yy>>h(hCO&}LbM+@qEJCsoZZCVxwwr>$v7?6Kn1S+CWh2m z{%ea9?U==J+t-i~u8AY}XyWz)FV+-O0R^L3>aXH8DSev>pGFSE=7$vee9so&%~A=o zl3~Vc@0b6$=g;+-qM$yBg?w$%G16z@IkJWQ&Xhf5U3hGByI^`d{H>{lwWZ8OsZk4K z63pi72C1z-O@%bT!ufe0xE5carM?+H*9r${`J!{rcknc%4PO6!jm&Wfg^I(SG246&%xw%8NAo`=it!8+ z-$E2;{AO}73+42}-x^j$+>2aHqnxglI))BmKAr4`V8wqO#J19RJ8Q+JrL=*%_}IW7 zJucO=8mW$$-SmR==<5#aBP{S#s22DhBqGK_8qHybdA}r5p}t}+H*uDnuKM(ZuTVS2 zU7b8rHaTA%%~r8hdF@}wcwvhf^H{?rD~T6$0rlg0xO9Ubx}5z8!5`b=k*1p@l4%0f z35Gaze=V7!?=51+N>ktr!!*A;q!^MI!nLfDQ^)%i$^$E}aTTeXmEYnuP_PJ}tf7vc zQ|-iRJF~}ZJID^~Z!`?>iu(Y(GpZDNv4~#y8APs~c||f_8lua4p6s~NOTQ-)_TIW?bazraAF_DNDgRpoZ5N?&mFg{M6Y1Q=7j*X%$n?hZljOP|yu}n@M7yHQZX;ef(=%9WiXn&_)M4 zPIE-vZAKXX_9wI~Geyr(W88Vf5x@010XVh{+EmE+RWkPNbhkv?k;ljzG+5Nm~ zvL5+%+Z3CYbtC~RyNjb)D{Tj>7-nPdA&O)3*K$#Qd%K12!-X}Da zJ#y5;k+z+2!`LPp3^;rUM!dNXTOS?ezgz6*y45km#`1J-Sgx&z zc_WFCbqq6h^DxDYZyUKKJ$UMW3Y8P?_2An2z2%jy^ic3sKf*FR79@2Rv+x|g{}J1K zB6G~}vcC<+-b;e%Gas^o%+q|5Wh-y{Omm#o-;8tB=qzHUOR`-9!%TZHRH3)>KdzIC zr)srZWNov~$a=NB;7ya_t=jVdGJDFohG)r4r*#?#8&9S?y1>Rb}2Ts4|A=J2*f4OnJ{IgX% z42tyO6c;!VLnS>;k71Hpbyv(!4(E&>QF^J%6z=S@;asYI2A}ayAID!|?jo#&+I5}_ zddkdMfKUqzJJSX|znSC8spjbXAQqbQ6)-O9CEq5ur*d71E$)0*FZ&hYCt}hhbm zz5Nss6DYNnx-bl#+*)yF&fT=%Xsu9zrc`ueoNHRmiaj?JnEXZOPM zJ#uijZ%e0IHE?~d^<;^R9k@%Y=ZhF~sjXDTFyj~0$({S};sy-PpdC_UxzCM_+|lq@ zrFK_C9DiFAKgAj0n7u`yqK`COnHXMtT(d2-a7jsB{B=l`*fs57XOj*f8IE}{aeo6aH}|)MN%*BXoh*2 zbyXgEaSzvCmO+;msS|@Xtw`p8U7YDOL)4zEA&$n<(HWnHvx=02X6QT10$ZLjr?C`E z)bfmn_s_DRrP+y2Uw@ixi66*Pv?r5!mN6oxSi%G{%$erR^2M|Ea-G^{(4Q_&mEl; zb7G~5tZ+=wI!`*X_p{0zbINyt*_&*5nAe-WUiqEa1&zQDCzM3Kd7n6%zLLen5{B89 znVl{xJH+jeQ_;Vhf05B$zH@gP*N~g{SgLY&HE}dTb$2OCzNqT`2MiU=Q(!FXwJ9~h z2VY{KhkYI^lj}*}W*Wlh;8Ez<`985MOAs+-(rDH)jLNi6dg9z9uA7&NYRt{#9CFo2 z&E4H3*Te`DAN>X4p*?u#AodXm{hqH`#@fAfODrs8InsxA!!ozWEV-lyP2Xw{6E6f{ z+l|E}_}xJfGhTAC*upUXY8R(fw;bX6lu@b{y@NXw_k*jRl0csMu)<2NMZ^f!ljk*c zQNReQdZ}$2{O50qmjdD-@^2y7t?o=;h4zDoi^gJk%O5hoi!_=X$ulLIVK$%I;b{_> z%tf!D)M7<47g@9!&Gs zH%7sfL3n6!KRV(nwo$s=_YYj_ZG@)n+Tzh%7O=TE4t(Ff0J~^sdba%(P^_7VZFjYW zpcnBXCRy@NOJ;lKcbEH@Q2L8jq8WKD3B6uXYLHi8{M9d7yMKOh8CVVjR z9^dHct#^id^;$_6=_Dx|hFnsP zuL>nCH7ujJH#@9<)x!m=+hOMPe^C45kC=sb#Hk%B<67ZTtw@OAHB@yY+*DfqKhfU3 zkJ7HTv!Sg*`aI7`E{Z(EY+X*h{PvvUEEARV*I8Ze!S!9r(XGdk4x3G}zUL3fZP38M z@kYpJd>2a;g$qfisqL@}bLE?176&UobX6^zHB9w?4{ZIZ4 z!+h9a>FwZklG`~x#FMl`0_z*lt^l2XZ(u=3mW!8d zh3Af|hU9|Ah}&SDn+^AdX<>)qZ86A99XD<}1b$Pys?5#1 zsXl(|sG8tvrBd;)VRrRr5tH9ftbwXvnDF%OvVA9ya;qjOsQM0VQ2kC(I!0b2y6sKT zC%6VqG@OJ{&-a6niyL+On0R2nS!9XtZnZ$C8L z^$7~pC=U_yj$y9ZY?5s`k<5*+lvCqq4QO`iL>#AIB;&W3pxb}dAXrRPXZXU6ZQY^z z>_X82=C{HE9hd=n)Y-$Zy2~Nzd1DmqsjyJ$p&8%zd0QOLe%J+!jkk#T$}ls3o|gp= zImso@k<;O`n~7PT0l6D_mbo;Tpx*D7FjUnWl0P#;2Db7hTXh95t6z}Y*#Zy#W!bnR zQ{Y0O4*$jIBNzX^mdn#!tTY>7i>h@}<3DmDrio$bX{9W0(iyJD=X4qwypw!CID&Lt zc!}Km!ctK4=9h zpIhYXuR)}430v$3e*$5j_Q6*Z6&s7;P~ILAepMH0{^&x(r8rV?qzm4jsxCe>6BIE< z3{%ymO!ju;b#9qsI$eRI$ji7Fgu_@77SHu)_dH`0REMc_qZ_-+IjNI_IgV5D)K=_ePa{dhi`~P9a4cGryMinaU*3BJ( z{wb1K;}7YfIWWwPQySd5*7vxo>1p&4QIO?c>d<3$gotrpa~Dct2f#&}z98Ff4Atj@ z!7Z>7oLnuDd~bn|Cp9t5Wg@EW+b*KCk0#(^x6v5W%Um4I7-^<;Wthrv3od-gQ!eq# z9XfcQ4(k>8NSbCvkdX^mD|S2&ZY$%V{@Fg*y?mSK{Sd;+;ByNtap|F4I9>Y-!kt$@ z)CLEb^UWLU6PT%EPB1Q7Xd_}Cdx;ONAH&RjZO7$733utj9jb`y%v+w^O72IgaqZ@r zqQ>=fuue;d9rv@K^5!iVwX_80wtWuV>$Z3;>lH-$>7oDL*|6aEAu{)O9ESFA#q#sx zaagh>+jWqM7-X211A5$;9u?f%(|2eWxdAu&%oW+GF@1UUODtUD#%(4pJ_EChl~DZX z40I1Hghcxy5SC7k%Ykxc5IB4MXxL$z#wsIkV(8wr*rjF$1~`|Bi;bzLi18C18dS;T zW#wGRhdb0x>nvSA(tt*qnvsMv%-z!Urnqzx|L@RLaT!i1U%)$7+B~?v9e&kjmHEt6 zGica;&^9>$zn1OB4fUO|`6_dYFO^n-mcAlp9K*amcU!h0>n@l3{SKYxJ%bLLlR(Yg zQuw$@qVW`0HKW;!UM6~EoREi0|M4pFaIk{=sQ z*!LT-X&hThs~>>ts&=^H`c63ZSPwI;-Eg<=aNMzI3vQaFkJ0Prqy9hXyP?uvU_QhA zY!mBUIBGvP_f8t+&j!=o#^>ndH>JE%-x}+8-vYsUGNq^vYEy5E87scy@}Tr*I~=JS z0|T;6@XCrQXf=Kfj)TcqTYC*YJ)MYsSZ%Hv`zw(4X`u{rt7{+c2PJE`7gN)z_LSeu zB4<5)<smnKfdxZ$fX z*0vm8bPK`p*~KE}v$R#;z%W-geD(f!V>qYTNlyC)8bj>TP}=X728~IuM=v)Oq&Rj4DG1%hlCV67VPMe~+_?HL#Cfp{qt=p`a!xw1 z?_ijl8`j8beI2>XS91E!&<$E8?x2_QOlTT2Ee$Zd2SSo;V9pzeXGQ!S2B_ig%=@r^ zXb1f9Oov8v`mVIyz$%PYqp)PdDsI7Xe6b#7{uz2B^$ zAD{~ykC{UwUTf0j)!%?Lhly3F5w*Y4JrVG zk0a1>_EKC}m;pt@YneP%#^X5?+qE^Oq-(|s5<;oPj&KnCG;FI75AK&hMwBVkmU1= zS_~c_VwOl^$|;7q{WwXcKDL#t=#G*GRI1bJ)Fe70`9449N_$LEPle!H&2THQ0`y8A z!=-h480CB&hOtA*sZGJE-79TXE*CZNL&hqMEEtI1VE`vIOjIk#6cOVjsT`LXrt;bf znd90W^4qRFwOrOheg2E2T6`-1$WsqB(hflI2bS|ai&bz>D}uMI%Zsc(0789QhSn6- z5msGCs3A_?xdZ2`+?iK&Be}CwQ^gJR7cu(MXznmfXRnU3l#~d?#XUToPb+AFazAy7 zI?B5}cnvq~=82esaF(i2`y9euOi*j(GRU8t1>Od|RE=XFQJ2T2_}_{ctY6}aK~9m( zxGR+=_U$BM;v}IflVN-|t@EB)_DXS~lBarK&FQeHXj-W;lux{P1_q7n2vJ{}Au#9( zn z!#J$JoNk|MrCipQ()OoY^MSshG3_Z`$9WmUxi#@5p`RMMz0DQtY@8lhp<4gjWKxD2w9W7*JDoZ};6*ju zy6OOa^RdPmU()z)`@6svjdtP{UI%FkykeM3RhQ-auTD}P38b{3%vYWjrbSt<#_ zdB_$Io&HWt)E^S-D}=O)bAWc!PeHlXZcJR(72}c~@()^f0o^_}BBn}uH$NC==JS~J zQL8s7t!7fHw?C4UOuWIjt{SLZyR$@0`4t4>+Q@sXF8U3eF1KSl$~JIr+yC$V(CYaX zm~bNs9~Jk-;mecw|GST%pCl0fWte{B-M#+{+NxArMrntr*JRT=NnT zEFM%B<9}y~UPGlfI$=b{csMk;6ZE+mCGKWcd>jQ1pLSp?3vXQPDHk!X>&Bxn(}qen zg{@;)Zq%0J-cDm9lzHnZeWc!pJCPs32R<@Zs$_xSK5iE%pR#h1SrW$btTS5gI}Pqp zTcOXbdtlwl7qd?dgUge`(Gk3G^csEIZiXk$OOhJO?n)OcW(?!Dqt@F#KU%2@rL@Uw z1zBWQ$EQZra(XKdv-F-Es99?yV*FmR+`?*CEbw>>M}J;|5qXuQ)uoHXc~TweK6DHE zrFFujh@SMnc@(y;l@9Ekr5lg-470oM2w9tbiOM2(N*~CzA%1mhIwklaY06Q7&wtF? zm^qA$dXx!1x$oh;eK)jqsRXl2XF>10HvBC8#0ON^lCU;gu*$*-_c_j_!+zhwl5ijK zp}9-#an1}=bJ|Y!Wnhx>P&rSxxU}PIRng=cO(K~tC2+HcJ}TKE!{~ShD?9iA|Mv96 z`pVZ3dhr@lJ6KKH6?6EiexLL=jl|P`Z1DHmGjy17B5E`5b@po19HjQRo(zKqW4z>^ ziOT4cJnb8_mgaBFBJHPM;o@V<;Iy_b_UhXP6TMYX|L8po%kPa799TJAbQ=7t^v967 zUie;S54}4_H~W5&hX{C1P$BzJp%F`eNomX4~qi0+>7s52?#=aMw4a^M_q%aO^L*2c4#m z{30;fSL(>$V=Q6@F^siAtRiIV4&~cmo=#N0=g)or%{??;$Zc8p5lJ= zV&cjj%7>G9diB9f7&y(27@4cMFxNLQM?(vhnFvmj1}@$xT*f?@aJ!wyGG zc-s+Inh`#w%N+diqXyoXH1c6@4^2s8ezN+2Ju1g(R z@l>6xj5S~i&E*L!_{48lHk2)R50Rz)P}oB^J$?Y!0@QJ+&Ucv2kA(0d6*SbPlKulU z`KLL@F)mix+}_j^F~JP8Dy+Nr^r9`w9_x6jecKA=)HEx8Ov&Wj-9E!N4^3RRsWUcR z$Q7qR)&oxrIaC0Cwof6jO9hP8%7z06N7Fwh?Z}?srS#c{Vmj3PEJpWgCyr*QgjvKe zJv?+|S=+WN?=I%)?pCdc>Yp#kZkNubU;7UBERA$Q7gtte^8ngRU^zH_J+a>XDF{IU z(GB0BFscFy{~4Fc2|^wZ+k_W|*F1{bfbglaIsfNoH^(sG|mIGS$|{`o6dqsOj1hqy9aHyzAv~^4vT4TCRdW(?+Yhul+?6 zvTarCXUtda3^|Uw21`?*TvNnsW|)vJ>tvIjtX4Xi@^t!jE3)r;97)OVPNLrbf!x9B z$PsJ26?_NER;0u4DqHj|%m*{()sZ;A7K$(5g0&BpsyYN)s=`e=srJncReAL~jutF9 zRgL|5N|-2yX>!;tJA7lI((Hqh9x8dxx!b)YqpH-1V9in$@(A0mg-HsMH_l|Qsv(`gbzkY2DG{o<|xC+&qT<=TLvmMSdqoh=NtGNH=0Q0 z%u_`0Ag)sU0fg?L9 zs6u#B6xR!C19BmNRT8;Q>Vdskp!1QUd_JK4LSoi`DrubEn|JCNg$e0*L`<_Z(^47c z<26IstWI`HM^yx44;4IjibPqB~Aa1hN#iVU}aCh`q5pzRL#C&F$#s+mR zFSoy9d~|1 zJQB{vw&C3#pM)O%1YJG;dVyZ zErkW2Fs(CXY#Pk0WpNa%zrrY=hY(zR7oOHxqMW%VPrp4DENbS%Oshox)}-b5ZryB* zn7$SDZb^62m!*fMv0Gg&Hs-TzlV953dH>Q-p!rs$B?`~_1HvJ9rM~uN~aY2}1z8>FL?hr>4^C!wj zEk$m?F!TPskR4oTDPPr&jfVVCjz3?joaV5S+#76#DQnBX@A7@vzE%^x%D#dSQYTm0WFV^gt^Zgm*tXqI&cIG&)iy z9z3r85;1NJQ})PN*0oon{Came&2lr~(--^jt-H79O#@hx#nn;>wS59xYMUYZXD#Gw zy@8P0Jn;PFgmKKCx@M9;41UKvmEXH#L3_0FK6mRe{z2Ec5d>K z)%-V8S9E(?0YWyB5B!3tDCRKEOinjFdJLrrUD59Keg0_VTmJ7|eVp}`xn2%JTzSzA zPi*()FW%ikg;k(ullahvGK}H*fwGCwtrT0W74%2eSn?<&iSKjy9KR~03kq=|LVDbR zmp{bNpumqz=*oWr*K)hz&MseQHOZ%Q^-OW8lPykI+#jDE>4*_auF~_BHYx#AE@1)~ zM#E)-toQy-itX{N1#7B{BGJQvAM23M_abg+-LnY7RMpVrP!EF1Y5Kw@sNa?gLF-*` z?{lJ>o@=d|<7tV{4Laf&4_AD~?%*D;(p61!pCDqcOPHw)^JeWdS?kFGicB3Poo;2U z_}z9Cf5tF{e;a9sd3Sk;VkzZb)4zxqjfj6x;ByBy)>-5H`su2h2i;WXFIwR8fA;9B zXOEt?Y!`H{oyzjcA`#O?`aI_{%<4}gWbUlo>PDE7?lDkT7Qt*)r(c6bP!?62m;~9FYt5c?nn5EJb zSjI4uJWOSq%nvBawRmb!putbQ9Lb+v@{AYkrW}7R10k(+b$jO8$MU?L{FsZ?kfo5< zhkZ|%`>7__zM%FC`(gZI4|X8bK%0x&_+J-FZQrjZAqNzn0S9aS{+r5k&57;urG zUe0%D=*T=h?KJ88qDpb5xk&G38^bJ5Se|~XI8E{K3r~+vc)=UD?#S;;lku!ua|J^3@U*(X@%?{-7Dpxod z;DE0NdgH;mr{FkV4yOa%;7FaM*;q@M6AUx|^DxB*k7J6$+mwd){zP>X%E`w}3tkXY zhKBAYLWyGifl`<@kj1>Qu9UCF)#QULjX0GUle-W;~nTRD?%*%SNA-Q!n=uR78jda4C6hDS7_d{ zQAGWu^x!>nI&y1AD2X|zoYAw6Xx-9;VRv=0YUMMrp{!k!6`Jhr4X@g1{%;>al(`*d zZ5oWeW!IsX-X!tgfB88`#FR=aw2EPNzpq#1UTPyBq@kj=RW>whgCE>@tHHOn8w`Ec zEdWy%7<6K25x6B)z=Cf!=%=w8B34ZSZmHy2acQ$1o?R%zT*C`6>Qi5E^D@H`L@G{d zCt>m!rb|adWp+iL_fHcQb*sA0_xsfYp6uVpm0d^zGpE}S!)~SG+Z4g&m1Qtyc1P4> zU6Kvnd%@$tIVjxU8k2Z^yf>pKnpP#j`c56eD#!q0U8K$JU1=34VweT}wUt+YqHOO6 zN-yLcBT2r7@YH)a@wxX1())df7l+$mdWRwiZc_@!(;YD0^DCU$e;J-7nnK^aB2Gu+ z1)Lk}go`g8hQZbL0GgY)gdxks-Om zz_19SE;PZ?jyB?Gjs_INHxp-k`-<5czRiY@);rK*t_<@Y6~fiG#`w`K4Wi$4hw+69 zrM9M;h{^jaVm>g;7e$$3=bcj7pur5|dlsygHIiO`crHY@7+Qv?;l16qnEJ60_yq;f zi+Mc>MHXj5N}#yw6ui8)Gukoxf@N;H_$Vn8J_i`XVXHN;xJQwQ87^V!87AH4gd)+s zT6WNa(xVLnVe6D4&UzY4Pz)-A`pQ4>Z?ipaN-Y${`;C*k;$n|hXf(3~7BeyHWEXdw zQ9|L>J!ZI>mkX^=GHp-28d?Ikyy=mOLaM`q*He zu8TOK71C&QVp(HMS&aPKhmW$uRZ9BbRCBl(5y}5ZVcri+vvKS46V6X}!EArlb8Gw< zjIZ}WA+UDB#uwnM-x&il&2UY>ZQ$d57oNDE2d(j$+*PNZsQJ2|h&du*Oc-WJZfm)- z=L^}d9!mPYFpK}necG5+&DR3_8;r|HZ^rqUfr9i^qpo2 zCzxrL;AHXEr3Y&07lTnwA=Hc^$UMlvizWXqy6c1Io-;is+L$^AY~g>7?@QB+_R{{3 z+oJ5fo`|uN-i;%}G-tF@jIDnl+j3Y=dA&CLs>?_D2QN*bVB%NsV~xoDlY5F7pMwRU zei^apBTN4^s)Y$-d*jA4HrVaHx=MHFO}b{(JDR%5QT5@w1M03c7BS7zXu30u<}epU zoBAx-zQ5@-KlwDDpgn`LoAHI1`AC_?Pv3UMHfs6sS&QANRe9n6q3X@!YWl+V|K_D6g`-X8Ns!@*XMc-u;M1!&g2rO z*x=g~ai)zBA5V9Raa__>p8Ni?Q)^T4puB_N|{bZGxS(N z`#Zz);Q_mnn@VGMlS&P_e*ud)?dMZ*wD%YR(_LIZjiZ>q@h)EZmsd;V{^{)F2i?Ga z^$14eZ5ru1Um4@p)IjR4zhIxR0k*{WK;4fPNC>M0-d|wAP-FaD^8oy2&ft<;zO&^g zS+-`5JGa(zHb#y06);I6#*boZ^KB(FOh!rcYtvYh%R>N$zEeo`!b!hNs)Ej@*gX%z z>|LOF^ly?iD+NX>l>ndS)Bm6@dMxIkDZCeVd+{zdBJBgC+EKweXD-H{Hd6%5B@r`+ zVw|r>NRBjkNR}N=W7q6(gNce;iinCZGJ^kVX1s@?xyK;w#Rn3-bS052Sp+R9^ci~j z17;chgy?Bk;CX&K(?8@W+3$0l7)Hi0jmOvFRMp7>rd-4J0lsrwW#MTm{vxMUv_% zV_{-_e`wFqCmUC6K-+sG1mM8Y%ZXGP1C+sYt5JODcdSugu6*z2m zUjdUUt_8MH%%Ltd5{LR|$w%ij_UhjC#4|(}CdX$h)a_{`wRsWzs_F;sXFih3K7NGL zd`Tk1p1^rcbsQ^y2ySg0#0+Ya^d9aFLukiJ+_^UC?K>;+c!`+lHAZ|q_fpJ`b?uTF zgC9uVPEKRTH+z%u6}{kCVP|G4oya;*Ujc8VsrSPG7TcX6C*TDsXv_tp?^>wZcn$hg zKZ3;l36hn{w9EB>d^?}cScOh#FO23t5fj5-w9cKRGZ+4oNcN|(zrwzdL5s&jqu*>M zMTNTbeR>93v97>JBRd+k5y$mv;O6=ew5jsjDUKR!K6wJIeck@IX2YY>f>z<_EO9h% z#kIg`iYW~4A?+P(C$)K+#`gMQ1a;x7VA~O3ZgA9&wRav2YF-9))zNT0HW;3U1PjF! zzWHLezAprh;9#*w6f9b+gpM{G9}e}u zb%{gHU)Zo?CTyvlheTCXz~UflnBM&71RtwZJTK zohGB0@9mwWV76E~&`-w3)%9mTTmB*Hb^X|@bnjnfPLJ+pXTc7Cb*i*~13H(pAhIAE zCjIG(#jz70t>_C3zIquvlC}`FuZQuGwlBW#?~KI(qG!srR$(oWLowMO?n@$JsdVZ` z8Jn{|B2kM=8^7apO?z`BEl~X8bn+^NeCfbhDQ%J>w%af0V%v^H%5dt4Fh`j~keH zBN`UmLXYw4pF>I)T3M$HsK~yw+)eL|OKA^0k!J%g4`_VV%IO%q&KtE-g0OgDDSRA7 z10SlydK$I}m?DaKSg!2VKF(b_BTCM$t2JczDjqUkk9^qbe$+CeCJUVQJO_&{s+js; z0q~AvolidiZM9yQZP-DSR6C&C>~&asZz=Z4oQClpa!_pi1h@LM3mcCvUjn zly5(7F10_SV24|dk%tBEVB=@>V-G)ZM?2MA0W~7S^6)TVS|gb<@+{u zFn6`x*glJ-xYRZu>dXtE;PG$RBz-BgW2a8bg}YV#uzKljW=6$SFpKlSvtfa_$8sSq zjV*w(luB;OMeQppi zO3}(nh9$SWPN^nJ;tAb&&=rlx5L>p>msaNduo1#LZK-W3ong(wI!$H9H=)qApvo2f zLc4H7B*p9u>QL&_BtieSFw`z;1K4|>{qjzi<1w@91&j{GT(NSKBrgn=yeZ^Z$K&(J zU$cI!-uLIs>ivjWU-JZ;Ho@nXPH4Vn!&^_;brdr-a39?A4jZdO+(?#n|faZjbLl8=EG_MbMcda zv7wkxOfOo5^!9AqpUED2xSH`yac8ge@MA2ZY%$?SEcHwK2$rX-;9(OL^U-2T+`l;B z>(DbxR&ft(Ex7Rc1V25Y(eJ4v@GgmhK~IgiAfsRbBdHZIjuZm}qP==Od!2D1JCpU$ zGiPHQ#<88pYB95d)o^(7EWtwWp-&kkMNmhWbWOA`S|zO0Zkc*>)si@eG>7t}s< z5)1+P4ZCsLTX;J}7tQ~(2Vaf5FmJskcka(1cAoznyy>zJT{_$1s-ve#gN+O8?x7=K zQa%V63B@>G94oJqpOBBs&18S;Z)ID3^O=W}Pe}td?1IrdP7>Zu*Xct6xQ;J^5oVq6 zQ~!s=Iw}-CbzEldNADxc`Y*%*-45erYZHvGysEgq_A;@v5e;a=#nFtU80Alw9pY=UVQ_7V5n4iI}u%GkY1 zBj#3q*iR)I*AFnk?>$d4!OlbB&w_BlVxs!JFq(-JGr{wTTzz=19Q$Un6;3SUcH@pD z?$}w9yRMSFnBh*0t-e93^eOm#EP_m(E@(dN7;%64i~Ke=Bb{FM1(&k_u=V9$%+0jK z*!Ahmc1M7;?up*H5w!+1Q*`#PdG11IWC3?MFAZfP^Ivn4DSmTJ^uS*&2TmbvvBLZevwJ@3> ziV0enFVDXlFW=_Rv8yj8lO*LgBrxG9Nz+ph$Gx}7))ZyrCGq@*{VL6dnzsHA%xQW> zlJ^!!({kJ)PKAa(4p@h)Ck((vYpVqT%;U-BvY6MI$#i-6plaHCXR(@HPWA$oJ zkfWO_NzU^d}z>=b0gu~?J!~Cv^4S+DE*v?6R(fNU9^F7hv_`**E3W25SWXYaEjSI z{iJ;2Z@-K_6IiyR-x+C|MR)M9b|ZHltb^j&XP|5(ZTAUy1R*P*3pyMAC?eed033EI zg8*Aiekz;`^XP`{gd|QGs9MF^8vSm ztn|OsH$>)o4ftcCvIoYvZPz1cS@Rs;eC~&QDv9U7>yT_-O9JZ>NayLRU_}vNnvEw; zuD4+CCsE_Z`Qln2P`o$CD5g~ro)IZIEzpq$1`V z#kdn2j}XIfuVMEUY}-mTrthLiQfBy>wCv7-S)WzWMbA=@CHzZ#4*tIeBj1tlSs{n5 zY75bU2GWIAF946z3H9)q&GnjnC&i+Bj0>z={$zaFUQqJ~M?SupYVDBOO)7MJzj4MT0*alh68 ztT4aNmJjj9^Xa_=Ottvj+@Y9=i~o6=4#@R-qNQN1dR!q>3@%GAddHE1*-zo?cV+zQ zXNzrH9>UF0&)`*q6nTeB@2@$qaScJ2Pu6(4t}~2X))STYIiu_OL{??!Y>Y8?7ciw& z!gIq=%o9sHui@h>ylki&+^RoArP*DKq&BB(NGe@8$>w)J>&PC$gyxGWgAWbCg|pjX zcl`r+AL541c3m*cCYe}0w!wk*Ciuts8auFh1%AIWN5HHTCv+~wY`Cs3349yrb;?-I z`ruq@oj;SAm9vY46KVl^vmN|D^~7Sc$6(j@HOz7wF3dF9+DC99+!?zUnc&{jL!|cW zbaDB6+B2mT%kD`D#@P6=0%k&mFq#628Tqce#Dp8+Rd+Xo4c*q2uv;6M*p-V&!QZzK zQ`QFQ`<&3TC=X(~6~ciZBk4l21@bhXfb$p=bZD%F@20(&X#FSTv2HUntLGK=$)ugQ z#!B3Ko)j^q6qA$hDOvZ2@l0Bu!Ja>s#Q0?Hkv3mmN>pgN0`J$E8AmG{Zckxo)@x9_ z9ffXJ8zIi;IfOG^v4r}o>1q_RUi$-RYDykEetsV=`RqEhG8G+QLdA<#Loq7O6C}eY zD$A}6%3w!HE=Y17x--e!Oo;E?Drh_W6ZW0!gT{t=aBp88{EbEA?R0qu|AV7!aGj|# zt{daQ8SVJOmV7kgK760cIVW$zp5`cAw87$Nnkhza$pT5=^0l%_e`W07pE8)($4^mr zZ#W6qStFF~lsERkf7=wW+u<&lwGP1Xvuk1KvNzDai1w|~prDBb3%Q?Y&Yjn?Wp8 z#mL4>U|f3)w5dNA-%7&AA^v_#EhtTk;M>0tE|o5tp68o#mBUwZr>95axn$b+L4OxY z1&rEZ8XdM-CVBfiaNZ+XMk~u0+5XP>k`uLdp3@O`bMW zWbCDwA`%$rOQ=~N$-2`FdFfxk_R4WK5x(}P$N+5g$^^2q(l<#!Qpu3|R zH}q68`zLE8n-ThpouGdJ@A!(CKH_N1DaK#^Rq`q{)yvgP#zsz#BN3nT$%%1WNKDc< zuzUImmXfm|SWmuABOeQcA$465>>gYN=3RBrwMQ}hcdwoKWi*Za9^p^QEcP;)?FX^T z=W)VlR7H#(#po^7l&)HDCpnmv&VD{}jQDo>NbY4%B}?c2gn&`i!iGJ$wuGFUy@)*B zZ3_QBya7+T*kx)pQ1?+W_&<;_T`Erzc5W=WwxeF56m$?@uaXKF7ZKB!VjlK2lzOsj zBn^@2Y}lc2vbn<+9LjDfBocQr z65Wn>7e?bLjs_{_`LBM`le+5C&uh}ziq0LReE&`;@*F5h2~@=Z%XbhK*+-D`OnZ_- z42g^gg|49;V0io`%<-*+B8^OG%Xber^sqY(7aB@>_(Y+;srbDK5T6@wih*sTr7n;A zN|(+}XY~e+1CQ{%kXy7^!k6v%GwCp|0pOVF1t-E9i23C*!k@5vji5oC=Wl_DJ&i)# z{(oyWqu)g1FJm!aqmy{ircg}s{vhdSy&2Mxe(CI~HV;@!1ut`?Bc52#$NxBzd}^s(KWG(|SZ>%Ow$W<*o4C z1X9fMgg+4yRgN zjnxo3?GAM7ItoHB-Il)6az{(kEVy{(Aa>9sKqdMcRU}{*Q_S(qwNjUa!_qm!)7gu$ zDU74J6b9UkR`5sPLr>;H(*28|;$8&_X3wZ66hnJHp2M=qhWOn1ENr{f2qPm;Lxx|X zVpqlu+*TNi)t5J7qH2+_PHPuO6GAZ;tmjGhFF7v_+mOx{dj>LC&<#2_R4{y7Xjj}Y!q3N+@@OTYPE1gU=H&mjSy6ZK}U1^CdHKK2tV}{NeuOa8v z6)-;Shf906!g)Pc%=x-YxM(&aCYoaAuZ@!ATgOQEZj-TVx0 zYpJP$or#?=viu!ny?zJ0w0FlxYh3Gng0^8RW2L_Yck8O+o->G7BJ-i9!V#~8bP_NQ zuZ7XXQOx$qwdqF#*GXSY$zbnQ*Rc!QId;jGW@Zw9bax;R;{2;&YMB8peN+aQZoH?> zWp80?wheyq(*dhc7CxAJ;`Di1*kL;eTh6D!VSi6#4Mo|tx`??*F`U1ztbEv5=>&H< z%j`eKsP&o6o;pj|1&{48@BK3&r|_$#J}%rvBSZr}32*4K<=wD$P&!E+dl#4@H^fM5 zJQ&*_sYD)n_zuJdB{9t>M8w>rm>V|XUQ2#hOM^Qp*zYeRVBqj+?6$g*?BAeX=uNeO z{1#Vz4~?XvVZyutZI$#LWY*I5tZQ~;ydsg<`)FZbY7J(P>5YChRUlQ%BVMLc1X)6e zIMdQ7#B;MOlwI&?p9hliaa|>cAF*tLi#;h)S;88;vu5ww z_QaTd`bgTT?lMi*24Nm5dkycop5jJDCYZBL&^QPG;itn&g-GwqW-|V3hK`H zP#cFQ>Os(fdGPx6F(xg-o}`SVFPVZl^kq~4gRN$e-cP2I-)9nq2|Zu@NdKc4ujIb+ zS=+iPlr6K_X`$oU<1eh(Jd0E&?X5lJ(pKvL%TIznjZgXIbvAsJBWjT`Y-=}Rx((Vx zRCD|h>z3g0vCrWZ7a&*bdW>`rqCGtHXC!{4wPNVk(|fnv0R}5Z1!c2ZS8|zt?YkJ2 z?ZX+qH|oXe5F#u648FI&LE&&}{b6N*(;lUf=23+tOf8VyxMK+;8~?*GX|wUl@p^b{ zBa^;cU=R7MyHJPTQ7&9GV~UAC7%gAvGH zHN~7-cu?Lu*;!FhpUp1f&XIjXBZ$%VkpgD)-g~6#eT$e-Hs&|%>}HJD>y%)_NRH_H zj3bdMwot8WjPJTnKr)lI)_+`2JjOYIZ%x2_ePxP?P=xHrAM+{E7uMCzk$i&BnXG4sKUWz@Rf`7;SVw z`1=jRQ^?<&W#SYVKrx8}cgZ(=?yR^qCWqbr>^oyI;2C*pvq_;e!wO7qN`OztmW}=l zS+3up;))r*{>|!DpQ&Dt}hT zGv7ag=hY^#2(d=(P<2dzJUA4m12zL|nFdd4iR>|suG_j`3D>Te_S~4MJaAr^0wctk zHjQGs2V9b;bli|%y-XdIhe;T<^`A)hCJmx9_&uag)W)mFG|_c+75r-&7j3%u7FbR(A7?$3kBi44%Anz?krVP^oerDsK+K zt!Z8G)R<1}C7Yh;A0f8KX^Ar}l449%EahY850ek;$YdW5FOx=33?_DxH>B#x7vLSo z&Zin-m0g+8@5xK8_*`74LGPj1#1Y9CRjg0zO1*BkK;P3*gjAhnY9DsPa|YsQ{KY8{ zOEE9BZRMl6Ir2VxGufI8qvZ?!WJ(tHR1jWg^VnJ)KmRnwg!`os<5LAwllq`Voig%r z9_<|ikeRH93fUyK{n%mV^14mz!Dm&h&SX=3dO#suv_$cpc7|e}gpQPFcn_10)yZTn zjSnfZMxIkJj7-?D3yx#u#>fjU+X_mA%I&gDD)y&xU+Lx^IDKUk6kSv2-ZtD}YfFBz zgPPsBTU0X@lu|5UszuBdis{+gSH7}py4>~@$38MUz-(D?TJf>_86nDrZ;xB>M<3^H ze+??Kr?BEZ74=aKRDxDL+%UJt(`_wa7cb%Rm+5e;4Xn8?*Jg3!yY#`)JN^imLJ^Zn zF{RtO$y>Lrk()Vl>`*5i(l-09VtwdIQb$|lrITrUoW2^~JWD<8AKivYi}lgzVjJA_ ztcSiCU6EN`4hDIC+*`A*T=9AuTDx`@7d3%asVuaSe|0_-F>;E@OS+Sxw0w_zGhL^( zI=%;u{i%%p-J8U7UmKj9se*YEYoLz12vz-KAb|Mn33G z#DkR=6w?wg)N6IlY59At4vOhoUQ2(!cx2W_!HTud=DO^>qfq{0r0aN5LS?PS7nro#b57gEr>VUJ>F#zOR=)*<{wvl7eQA1P+7(-p4+YtG0$>=^dh&nr?pskX%U z`x26`ri8rUa)65s1Wi{1rI^#Co6iH1b)bg&K+ur%Nd_1W^ysLEKlwY(8uT4BAbI0) zav*#K>XzyXm^kr3vXNq9mp6G;e>x-|^-sYj*8NBPhQyPDw-Tjh-pUwm^9w51&=?n{ z6Xa$lkpUM|$fheF1gX{LCS9ypSPgHyW|OxgEg?En11{n*5^`-B9*R&BFlOTM>Mx49 zuIMG{TDnqRTdiP=Z#^YrkKZOFG)4M1M+JF_qPvMisMB){HguD9=~0 z@27T$Yb1uu%l#ndy;Sr1)I-wKSg)9oI|~<0PsDVin1}t9q+5RV@_h7{?mcBg7$eDEVlgmWFgbPl_X)Dx z?}BS{4FpVn56`9*KupD3SUpMwZ{N8InbZ>^^!_6FIPAByEy@^%)kTrYPrERSD-qsl z2gE}!CyJ@>S}VD!e88*MY=%7@IiI<_X*~StD`k$--ZWm+7c%H6DC(7w*Q%!uq&>LR z^kC9M9ZQGhL-+z!RMu33F}6pf7pLw;GtC{C@n{3K+!jkiU&Z46Ac}E+lP@`xZX)ra z-ra7h0~u>&3&KV0V?N*1Lz%?~@TG#~^R3i^n(jU8O5Q=a&l}h{Q3IcvUIW?CHfYP~ zfNI+F(PtOpNW($+{liY&;3>A1_7mS}gklzWq)X2B(3VtIFznh)ZD!Bd=}gN7XNGT& zGwxFfdGp>0rJrwIqy2fd~Lz);_iJpa$D1;id9MA(cd@b0H1l?u2f` z?I71m0)KPmU_R6yJN+AqrTz5LsNf`wuF@7T{l$B;ieirZJ|rPw&oa{XQTNd&x23VF zJDC$}UNOo8x?`Omjvr)%MG;HbhSAonec@G@al9wK?L}}+ zu`;#Od862WPYl>NC}K8IjBi1rq|*p@d5c~aYuA)RW>3vvzU+O=452R!{)`~+KqFYz z`~xA!V*&NHp{`bUPf(*qzfRl=j|%qbj?*-gwHv;)_Qa#qqc~3WB5PZv$0^a@KoJu` zF~PI0Nt_G9Cyq+*kHXZCg0BzQQk~6_7odJp z4-NN>*#g6pa#Pl2Z4!;P- z^c<(y^EU(=wL!o6YS{MoBJ6(s7V=a^a`y+AaF^y6!mUd_7=O;_{y9w3Ai}QEj$QF7`p+2A@rq1-En z9kJjEGeNI6yW`akW~k{dcs;8h$hNhB#?%(z!-UtL)5Pl&+#q)9d`JmB!S1Je(1ag9 zpo`Z$9EY9o!{i-s+_X-r@!v6q&H$x#;ydjg#XS0}E0Odas|X3nVFSllDE>>dWTDBQ zS#_-k@JX^+W9g~w(Iyz`@fY6B)5c`Yza)8^0lc+)srawEC7EB)06&W7;vVW#7&UAT zOemgA&YvkW|v$bnW;nQ0g3r+VZYgc@Lp^cPEf_jSw&$;@9&v#cY4AAyIo6rihHrVMiJ1 zFzT6UOwqn|lH?g_Wc2ViLPOcZO`iqK)H$6{Yq|;G$~$D#v`BLGvp)3hsi1zUD>1vo z3`3n;NxP9DExm>dm~`>$Sxzx?Hs1A09JNQ$YfBD$XxL6>;?@Xe=6PSK`Sr&{tKc8m zH1oIck>*F^)6+AWbM?8gpihg=bb?}f!oj0Pw`9Uf zhfQdgK!YBLD^XKAjvle1ZO$w4Wz#}2O3Qb;PuX}_(Q2E+{!PqgBD?iqc1^b@YnLyE zHuY12N0;5RD%ic?AKakNhK@8HB6aqGT4e($c50%&el{$+zX7}brE#y(2GSL#AHl0o z^cP4LG3`9&twc8YcC2D$X*R2NWFRRu*~V;t97VF$UZ$p5Z-hJozRJO4Zc*Rvn-%o) zHtaS$A5%|GHY$@cn?0a*a2b{`RyaoayfidxA*5aj6Fvlo#K%)3mfBEXIp}3JKThF8 zUpB|&GBVD}o3TvGCy`&Dfx}NFA)YF9Ej{A?^AEb-F~^hpXl%&$Ou%`a$t^TuPvzKy z!MNp^xU2^*>CuTS-7p>>%|+zz%{g%=ZAdXXfpuQ)drm9%e$8S#$HcR%t=5z7zn2or zQJ+EktO1TVrh*531G##|hYCB=kwJ)fR@D^?MBIg6c8x0Cf){!p4+dnzM*!#D7lZG`WJsA6F=J>R4S zV%}~l#Xt#ERGxzIV^vI|t@N`tCBkahi^m2!;b#ja_Q2{9*l?KQsd25YhIk&-=*zzZ5~6;9hgMf~>d_%sv-JAj6O$I2 zVeaI;P~LqL+Ss_FS5PYBmD3+n--xB5!(zF+KgGCw9WCE>bBm(bCX2naJe%=Z^oZ=c zdx{j$6raPZ46yrl4IJ894D;r+!pRgHyxHCkHN~&MavSY&XAH1m+;HgqCLH6V>~KMc zCc8st2p*j)E^brA;=Mb?SXjEqeH&IOF6L*lZW|7heLa3i{o0987f_%+-sQA$VS6#~ zDOmdgyP;bleU7vW>A9K~Ruuk%yohh)#r93udxaw&%KpyGc{2ge;uqnf`H07>Ln+2} z)x(S{wF?vm$1_=rpO)YpY(cC_YzZH~tA1GzAJpjz7p?HvH+bLJ9TSRwL4TSqo3Hd1 zjs>!?vHLQ(7xf5~M`**wOXC%@X-WO=NflwHC5o7F6w}e7nyx+|P@%UnlWjLhCRMr~ zq|UY%sk+xr-FNjcpH?}-yO+Y!gs+f2u?Gg;{0UBXOW{HHTv)3tgQQ!!>^|SQSg^Q*kPJuZT zGdf>a;`CsQV!T==8-B!)9MQN$YN{s@BNt`l?WXv2g_@vukmOnpW!o({G=Z)GdLnsZakCUL7jEyZ5_#HIQvaWqRQ<{5UEbX6gWvTTl>*Hllg z_qjo&vFinEmUY%TDBY@p8s(3n_}oLGf!U2lBF?j^0Z*MLu;xYvGzU)Rlv27-IZt