From 83e103ac1586e9ca1e9da857160ec3626893700e Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 5 Jan 2017 17:41:58 -0800 Subject: [PATCH 1/6] Add pybullet setVRCameraState and b3SetVRCameraStateCommandInit to set the VR camera root transform (position/orientation) and optional tracking object unique id (-1 for no tracking) Fix robotcontrol.py script, getContactPointData -> getContactPoints --- examples/OpenGLWindow/SimpleCamera.cpp | 15 +++++ examples/OpenGLWindow/SimpleCamera.h | 2 + examples/SharedMemory/PhysicsClientC_API.cpp | 51 +++++++++++++++ examples/SharedMemory/PhysicsClientC_API.h | 6 ++ .../PhysicsServerCommandProcessor.cpp | 41 ++++++++++-- .../SharedMemory/PhysicsServerExample.cpp | 58 ++++++++++------- examples/SharedMemory/SharedMemoryCommands.h | 28 ++++++-- examples/SharedMemory/SharedMemoryPublic.h | 2 + examples/pybullet/pybullet.c | 65 +++++++++++++++++-- examples/pybullet/robotcontrol.py | 2 +- 10 files changed, 229 insertions(+), 41 deletions(-) diff --git a/examples/OpenGLWindow/SimpleCamera.cpp b/examples/OpenGLWindow/SimpleCamera.cpp index f0ba375d2..4b0b27164 100644 --- a/examples/OpenGLWindow/SimpleCamera.cpp +++ b/examples/OpenGLWindow/SimpleCamera.cpp @@ -71,6 +71,21 @@ void SimpleCamera::setVRCamera(const float viewMat[16], const float projectionMa } } +bool SimpleCamera::getVRCamera(float viewMat[16], float projectionMatrix[16]) +{ + if (m_data->m_enableVR) + { + for (int i=0;i<16;i++) + { + viewMat[i] = m_data->m_viewMatrixVR[i]; + projectionMatrix[i] = m_data->m_projectionMatrixVR[i]; + } + } + return false; +} + + + void SimpleCamera::disableVRCamera() { m_data->m_enableVR = false; diff --git a/examples/OpenGLWindow/SimpleCamera.h b/examples/OpenGLWindow/SimpleCamera.h index 7221f01a6..5a61a729f 100644 --- a/examples/OpenGLWindow/SimpleCamera.h +++ b/examples/OpenGLWindow/SimpleCamera.h @@ -15,6 +15,8 @@ struct SimpleCamera : public CommonCameraInterface virtual void getCameraViewMatrix(float m[16]) const; virtual void setVRCamera(const float viewMat[16], const float projectionMatrix[16]); + virtual bool getVRCamera(float viewMat[16], float projectionMatrix[16]); + virtual void setVRCameraOffsetTransform(const float offset[16]); virtual void disableVRCamera(); diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index e30c1519c..56fe09ee6 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -2191,3 +2191,54 @@ void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* cl->getCachedVREvents(vrEventsData); } } + +b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + + command->m_type = CMD_SET_VR_CAMERA_STATE; + command->m_updateFlags = 0; + + return (b3SharedMemoryCommandHandle)command; + +} + +int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_SET_VR_CAMERA_STATE); + command->m_updateFlags |= VR_CAMERA_ROOT_POSITION; + command->m_vrCameraStateArguments.m_rootPosition[0] = rootPos[0]; + command->m_vrCameraStateArguments.m_rootPosition[1] = rootPos[1]; + command->m_vrCameraStateArguments.m_rootPosition[2] = rootPos[2]; + return 0; + +} + +int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_SET_VR_CAMERA_STATE); + command->m_updateFlags |= VR_CAMERA_ROOT_ORIENTATION; + command->m_vrCameraStateArguments.m_rootOrientation[0] = rootOrn[0]; + command->m_vrCameraStateArguments.m_rootOrientation[1] = rootOrn[1]; + command->m_vrCameraStateArguments.m_rootOrientation[2] = rootOrn[2]; + return 0; +} + +int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_SET_VR_CAMERA_STATE); + command->m_updateFlags |= VR_CAMERA_ROOT_TRACKING_OBJECT; + command->m_vrCameraStateArguments.m_trackingObjectUniqueId = objectUniqueId; + return 0; +} + diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index b8b27dd53..2f553ea73 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -314,6 +314,12 @@ int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, dou b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient); void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData); +b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient); +int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[3]); +int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]); +int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId); + + #ifdef __cplusplus diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 911a501f3..7f98b8dfb 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -44,11 +44,14 @@ bool gEnableRealTimeSimVR=false; bool gCreateDefaultRobotAssets = false; int gInternalSimFlags = 0; bool gResetSimulation = 0; -int gHuskyId = -1; -btTransform huskyTr = btTransform::getIdentity(); +int gVRTrackingObjectUniqueId = -1; +btTransform gVRTrackingObjectTr = btTransform::getIdentity(); int gCreateObjectSimVR = -1; int gEnableKukaControl = 0; +btVector3 gVRTeleportPos1(0,0,0); +btQuaternion gVRTeleportOrn(0, 0, 0,1); + btScalar simTimeScalingFactor = 1; btScalar gRhsClamp = 1.f; @@ -1369,6 +1372,32 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } #endif + case CMD_SET_VR_CAMERA_STATE: + { + + if (clientCmd.m_updateFlags & VR_CAMERA_ROOT_POSITION) + { + gVRTeleportPos1[0] = clientCmd.m_vrCameraStateArguments.m_rootPosition[0]; + gVRTeleportPos1[1] = clientCmd.m_vrCameraStateArguments.m_rootPosition[1]; + gVRTeleportPos1[2] = clientCmd.m_vrCameraStateArguments.m_rootPosition[2]; + } + if (clientCmd.m_updateFlags & VR_CAMERA_ROOT_ORIENTATION) + { + gVRTeleportOrn[0] = clientCmd.m_vrCameraStateArguments.m_rootOrientation[0]; + gVRTeleportOrn[1] = clientCmd.m_vrCameraStateArguments.m_rootOrientation[1]; + gVRTeleportOrn[2] = clientCmd.m_vrCameraStateArguments.m_rootOrientation[2]; + gVRTeleportOrn[3] = clientCmd.m_vrCameraStateArguments.m_rootOrientation[3]; + } + + if (clientCmd.m_updateFlags & VR_CAMERA_ROOT_TRACKING_OBJECT) + { + gVRTrackingObjectUniqueId = clientCmd.m_vrCameraStateArguments.m_trackingObjectUniqueId; + } + + serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED; + hasStatus = true; + break; + } case CMD_REQUEST_VR_EVENTS_DATA: { serverStatusOut.m_sendVREvents.m_numVRControllerEvents = 0; @@ -4287,12 +4316,12 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const gSubStep = m_data->m_physicsDeltaTime; } - if (gHuskyId >= 0) + if (gVRTrackingObjectUniqueId >= 0) { - InternalBodyHandle* bodyHandle = m_data->getHandle(gHuskyId); + InternalBodyHandle* bodyHandle = m_data->getHandle(gVRTrackingObjectUniqueId); if (bodyHandle && bodyHandle->m_multiBody) { - huskyTr = bodyHandle->m_multiBody->getBaseWorldTransform(); + gVRTrackingObjectTr = bodyHandle->m_multiBody->getBaseWorldTransform(); } } @@ -4595,8 +4624,6 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() //loadUrdf("knight.urdf", btVector3(-1.2, 0.2, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("husky/husky.urdf", btVector3(2, -5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); - gHuskyId = bodyId; - b3Printf("huskyId = %d", gHuskyId); m_data->m_huskyId = bodyId; m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10)); diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index ca4d9e204..9358f41a7 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -26,9 +26,14 @@ //@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet! extern btVector3 gLastPickPos; -btVector3 gVRTeleportPos1(0,0,0); + +btVector3 gVRTeleportPosLocal(0,0,0); +btQuaternion gVRTeleportOrnLocal(0,0,0,1); + +extern btVector3 gVRTeleportPos1; +extern btQuaternion gVRTeleportOrn; btScalar gVRTeleportRotZ = 0; -btQuaternion gVRTeleportOrn(0, 0, 0,1); + extern btVector3 gVRGripperPos; extern btQuaternion gVRGripperOrn; extern btVector3 gVRController2Pos; @@ -57,9 +62,9 @@ static void saveCurrentSettingsVR() FILE* f = fopen(startFileNameVR, "w"); if (f) { - fprintf(f, "--camPosX= %f\n", gVRTeleportPos1[0]); - fprintf(f, "--camPosY= %f\n", gVRTeleportPos1[1]); - fprintf(f, "--camPosZ= %f\n", gVRTeleportPos1[2]); + fprintf(f, "--camPosX= %f\n", gVRTeleportPosLocal[0]); + fprintf(f, "--camPosY= %f\n", gVRTeleportPosLocal[1]); + fprintf(f, "--camPosZ= %f\n", gVRTeleportPosLocal[2]); fprintf(f, "--camRotZ= %f\n", gVRTeleportRotZ); fclose(f); } @@ -109,9 +114,9 @@ void midiCallback(double deltatime, std::vector< unsigned char > *message, void if (message->at(1) == 16) { gVRTeleportRotZ= getParamf(-3.1415, 3.1415, message->at(2)); - gVRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ); + gVRTeleportOrnLocal = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ); saveCurrentSettingsVR(); -// b3Printf("gVRTeleportOrn rotZ = %f\n", gVRTeleportRotZ); +// b3Printf("gVRTeleportOrnLocal rotZ = %f\n", gVRTeleportRotZ); } if (message->at(1) == 32) @@ -123,9 +128,9 @@ void midiCallback(double deltatime, std::vector< unsigned char > *message, void { if (message->at(1) == i) { - gVRTeleportPos1[i] = getParamf(-2, 2, message->at(2)); + gVRTeleportPosLocal[i] = getParamf(-2, 2, message->at(2)); saveCurrentSettingsVR(); -// b3Printf("gVRTeleportPos[%d] = %f\n", i,gVRTeleportPos1[i]); +// b3Printf("gVRTeleportPos[%d] = %f\n", i,gVRTeleportPosLocal[i]); } } @@ -1040,19 +1045,19 @@ public: setSharedMemoryKey(shmemKey); } - if (args.GetCmdLineArgument("camPosX", gVRTeleportPos1[0])) + if (args.GetCmdLineArgument("camPosX", gVRTeleportPosLocal[0])) { - printf("camPosX=%f\n", gVRTeleportPos1[0]); + printf("camPosX=%f\n", gVRTeleportPosLocal[0]); } - if (args.GetCmdLineArgument("camPosY", gVRTeleportPos1[1])) + if (args.GetCmdLineArgument("camPosY", gVRTeleportPosLocal[1])) { - printf("camPosY=%f\n", gVRTeleportPos1[1]); + printf("camPosY=%f\n", gVRTeleportPosLocal[1]); } - if (args.GetCmdLineArgument("camPosZ", gVRTeleportPos1[2])) + if (args.GetCmdLineArgument("camPosZ", gVRTeleportPosLocal[2])) { - printf("camPosZ=%f\n", gVRTeleportPos1[2]); + printf("camPosZ=%f\n", gVRTeleportPosLocal[2]); } float camRotZ = 0.f; @@ -1060,7 +1065,7 @@ public: { printf("camRotZ = %f\n", camRotZ); btQuaternion ornZ(btVector3(0, 0, 1), camRotZ); - gVRTeleportOrn = ornZ; + gVRTeleportOrnLocal = ornZ; } if (args.CheckCmdLineFlag("robotassets")) @@ -1474,8 +1479,8 @@ extern int gDroppedSimulationSteps; extern int gNumSteps; extern double gDtInSec; extern double gSubStep; -extern int gHuskyId; -extern btTransform huskyTr; +extern int gVRTrackingObjectUniqueId; +extern btTransform gVRTrackingObjectTr; struct LineSegment { @@ -1607,15 +1612,22 @@ void PhysicsServerExample::drawUserDebugLines() void PhysicsServerExample::renderScene() { + btTransform vrTrans; + gVRTeleportPos1 = gVRTeleportPosLocal; + gVRTeleportOrn = gVRTeleportOrnLocal; -#if 0 ///little VR test to follow/drive Husky vehicle - if (gHuskyId >= 0) + if (gVRTrackingObjectUniqueId >= 0) { - gVRTeleportPos1 = huskyTr.getOrigin(); - gVRTeleportOrn = huskyTr.getRotation(); + btTransform vrTrans; + vrTrans.setOrigin(gVRTeleportPosLocal); + vrTrans.setRotation(gVRTeleportOrnLocal); + + vrTrans = vrTrans * gVRTrackingObjectTr; + + gVRTeleportPos1 = vrTrans.getOrigin(); + gVRTeleportOrn = vrTrans.getRotation(); } -#endif B3_PROFILE("PhysicsServerExample::RenderScene"); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 4efee8023..cd22178f3 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -594,6 +594,26 @@ struct UserDebugDrawResultArgs int m_debugItemUniqueId; }; +struct SendVREvents +{ + int m_numVRControllerEvents; + b3VRControllerEvent m_controllerEvents[MAX_VR_CONTROLLERS]; +}; + +enum eVRCameraEnums +{ + VR_CAMERA_ROOT_POSITION=1, + VR_CAMERA_ROOT_ORIENTATION=2, + VR_CAMERA_ROOT_TRACKING_OBJECT=4 +}; + +struct VRCameraState +{ + double m_rootPosition[3]; + double m_rootOrientation[4]; + int m_trackingObjectUniqueId; +}; + struct SharedMemoryCommand { @@ -635,6 +655,7 @@ struct SharedMemoryCommand struct UserDebugDrawArgs m_userDebugDrawArgs; struct RequestRaycastIntersections m_requestRaycastIntersections; struct LoadBunnyArgs m_loadBunnyArguments; + struct VRCameraState m_vrCameraStateArguments; }; }; @@ -657,11 +678,8 @@ struct SendOverlappingObjectsArgs int m_numRemainingOverlappingObjects; }; -struct SendVREvents -{ - int m_numVRControllerEvents; - b3VRControllerEvent m_controllerEvents[MAX_VR_CONTROLLERS]; -}; + + diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 7eb9d37ad..a517659bb 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -46,6 +46,8 @@ enum EnumSharedMemoryClientCommand CMD_SET_SHADOW, CMD_USER_DEBUG_DRAW, CMD_REQUEST_VR_EVENTS_DATA, + CMD_SET_VR_CAMERA_STATE, + //don't go beyond this command! CMD_MAX_CLIENT_COMMANDS, diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index da4cf300b..2fce9796f 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -2431,6 +2431,56 @@ static PyObject* pybullet_getMatrixFromQuaterion(PyObject* self, PyObject* args) }; +static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObject *keywds) +{ + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int physicsClientId = 0; + b3PhysicsClientHandle sm = 0; + PyObject* rootPosObj=0; + PyObject* rootOrnObj=0; + int trackObjectUid=-2; + double rootPos[3]; + double rootOrn[4]; + + static char *kwlist[] = {"rootPosition", "rootOrientation", "trackObject", "physicsClientId", NULL }; + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|OOii", kwlist,&rootPosObj, &rootOrnObj, &trackObjectUid,&physicsClientId)) + { + return NULL; + } + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + commandHandle = b3SetVRCameraStateCommandInit(sm); + + if (pybullet_internalSetVectord(rootPosObj,rootPos)) + { + b3SetVRCameraRootPosition(commandHandle,rootPos); + } + if (pybullet_internalSetVector4d(rootOrnObj,rootOrn)) + { + b3SetVRCameraRootOrientation(commandHandle,rootOrn); + } + + if (trackObjectUid>=-1) + { + b3SetVRCameraTrackingObject(commandHandle,trackObjectUid); + } + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + + Py_INCREF(Py_None); + return Py_None; + +} + + static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject *keywds) { b3SharedMemoryCommandHandle commandHandle; @@ -3732,10 +3782,10 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) { static PyObject* pybullet_applyExternalForce(PyObject* self, PyObject* args,PyObject* keywds) { { - int objectUniqueId, linkIndex, flags; + int objectUniqueId=-1, linkIndex=-1, flags; double force[3]; double position[3] = {0.0, 0.0, 0.0}; - PyObject* forceObj, *posObj; + PyObject* forceObj=0, *posObj=0; b3SharedMemoryCommandHandle command; b3SharedMemoryStatusHandle statusHandle; @@ -4304,15 +4354,15 @@ static PyMethodDef SpamMethods[] = { "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, + {"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 " - "FORCE_IN_WORLD_FRAME coordinates"}, + "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 " - "TORQUE_IN_WORLD_FRAME coordinates"}, + "WORLD_FRAME coordinates"}, {"renderImage", pybullet_renderImageObsolete, METH_VARARGS, "obsolete, please use getCameraImage and getViewProjectionMatrices instead" @@ -4420,6 +4470,11 @@ static PyMethodDef SpamMethods[] = { { "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)." + }, + { "rayTest", (PyCFunction)pybullet_rayTest, METH_VARARGS | METH_KEYWORDS, "Cast a ray and return the first object hit, if any. " diff --git a/examples/pybullet/robotcontrol.py b/examples/pybullet/robotcontrol.py index e94d6d5ba..3541b9d9e 100644 --- a/examples/pybullet/robotcontrol.py +++ b/examples/pybullet/robotcontrol.py @@ -23,7 +23,7 @@ for joint in range (2,6) : for step in range (400): p.stepSimulation() -p.getContactPointData(husky) +p.getContactPoints(husky) p.disconnect() From 249f843d4ea0d6a99017015faa462786616bac02 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 5 Jan 2017 18:18:46 -0800 Subject: [PATCH 2/6] update pybullet quickstart guide, add setVRCameraState and added drawing that visualizes base, joints and links. --- docs/pybullet_quickstartguide.pdf | Bin 181478 -> 194354 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index a46bbf1284d1c3cc7f3b8c9cf6fcf2926bacdfff..41d4a60b234fc99853b4b00191e0697d607bf471 100644 GIT binary patch delta 98680 zcmZ^~1ytWa_vekfyYs^-?(Xic#ogUCXmKxI+*=%q6u071+}+(>wtb%W-95YK{Bx2| zlJDF*nL9H%$wc;}5bMto(Wz7evKWB_7T263{1m?c5ntSsz*Q)hqG6@71Z#wHKIBq&p z9|SKT>u7G_{Wlj59uWI~@{o13bOLd)f>=OmAZ9fuCwCAh%YS#&ZG0_2JnSH56;}(- z|7OYq`hO;7SqYGyfCU!|E1Q`ak0mPyCl8ycr71hRr3EJ|k2xnh3kxd;m(c&V!26#} zQntV;nTRFmlpvFcqCsr8$dTs9;7LARJ+|b*ltsJlEP6S?QCA;UwM-zVd>Jq+ZG^0J zP(MUnQVPuyAvC1M#r^HwYCID+@Oe7h4K5BuNTd2syesh?VNTDe<;SlKyKf*|n$V^u3O^B@S8?95>3et&R{LNN12#k{%Qmfo%Y&_{?8#P*b1 zT^(k&D&E7~>8(wmmqo-LwHeG#Sp7)!08$+j56`=1ZDP%n{~^mxKFp2}%}i1RJ{d_8 z;+x7?clkv3g|qVWoB(puqAs$)8h?=IhKVs4m^!r}F@lAoxtn`RQYe19YzjDAiYZhG zJO_x2lLy4X%GGcNB>;)c1>)pp1#xoxU3l12uAoFxHsA;v65(!Okhnk`e`Dw5U;%M( zrSw3HHcX*rLLsw(*tyyNB>%fBfJxC9NN zxJwYotROaS?*F8)@$mlVD3b&P4Z#Hb;Qx~T_PKvYVdLaZVI}&ULP2EvPi1HOugbyk z&!J(N=nev&^>6+D$2i4_R3e246b8=*V&(j&u%?KBBvQ`)t8n~tWlcdRlSt_#3;SDS zR<{2Z`Cp6ti!p)x4<)CmB@efqjhUmP35Zz=^taj6EX>^h_Fi5V5HI)NYJ5 zRR5zPCp+su%YSA6k7bH61u+~q4~UhE8^rsc3NWT1fam-h$X}6@BSn>xI%S;_34)V7 zy>1zt2AnG$fP#Gy%k$ZZnS{Bn!|(c`|omIaKTrL>jzNcLZBrBID1g`N5tW0waLa(y)4fm zar<_XW(~DD)wMZ9Ot%fv?zbXFrLF+}H;-#&EMxD>x0|B{(o*5I8QoD9?hj9Olk1Hx z|E%qZ3nOJx;ku)f4HEzw(iVa`)o2@0P!uZQt~}RV)7u=I-YsK;EYO)>pd&}9vpyTBO`^obBQc5y& zSSRmm@tJSjV(T2L@fi!FSm?ZLUz4>Y7n=gyaB&DpM?MfQn-e03)+_j8jdmvms)25o zkFBKclsq6|h1%XmulH#GP0B2%@)a$_zfpF(^eSI}*z}P%ifJa}JegcXBsNyWd9cA= zJYN!9uiikykGAY&z#N5qR+X?NR%w=Bp*p5W6c(D>MJe#NW*Dxzj%xu?Wf3!akURpu zS}+r&NeqC+)o+jI1uurp!xB5RRG8fT<4%Y2uFL0J{}WR0=PxVS*WG@rUwM_yr=CJi zc#ep|Ory>4H%qC)936I_+HOw}a`4In4al~Y46eYj7#Y|aUM%ZMlzCgiS_?C>y`vW) zCs3Fp0%dubma=ISv+!LRZBtb~>D&m22eXy(m5Km)YPcDy2m|Aq(dMJEdL=jP)5o@H zV}q&su<_v5>@#J>BL9>4kIyK*w9<19 zLSOzy<@Am{LE-clib9O5pmK=CXdkn9?N9MntH8+i2|YW_&E1?`v{!ng;c+ik zMtP}}@J46MHC8JO8e>02WMQ=eEhvATa4D=j=jZ6K`B7r?`1=OSW=OxojL!=a5ZTg& zOl#f*S81323p+#H&#^eS<~Ut|d5~$XPyB0cMo?Mc(H;d?)u(&|8^XKx+!Sw*^u}K- z-2_?AUNgXBe}ClTGdd)P??8!*vAc9VQ(#wQro{i%!1(#=)ovF_htInC-I@XsdNoA$1 zQNB{|>`*)4X1_iDyxY{Z)(&sKe{ps$X(WRbG1mOn-%WM{`^!geQ7}Tk?0(YTB~?}1 zKpG#C)q_@PJJ>Uq(BJD@A&~TFoBA-f4$f{`8>b7Dwfqe#bIb0k8Qq%YXN1_ng8){< z=$8mnV*<{-c%D=BA`8im@_cPWZ83v<+Y05#;no!Wf$fZAkHPI;bHb+gbDzIKd2m#F zPIkP`ofytaj&YZ1YKN3D_5Z~8oc{q%y2@4cZmFy50Y&!cmRfaM=t%$gh(8)yqV$7XggD4|ftn$ok z6B*x@cDK3Ty%43eU&y;qvk7RRPM-N0+B633X>4)=w92)KRftEmQaJS1@u@lSQR^*I z`gRR#g~++*7go7lxsS6UpJOd{#Ou0U)N3`=XGVq7i;tfesfUiq(=>U1Rc;P({<+tC zT(eZiQ*c@lUeAs2or74KJbxk8jh8t{*}UclIM~>E{?C0Q8!Hzl>;HAFKke}H|EhT} z9C#iu@>OB-_Nz^%EDafamGlH^;+zWotNu3i@fs&9aowPJWc*HT_ifgdgMyI+Wn7!za%G#H(+eWl5tMOto89!# z)+N;}*jJQ(;C03eHBYlBiq%xlbnyN>s_%m2ZT)fTQ&0(ph}cHfry{%DdZt>iMnnj_ za|kZ4=PlG9rbFLNo_q6BQK)M3Xu3Wr7`tC6-bn|3bd=0ZiSt6Nd`FXT3{sX{P$4~Z z4B7xt@7Ql6(~O?b)pX#6fDkb}cnB315gaVY$PO2M0Hqwyq5xX;G)U@Puzag51YY&K zOpx3bBc9kq_nD3tO(B0e*ww2W3*3tG;HyS4>Yos2`X+9IuUsB-a2?l3C3%_bzoApu0(cJ_gj6pQVf8?DmbdK zFXX&7P~XI6@fx~?Q#sjvE8e^5tW$@8r2~`UIN(Yj{{hNop9YH;PR%0_N;u*;ZNr^s z7UhFG>OS;8bA2ZKO;M9t<$^C?;5LOxt0bm|Js z&|Y1}DFigFK-A^uz6PoxTyU{amqqy<7`^bv3p? zKNQhR4i_)$l5r=^xgB(qg9%Qkt3f1Q0^4FxM(=*ajumU>PUnXhOhoQL(>RY3K4kn+ zauH4MQ*`KpXd-OS)ug^W@2zCZQ-eT0%hOKRto(HY;MwgGT#=VN8qew(Q60MR* zA~acCa}3{;gob?f_=VV8V>Eh%6l8fgCiJ!02y+Z(DmD~@P$TcqsAyDEreKw^ zAxQ`F$X_ECA(HUN8PJZbQ6;4rxsS1eyqUay3KAlyqbsc0y3xM9AzlPx-954c4a>@G z7LLlceLLE7>l?zKyq@eu`3HO|ZS{n262=BuNrzvF_+OTnjg)J)0jPjMBMaeIaHObZ z4?1$fr0@Wu=;x$ReX~dM$tTSt@5c8 zco*^ccGs7mJYIs$^lB5RK|*6R*X%5DdxtZ+0Z7eS)fbZ=n3k6n8SC-4sw~k68DyO! z-o2zl78?@BI+-j`^F`|xSEHLYCfpje9i}Jw#Jv~w9n#rebaucND|9{zfSmof;WDn+ z^1Ipmxx7+2wwdgeUoWo^aS;k-VQ?9QmvD*KQgp3DGg>H{_J^V#rHDZ%Z=1%o9lRIb zz6*MvZmw1~Gxq(+%9(B|eaP(W%gWbe1}{UQnvdZ7E5YMMkPcl&U)S*Shd$5PTRhjT z;4&^`4<8~=*afhq+E`Lj?@#Uy-9UQoSIa`&bBFwOC+b3VFfaJiwvx^#u7Y*qzJ^V_ z^Oc8|H2wn2QqoPYFU)2uB#W@Mb#?7|M0vGtatNdr_l4FFZDPGwb;#MFL?2r%tIa$c z5yqdMlTG&?F25dHx*(I4`$a|GqYphjMfyahq7PYofujOQPR*+Ig$UM5`FWzB$B#F* z@+4RMu%cTX^7jXgUoVLn@^x#&PC|XXNG6d`o>(TWL=e14Mp}&aZmgp6zxcQ2U{78( zs7z>+1DLVfCni|9zZ;3K;EpM-;p12&@SRpXyr;Gp*d?0WM*moJynJl$CGhNxpa& z$R|*3o!)_5Hv5j!7lRQ9_NXq|@mKW!u4xkmt`PkLN=|cv) z&pw3|3(vl3v?7e+^U84Bw?wN9#SJ-vFF~xJMr(rcMlhPG{EI2!A?NOuQs&j^=E(^p z4bn?9ftsGPvtL0ip8o(>GLT%0Eex=zzj^v_kN?oye4mhxP2DqsJu@ffi@DYgiY5x- zmjT$1H!NFH$+BwF_MUi_1Kjg!{VVhX*WL@N-FKfu-2-?_aakJoYBm-=(gp*)4C1&1 ztwYIS&CsDfpqr%i^9FB>Swn~18N??hEv!e4@EF6K=gpFWUJ2Im6PRH6HH(cW_hIRk`~9_{2HdUsd7&m6p!+h?7&)OYH@*ZnPn3 zuLZpC5SPVm2fpJBNcJbZ);rVx{))gG|64~ZzE$@Xuf(-IKp~z+_BN+bLHBfQTN{VJ z;Su}DvN$G;f+w%SnZE6y!KdKZO|^d%2K@VbM&H+85Z;>7_b6!{FyTtx@xVBZ-B9Q* zJO*W%OorBU^CADOTf8$-*|z_xfFo~nvR}vxV$Igeb@NT%W5na#tJ$l%KO~U&@l}}S z6xR^56O$>LfK|yoDrew*J7;@s+uS9$MQ0Tx#3)36j3A^VdGL$B4ROt2jp|(X9C$h}TU%M3^np^Y96Y}Ag~;{H4bJ5kNbqj*tI)nZ?x3z2 zIJy1RUa{`(qiusjK1r%l&-K zzll$pTGwb>Ilk)018pF>R(RUhG8I?;>ZDb$NtMZE`egRPU842=^4;$pMdrh;A91@Q zH8PG>T@zh9(Yx!C!#N_u9-ZW^e}dtyq8NBxgS!+|Ty4_%3wDb~*O=1{N&I~#_V&`X zjT~)Si+<9}Rj0`^jh(9}gpJ=C_-2eE^aCK5z}H7 z1y~B}h;GI(tI#`}T8GQmKBEz+&CFIIORsQ;-cH3k7gePa=wki8%;P0T`Ef595Xiq zt>-ZwMgmU*074LR6WcnogOS2Jgy1Xgl97zjZeWu8_gjqw_3$zTB@cmAKe`u<<4+eA zE$aK~ySp38fxz|Yu#Oz0PV%~b1(am*ez8h(DqaOca^@6j z;2Oavbup6IQ#6q$GNoP0kj8~Fmoib}8pa1RFmz+f?(s`YWVUx?db{L0^+lrBu-|UL zZ6-h_lq~T|DH5Mpv@3p%{*>Vl0V~5MOIAUNtkl=Mi$@f}yruq#q|}Rhsr~rvRfZ`M z*wnqle4=TUVM;O@s@dhf=9i^OmqoMzsK}Co5AamPKJC#eL({22YpP*urYI1Ib85(Y zXecAk$|!QAWy$i}7HB0))>p(WSA_D}5XF_jb0qyL&#o>eIi@<3MY&7T&yslK5J|B? zP%N?G$YClOg$gw;7IuAbd2owqp;~2g#BToL7wH$aG9>tg=74>*VO8ne#}T&~$X*#e zJ3w)(advXPa3;;K3LGNd5!w?v=-lqyn{YX3C2a+!fT_Gg;Umds_6`Z4plf>L@Zy%u zVQW?&sjO!ve6uijKX0q~dgbx#wc!;dkmiHvLm-!~?GeCgW8q8G1wJ(Fc$a@ zmOB&i*!L>`I_i)4f$%~1LGS_aeZYKBf8cy@eV}|WeUN+zeSm-9zQX}uKN3G8KQcbT zgnyGBd_1Hd@Ym$%=w_whS#Yx4Tw@#68~iS+U2b>oTj z3Gr3v-p?qA{f}$^do=5be@fphcB|pPh0_B#k zIW(1sITE2nj=1R0@hwczr+NFj_}qF~!@CYx2Hd*H;@B7%iIb&u5z3jXuC3VUatl3IW%lsg)n+cv^x)Qn5sw zzGI6nJ2b043u~A(a|*d^9?Q4*>{jEsZj&8u2jevzPCajkxQvGN?n~F$^x9R14fnyY zq`r?y9w*%PtG9>ygCrYj5B(|1f^TE<4l8+Ubt!)5Pq?1YUJKl(OKleezu#a{Ncdi- zM-^+@pO;UZ+JUF}m5cV5^%v6Dy&=`d%c2BfUeDJW8lkt--HOSs$7`umZwk+LbpG{7 zVyFIiZqq@+x}CViE2+~*;TU2nS-N9ib(8c7=$vc*-M#(B$qC!^%%t43tYo4~ny0@n zp6FT0geHz^S1NJbDu=D7P8zfDe#%v#LFX1hvH3pA{Q%Z_L_88vAARq~%zZYT8Snx% zMLnkCBuf^W;D7ztvpl!clUsBh^I$BIkw21?H+9ApGqL>A7BNZun%{rmNGblTY3!>R zRWnU2z+C1xdi2xvbBs*_EdHwC>5km0sM^^%IztYtqff#y#;K!M?60<(7i$kom{YAm zV>TFd(QKf`lDp1>$~9!!*L_`4v|>OOI;S(4L^Pr%Y#cQ7*I3!Q5eINm|3r1YPgEfW^LNeE*x2fF5mQH12Tz+VTxDt}G&)kp-y zOTHpTwsBaOpX2*zeHY9HMrX=Z3A-$C6;28<|i|v&{ z4FMB@Y1S$yu1Jf4&@Jdc;ZTk*Wp~@djL)<=`akPFJS?2Vv26(6E%_u#g!bgB8`|$% zf^SK=VfMf>wbv?!Nfc8gQGerXl61Y@Gz+EpNdV?^@Hf9DN9# z#5C8aI~?s9(Q~rarO--Tq8dA(gDpJ?ri!VoLTA8ZU>PL!rU=Kiy!=I^jEEM+`BP$C zKJDyNM%HAf#3bY3tm|s&UJK`_i(T3dLt1F0%RO7A?iYvp7G9OU@vxtfj2ZiN^74Xm z&RySRH2DYmBA44fUu7c#6%y*+ zN~BpP5B*f1MZdmNiS;SoT0_Q@b51AVIWWbSZJ1j19Ujy|tA8aat`X&8^OquAVmK^w z7setJ41Q9Td7v1V^vz!fZkm21adClqT7^H?{H!0CUO1j|z? zGYa-T-L8>IN$eEM?vA;&DE2H?bSE%W*LP<=12afGkD6XMA}gJ_mHdUuN9ItzQ1=Py z1UvThJ1)LY0SS5QHNyhgGsGIalKr!PKzCHh3L%6n)0^mN!j#n^(D)3MUZJCy2g2SZ z=lULs85h4Hoh>UbO#e(4G`g10oYrDm$;-*?NOgNz%RKjg(DJGau7&{* zkARWa-ef0T#rg?LMm9ffapxac+k(B&KQCE;ljq_3ogk0X72(pRMa@rC3Hy)a6s~Ap zf=}dA|@MBKyk zJ*kL*_b)#0mrKRl?*2n&=y>yA%_81)msa{8(s@UciirL}fB*kiD0dSR#l=u$_y4nk z=cUa2yZ3KJLC9MVB>kgBy#4Nw)IX&0*8f*Q;dX6F>Wd?C%>0L4XNm~D{l6gmJ0^?( z=S3Pa5kUzZ`wK`{yu?0`8{Y0)X1p=c_|Tu&e_(Lqppa&F{fmaN|0)Vr=lk(EUBL{} zNqe;QM5(&*oMH6yhMg)Vtc#cAMHBHI{B-5vBeT=EtQT%?N#z~ z3?rOy1JeeXwE-6m`WIDq##*VsiNS*eI01=EUCOd(Ym)fvh`=Vu_x(Qt!`|y}W&i_AgGnzw{-3$u(tIWlGq?_S0$`i z?nnj@IhC@PWDwbbPcAxk_lK8<=ysJCcI~{Jj3uG6#L(9=8W7$dfwP$KISsZzlBxayV1U{hC~|+H zT3b$%_lwYnQu;N{ytderc*LKG5V!3(X0B2&7qzX3W9ZOuLFcY*z{ij>i zguRC872UT7HlIk}1&DUs)32rmKdbE*8pmd;E2{PM`wZR;Gy@rGyw=Y7`b*(ci$l&= z59kI_{I=*`@2a!k;;yme0fPpEWcnq|O`-l>#2oUseJc`EjG%8rhxoJ`900}4mFQDk zKW)h;Cfa$rFLb{?{i5|ps3BKP%4eZhlnYfWo28wTD^b(9mirD>(#pEZP||=JH&z&o zo@AwLs69^8M~Pj&V}K# zrY^kaNi4ZvQpJzD{Kj2nlDR)t&!oclKT_a(JS-sTLijQ0LU|d`mC6|q*9RTDUMg~J z{l1=-@k!Cq-`{X*Yyd^V^aplwbahKMt@ySLDA}TH6pIQ=$g7q3&nb?T_~)v{24G8d zIT7ggW%FVpj<_mzd!7O&XP$Y^541~Xo}&)0U^Kg2G_TH@gtK_Nj7!9DLskBcYCWHm z5c2eLb-u4AjfN|-8MtDGxa6!R#SDc)H@sVKCvY7(m&n5UFaYtde|}@zm?_!VnJM*f z9eqRy7qyk7e7T=F==g0&tMTF+E2ROeJ%(q6Iv?-c<~5m35-@{SPQvO+RMaO8TlONA z4t4M(x7xPSbx$)_Q+IsdnY?!SIUyLk%_v1GeYQD$`QZ|oxx${7u9CLXveH8P_jlUY zlnDe~D{TA9!fimfg2{4D(!SD^ON*88hYVfv;4y3NQGm~YBbED)e#A-zLhD!pj~2cO z^`&v!@}m(fUjR2Dz;G3uWXLnJ=cN7j0%N&k?f0?mF;lH@&)?tOPpecLM}%r(XwJcw zNUGS3>;5btFH0a+s_NE?ch%=xbtfW}(uvwU=3Ojl+*1JBD+Pm(7_X=|Gv=EYbBrd( zdG87@4S7d1Wy%%_M@Q=5BOx}BBO%0B?;Uyt-38y}>FO#C^za9VE!s4{lf-RNS1Jt3 zCfeBZq{-17(Td8(H8Vk1VV+=pHNY=_hb8On~fcD9(w zz)~-<1R~tzXcYaGFS~PU;keLXAE--7g3HJxI2xl*nA&40?m~K4&@Fpi7r`$uFhAic z!Qu8kgiYp04~QX5*a&>1AeM1@Myi4LLIwaBaTDS8xD$&m#aETUY!(g;tU!iWI>Ra> zN?X^+cJf`gA9@#v!svnE96WjVv`Iod6L2l0hQVH&q?edEq`9bqCSdWeFtQ*=43Q|( zG8Ddqi5;OYo-NCC-_G0@Aw*Y`Af3@ritLrd*!|_lDC1Yfq!M9=lr_Yq|4^(JtpX(H zn7Nmeh3x^G()fy@R>pa+pVrXHjX#!(zbSxHhJ3H_Y)VC+A>YEauODvGpR~x(Y*7qQ z9^gM>acyZ<5!{T0M(#g7xkYz%vp&MV!>30EyOZziI>~dSkd{aL+8BKnU)Y*^^r=RD z0DC~#2)_8eF${DA)C@RUv|s4O7y&(T)bL!?0K7ofSF+=HlowQyPja_Hv(Z+Y7LRy- zA6P;WHJR_m9|l8cuCVcJsSH%8DF?%Zf1i30S7YoNF`tRaJI~6xBaGO92Sf_R7Ll6N zupV07x;+cNWn%I$FC=A;3HCs@N}ba_aIbg6K6?85butTwq3%rV!f_))h5={2N?V#+ zAv(127^I3#rFNWd%@_3)e4t1if*oo^ijquP;_!<%;8&t`~k4+*0DS3LcL8;I=oTr4F-5QOSdGnvajl%3!G=gDesou zxIMu3#{=Y)1%5p2;`G?3wb{!~Tz9pIgDr$*{iU6$_{)8SX-CB5eu< zVy#}~39HjUJ0nbllNzq`C=I|uS$G9pzWH5IMJ zg=YUT?UZEXjrB=uBW5&+>!gIO`bG4mn>HiH@FLimrJdIw@b(0}G1?>AyHb#@`76X@ ztR>>bya|DY?lN=e<*o4#pPY|#8V-c4O@33Fz~s<-XTuD#N^DO!zp(T$)c$+gv+zq= z+uMcmaa;W!nMbtFP@_nUhu`4%i4iwvVQw`+ZPrv?c)u`dX7k5O^GPpo42CsMEx_fR z*q3ii8siWTX&ixw^i8OO{x9?dQ9JZ?d2C;ASnNBny)FZ%gQ$w8?8d-yyET6gh{*t4zEjd}>D()Fh?dT9@{rL5Fmw zFudlt)+`D?27x1lIl+a;s^mG-@a6KyS}EX-o?PBWhh_sq=HJ3e7XBdMOylx}J?{{a z3wyn7KvsypLUpgjcwPlUnJx(Dw}9o3JYA?b^*)|cfQ=Ub;Z2kfYbC-FCX8S&%{F5` zK=yM~gp?S4 zqv%HfdIQ#k6PIpa95?^RxiJ4!Zw2BV0v6%0DIz(s+`3p&jRDR-67pvVD!MbRB$-63 zI3*Yz2Bl|h86gvP6V5%WKEvtSXE@0WuEx!xfTqDi*5@nHpa>l9g<0}C;TG2$#nX#0 z*oetXz5;l_ee+91alP(w$+3fZglU9r_PONT3f-QuS;^07-bK!No(aAQ-uV)Sd}vc? zO=$<_W%<(rx;aPn4(SbaBkhjrx39Ta!m0suMasz&-olILDRT%bu z3#5mGr+K~(^YR_1F(t}PF#1`xQ|y;_Vb;RY`rtzg@Z||*76forgnXwPgMn%l%6AXlMVL2o%BsNl-hS#*;A;LYZRvhI|lMInC zDc`{uKrU58q$nh`7{WrzI<*)($m_~cXy~S0JRr!P!UM!y{JoZY1$H&4us25Y0CCw$ zJay0v3!9jadhftBcq&toREd(~h2uhRh2q=ogz3FvmOhwaD7y?u$Y#;-Md;wY#p|j0 zRQgPsSUP9q++}U2jRwh6U_{t-qsJ*uJ6eewD2{xZ$o2Q~^OE)|V;j!hm2q{Q2NTXP zvfUtR<_&b~jejJDm&2sQ!&rqs!?dJiP|(SC77)$sz8|n{+NDwnmC7^j4k&XRf`Oll z3($!7gNnP2f|29!y|1FllTRrrAZYT+s;Ub)4x5vE-u{}y^akIja4ciL(j9Y+f`fAp zaBWgIl`0Fx(PbENwoX~ofqt*v(%s|pQHEt7$3fep-1%n8@QH)haA3j7QK*@T?wVc5 zHN9B8(V>Xzx8QH1!*A^?wUe1+T0&-p<35 zkSU^>(_j~sZl(Mp`*LK$QA;W{=QW$W7*++Z=(mrw&UH<)eMr4T7OmdL-dn|OI587G zBMQ_Fd=_M?5-oD1lueeKuKuG|m8L@opL$!pSgAuW8iw1(sRW{(>VTOgm}Sxjd{J<2 z^iqC`Dq_m%m~no~xcI!YyuG~VyF~T(e+8On>Lg05Uw2^+)V$#Fjr66ithNm0M!!QU zzn8Zxg<4EvVzt(REvmnxhDVu(e%I-;=dPc{dYY%-K9O^CTO{@RRQU*&$6dkAYF&2Q z=CJ?uop@AV-BR=Rn3tM*mcZ-54roXiBYwGRzbohpxYauJsvlx^-0sbSfB4+F_j|)r zexUp~R#NW^Q@h;}z4{Icqc4?va6q;{?MOptEjH&0sD#eLQL(ckq9Wa_=-y?`cgBh@ zbr{d?8ZV$!lA43IP}7d%bIPAZnG?z%N_O){jnqFg13DSetG`uBrgTV!F#{tQu`{*= zM`*GqYE~5$S@3!tb7N3MW=;F8<4cyqW0{1*O2hUXzmRlcvMgxXZaJM{=4ZQqN6(#j zw66z|3)@m8$1Q$iGN8DUp*~Y^J)}j0Z|Y{^K%2dP+ubiOXh7zPBP65A=pi%@7!0}n z`$&Kjf3HizI=wpE&O1kc2@CL%u3n1Y)w!LDj&J1+dI?%*vZ1ZBv%Ia&VE21GJ)W^U z%AD`AT4mh^Z4K7Ici_UX@tZ6bbK0ddw9bhC{cGTbk=}i4rsIdv8`1#}=#_h&y0&JL zMwIL7bX<$N(nT`i_TjBnuvU3WS-Oq!${)OK&zq~O>nX`~SQHDFDAm~|^ z$$a7{NvcjmqOKa1k8TG7I%Y?oFYCq1Xj_!ZElcwbf6(|^#qU6I&j7v0)*m(0WO*RX zl$g&yrfCQ>comd{6J#whHIeLLzaxC#B@PD;z7%p|qmSk^S|Ukm zqf_)<7rb6c5EfuB@SS*7IWgKWyj_fa>w8YqMm?FSS>|oHZu$hw&<)1#+n?o@2R=Vu zl?~d<+5v~T4`MqPf~+@;(@vYjeK7aLT7NrMBea`UY))HNPR~G#ndK@g;p1jNMPW?c z7!RLiyldvQ?w0PJ*4q4HM{VB94?B+Yr~t@yPObrh8&lXp4ciF(mqD$;XcUuDkD@cT zzI00yeFl18Sn_H_pwG?hWl}|Q`ljOS+ zA|Dz-NTd}>rrBV#mc!n+IK;d3rX4V2&cPZb_fK7s=Dh%6>#WT{UL7aoiy}EB2JF{` zpR3}g@qlb>fkVMjK~%vwv+I@o!dipt9r--~ryGGj1Gfd%zipESPE%Z%X=DD)QEPeQ zQC^_tT1UfF?#rMPXDdShBgabps2C$o!{iC~0Nt9UFgQWFKE-^r27|opdbsZxikPMX z$*Pthjkfk4)Z3`DbLsDZFC*Z zCpF)G(a|Kl(8`!=GHdvSc^WL8MY2QlVoxsy{s+3cKbjZ}h`*6&5s#N1_GcXho-!aG zb}6U1II*u5IcFF zVn{9huH3vbvv|ZK;4jr8{)qSOGHTYZ&NkC0(*w~SZ9^@fHvr>?z3lpj8po$)4Y%(e zzgP@_pE@dZrr2D1mE&o0Gdx}SGU(AVM)j&XHNFvk6jGwkgo|D2zTgf)va8mUDHWe% zz9J>r-zykaq_~#~7%Z^}nv^o@p8DXW70Vc^muAg;loKKeLwL$Yu@mM*Q?)9I-Xf%v z>-Ct7wbzq5t_RUi{7L}l15lQTgJ$k*b<)pm=a`Q&APsu*-=SPlbISC8dV zReU1fKE`?8jF_sJQe%tQML)Y&6NSAz5;ju5};j zy%6h)=zK9DZn%t46^yQM`m;FIbg2@1j-EJyO93KZz+<(H?1p@i;Wex-`8Dh?~oNGV|RK-aeX7kR3UA*nc3>((zshs`d+q zyb9J9w|cLCc>k4TVZ-!3mxjVOv&roVoGxtS8a?4~jM^_T4tgx|!5c?W2OOxMp9fqDv(#Ni@a!2c1(c9XO}`>gZOBN^Aqu9- zP^R=A&0CsPN}H{QDPpAJaf{9b?viG28uM8t9O|1C6sQF9C_w94A2dOT7~2~wAF%Qy zV#=kd5Fn)1xSb9+Rr-bR!bJ{$|2zJIsY9tDRBSgbXvq;CHNx=LG;3)k>jHA4;kn>3 z1Fxv>I2>7T8SYIBfpkf(XJUX(X2gE?DO-&pyDd}u4 zL1m9+S7keFGxX`NC_I?nnXakzsom7`lw{;z^Y4toTPE}YWezB`W#APWvFc-LW1bUA z-_8uHbu9Jw^-tH!7qJ>9fX7PHygS7cmmjRc)xA81tcHTHmOEck^tL=(5FaUjaP#sG ze+N@44t`V+Okb68S|dC>8P`xP{pD*$;y?*WDfkd2hYi<4G~8&fO~5MYFx_uIos&ad zqFFXqJXbnb5_R5)Xu~m{s$WLt8z-MqwY8`^oyd3blYYH?Tu8Zj8|VR(#GNc7{49PD zGa=0ZnE>YL)?aJTdG%Pu1x;X8zqp^%9l3vUffpykFebSNn|xCx_R?l|an5vPsNY6^ zD|RTP7Q?-v##SRPcPJt%db8eP6ma)VgQeKEI~4Z0@nz~%eN|mTE5*f}K^HTNX!&t^ zIZEvz{T$xF(FQrZ4@hImwQ|dNFfBVFYotQ--qf}c4em^T=NbshfG4<5%b#dg_7W?> zNiAG1ZT!xEEay?;8$O-SmgQmDu{5Q+pb9hu{&H;EGV>T?m}3}>4J-Lx5KUnR45_J47{Hgm^2g6>$wUAk{gakMykXEVun9&u9DtIFM zgx?6m(W$(heA1u4NJ%o#wvkLg>he+_Fnds^?~t=XBD~xyEV}_xJW~&A(37v6oip1x1vRpNCghY)EUT5(B%AfV*h1}dJN4jQ(#*ai zVSII5cCuGkOux2-Nf<1HPEd{!3}|HGv&iC+=V#ngA9u+sRTGrq9@0A^EWaDp}k(?Z~BW*F?(0> z8r%BD-{P3fA*#8}Da5nUsmU|mE7P;p>xXZ)XB#(;L5bFFv{1xy!B1ao!@SQixa&Qh z!&?*C<}@j%dZ)92LGi!+d{c^Da9Xxy^h+~CbHiGT4VAn|+J2>`*tWOLC4p?n<*vO9 zU2*Wdd#y@=ic{e)S4~s{%h&c6(Yrwn#LKZ{kq5f?Pk->1M5Onn|Cm+Tiwrm>@@bB^ zU`yr8%#_v6_`5z2e7~JR=c9V#AW%v5ryf$8h`EmZUu2zAkS08|uBUC==Cp0wwryMA zv~AnAZQHi(?rC?Q`S-cn=Tzk)c~h0ERBFA+%6g>FE{tcWg?h_lY3~X=;tX!Gy-+6c zlAlU|t2b5hQu57B&B?OCC!4^mxP@){S@rL0ZMXpnwOfY?$NF9W5{6tKT9JHI2yGM9)O7w%T8wCnnBB0>n#dVFxGkZ-qw3 zPwx?EvbX7L)w9ZVQ~MkB%RFtT|$@WDJio{4D#Y)6m7m*ZUA|+k9hzz2_&+T6!9Hb)} zdobnJCjY47<=B%lCV26wPx_9tI`hnwTG9hr_8{H=4E-t|BvWP66Tpq&Ek<7 z&168%oBQpPVn6CW+^GtGP7*><fCkz(Er`pjtia&sT zt>b>=iFVo0)61W)U|w4faAg{{N;d*T!rBl?o}>-^1v0Im7S%pqu$fm#4GFqmAwIA2 z#5UjMNl=f*H)Tb!v8ymoi}tZ3@wFYaNwmqDj_2-aqYV-INcZW92&O!b-?Btk&K6%D z>8n74YNS@)MC0Pc>n18?Mny*#yKyi37{^;5UbpJMte++!Q1Dnzgd^-V_Im=fOx;jD zsLJ~pi;IOW@^d+r)kj4>hW11vNf?YIg17?beE?&WV@cdOI1W_H+7w7R_H3X$5$H zF=+YYAMDqE8T?B=Y>uTGi|qt(#$Z4`M_X4bN;RnhEOhC^_I+H&bfA@>1huI zzA?oZp^i7wMLS4O!n^9(Z&{D>xmfn-)|uv6x2n=hR(tH7rk`bpEk8M)QXUNNnTJZu zO{$i}WAsJZ6(#Rtvo3(x{Cbl8bgMISaQZvhfYBGzsM{jjrQaf7r4+@bzD|xDn}Kr< zo%*B{Zn)=$MNkp1fQLfil*|ZbTpg9f8obkL0Xn|GX}@vuW(i?ck_VymB(j#gKHfa% zAu4|3pr+#ICX*!EI|T&Xynl>`YshADP?hUgCA5e&fS=nzOi_h>V;XEpkY z+wbO+dva7GjPvUN;#6oCCvx0wG37W1_)W-v2UZo=za6`7Dn5%GtugdIfDZLrX* zQEh@nH6r;!N?AmkEzjz+LTQ0qr)Dc#gH+)#_;+z6G6 z*DiP?rD72rauI;qjh|(mcH@y06BIG<`*)TPRRQAzUWlbM%Zz~Td<@2DI*MFiHtxbjE;A2%gzLyod&hTNd4_rr2(pA#kXOyjY?p}6Qp+#nrC472i$=I2On6K)3 zpi$t8zD6tRSDK0izMp1mq!dF|_rND`lkolKd8uVJx zrEL@_j><)iQ_Gq%=})-9vE_+S<AKa53F!r=glc{ zCx8LX-Poev1(zch*I`KP00!qPdyPA16Ybq^-oxnom4`9B8oAZLqm^iUtE#^h108vR z-+B?no8T4Km5BG>P1fBO8t=HS^NIT{pX$n&0)LMdA3>u;j0!Kap(HS?WfSW)hPCzP zBfu_To+VY*$&!vD{-%jry}Xu1{T-qdex&@{>XUV4O*GT`Iw2v`U$Cf|rkM0Fpk%p3 zFZxt5N(?8lWS;!8icPviEzmHIH~jiX&-3Tlb_L56iFL?=n1zhC;foIt)G`}c=0AZ< zL0~lqYGz00%S6KEO0FD;898u+xTs_d43Ohy=1d;kcd49%^dw0Es2pN$R%Tvw?nCFX&I~z zr0nG~%QU&%>xV&nZog;gdKZ1LQL2)Wz~W)tC8*3^b@91@6w>o6Orh*p!PP-|2b^D~ zd{mCs=yBOSeHD*q(}d$&d+*}K^0m58Ga?IT&GIieJ?4X;K)=+k%zxziUWJe5mV3jB zJ`n!W5AT_Tepc$pX_Eljq!DIcn0^I&i!MVAP?ab^8*vo#N5r;f%P`_(Ci5ci0F}#E zs+>k|Mk5r%Q>Y+ySK6UNgQ^Uh08jw}te?q`tD9HXEu+5zvcD}T+!!FL(AQb&ZL@=Q z>JTFb)liY>#kQ|vf>%PyrRTG*4mEJy@lCA~jUi19j~;ag;QK|a`WG4G-Oh=n6SAcd z5O%lNiCjjuZ%Y=!+ljjPoBcYA&8HVws}bh@Zicu}YPPgJL+G$v+zNZV0(dEU9hLf~ zzVeK2)1oejB~@z*nk(`uBwbaW3#A;&D^wp*D}fAEAF;1z!du{ z%YkRXG!JrSS49)2 z6W*KJWb0KM)we34O7LZE<(37l)T}twy0YF)E7GVr4<92K^na^E1E3LV9mqA(u`1AL z?2?f^gZnLHVj^P^NGlbyyoCEql0sa{*b*cuv&6Kh&$AuqcT?l;N{nmW=8#=Pk0Ya2&* zD`v^d%x@81-}&W_kgWxlQyo_e6!y8_CeRnwLQcJOha15&r0A|R_^DW2gAn*0ZhLux zAfelO4f)Lp@ZMdzhO=mwLP;rnT%?6A`y(spTa6HDV23%H0K-TV^`Q-;P|8uNH?f>O zJ1nUrvUg{2!KCTsvN=mpSsB<6%p}k%!pz@0-)pD$KO;KJj6l&b-W}(P~=!osh}fc)9Yh#B`($Gtv0!+_!$n5s%E}-SR6PPawpSQA+*2t zo$zjt(sqTe1FQg1+-&<&&6veCsa`o`=1ILn-$whp1?FH@PLS|u)hw_vcsA8dwWT;i za1+lNV#|zPN*u*pC7dK#NV8UOn@P9xFT<-z_EtgX6Q&13{}yOw7#R^UIYB!C4sPVC zA&(h3=W&qLz=E0~=~v4XSC3|o>esOD%BGmgK6K>+%%Z+wruZV`-{~KBe$d-*e>eap@T>0%S1~ezch_9w z8_6sK&Yyq+1>qTtYkI?<`1HeYEIGdD-I3OJ8ae zsE?3;(dp}bxKWvQ3#f2031E`QV6@RF2is)EI}5hKI79(S$&E1vNNknURq zmN?ob(3iCu2O9ul9J2@ZY&Wg?w{eJEGPkT6IH{My*UwRna6fLZI+Fffe?rZB z{LSijk$MH?=||z6NW6aMKs8GUSjQs$9cV)8)c`jX7umXS288;?qNIz;>8Gm2`y9dGr!D&yZlcUK*uLtck87W)E{dA3J(qO8rn>R&>Xm zKs};TB;OBl(}(cU1cu#M@`vn_^-A{0z0(+)@O@wEI9YyWojorBWL$C_FmKPG^EeUj zTNv6MJx(sSI27-G`Z1lNmwy^E^KrE~%O?r-WrVB7NVSPaKv=7yrt^8fsFskt15l9i zN!c`FOL4{Pa(v5Q{=MOTebVrbOnYx^N2UF_CoX94({---{^t(!{T87}g?;Z?AiLtW zs#8?GT%Ci);Is<8F5PGvFl1I>W^}3o-7I8mj#CYxolR?TSP{>%&Y?}Re|aA;L+4^( zxa% zm#-VAguLZxg=jRj7k2-{U#+WagR73#)5-02)x7F>J=AF@>?}+qiQ{csnmNQq?Rde_ zU(^!VElEY()Y$0mE}oM+Jyq4J9kjttS=-0lH4hDShG1156rm7@*mXy;gNW=a@RY9v z21X>JJj3|{nEGCO%U96k{+RAQ&2heQpW%I(*?5Qu4S_atJgYQvkSL1If7&x(N4Do*EK$G!W;wvc{k^f-|nkLCD+M z1b9u7koe?o7&^Lx8%vdxNkeIGcCYD|bF_8x70vzuFmEruAtHnt!$7^W>Kwd>TfZX8 zMZQQJjCr8*@8I$$NOZY1rg8j@9JcuxJEKPtw*w}+?R_px4nIFX`f_<7@HfAdHL&DS z^l-iM&^N-Zw6^mA7#a{a_SPZLe|el|{$cynJzOv}fR4EoGqWfHuuzSBMBf+1OYN85 z9?A;>lD&BE1B>hPztYp=4~6ivcwd+LQThHTUh`_@oi@}9zhJ-vlZ*&iQL$@!um$5B z*BAGbZj+%%cHv0VgcS>y!hCY4fUtXjWzP}xkucw)kWt9#AgqY(22vcm*GyaJA>Zd> z956o&^dNZ&nR(UdzVB1g^oeTxp~opah(_1}fc@R|rDDxU8|~dKa#{`T)fnG$cJp!Z zL8dcqZ}dg{QQrgK)erIhMtgXTcQo+am4L>tjGY(vB?(7i|4H}QJ9(VU)$#jWpUllSX((K#Y8R0`Btw8tEQkj$D>EKfH%TjO_c&_~;1oKB11}&%yQj z%=k!e;k*0n9@tcOwxpScHeue4Py@bmIWzdiHeumczCj=P-TWVr#==pir;xXUZ6@rP z!ZZz&K@fSq9M+6%B6J@d`+_mGBV0Y$m#AVGn=K0cm z(2j((@qh5_8y*~?jf{=EL&fg#*Uo&0)Dyv*0^~fBp1KAwpDo@T4?gim#@=!v2?zmv z22tOi(RYFt{BfBkHjwFy_t^q(TfoL~v$7~Tq;Iq%lz{j<-!zc+I7YycK#kO^@zE@} z@ss%IJHt5tEaq{q&@0NnS$pOX+%ez4JK-_;8`hCN`5W(`Qpwp`%)%UYBm|dx{<+~F zfz>YXjuX}`GXDP>TIxOro#;HWYrcqR+CYFim0pm#;u2&nl)lGZgoadvX&cP1!{s2i zOj6P&4hBAiGoEHZ=1*x!dW*S|jbNrnN~^=D6V zwsH2e8kA)~9McNXtz9b(_PNcIMNy8VyW8gVRKna3 zi}(ncJp;SzmXO}K+$KWm4c9u(bp`u=&6}o8p$Ikrd&s4of<3tn{+h8dZBxxV1Z~1r zlJkzm5l3l96gAq4`{Jxq@3t+aWTTSmh~{#MWcyM{MCKkgdR4DbFVc%Uy`(xdyqc>z zLCqVz-WGSa$S*Msat*wOXxd2R&^Xrk+I4~`)ym>Z+fQCs_bPm&P=#}H&MTRASQWkU zh(`xd%mL38_w`3DKu-|C%`)B2S~GC#rU{Vi#JksgtMqNtdidG9;)|C_tu8#wTBBUq zwDP--Lc%e9MA|Xws=D75#73Rc+jxb6U)ZQ?WaGgI?8v$X!qxt?<@p7@I)N8 zMa=1 zu2Vo=)lKJU!n5L235i#z`OH*Y`Lk2CX3bessKF@9wVYUApzsVdZ5l zPlK9k(V-r*LnZT2CO37kW4h?o={-euTCl1rZrs`SJ~`C1-E0h|TUt}z;xd=qn(aK0 zoi22%vp{f~yjxf+dB0m?;ijJ0hVBj^^^IG0EfI_={MPd3+o-*{a%=ap{(i2gaQ1Vl z@Ue&AwiL_$)F^Jhjn?s*8T^vHw^W!F%cZ4_sA&BS-cQ%Vo#E)mm+d#9qwao&yMnq+ z(cUS}zf!tdbnqy4TZ4PKi6cI(cIsjiKhu555tG&)c{vgK&@%X-2h(jHsTT`C%}pa& z`)v%@HklQ;V(H&`)I}M_T*oZcHq*b&!sCp($NKw@^CO~dD4}tV8-f>X#C&M*^_c69 zi&n1x5voVQJ9>u9wT>NxU-o@`@q4H9fVRS?b&~=yyL5To<}`Q*%(kZGY>`~mqC2$a zQFHQCnWsj+I}v=zSQ)fsZ(|+6&QN)G4lNH$FmsEQFlw)t?QboD25ihK>^+&&ox|-)FZ!4Urmg*+!$5XP?r=RMK)+CJ59fQLS`H_5G;N5McM2ox{gjv zKAM^Ah+2RrkJIj28c0*B^J22M)-iCyr6ziM&Nv>G=vIs7Z>i)%yQu&?*I$T_3lj3k zgi*i+J9Xnt(Kb}=rE*|w7UR(+(%D=({PIky_cLBqBaltWZh(V&I+AxbU&mPUDEugYlBOuim3+oxJ@D#V6WpSwtPWHA~A#bMY1H9u%6 zEAJXpBeVsw0IlvKmHGtWp`|f&Q!1Dp31Pt3VKWRPMhE+WZINP7!;Jz-^aOaWLXfnm z+XW%XvPNmeT$lj|q7Z+{UM6w`MqhjJo;@m9fGxzqzobEquK0^ z3Z;-Fd;SY=LA5X2T$|8tkZC&0#Op zV%{H?kPxkq%$j-O1(I#6G1go4%3wMNnHWL5S$VJo0_GSyKn1G|nWTu{Uu~^6ZEl00 zQaP5fP}G0dfVYCz7)$FNjsD`5AYP1d4t2XG>i#whpUx&gU|$` z5>1EGG!*6wY}15G8u*-^q%hE!4m!G*ZhJK_SvrJOS{Wi$L9`3Lhe|>dbW{2B6{C;o z(OV%Agj~oA4-CzzZzYn4z4c^>=O%lmfyoVazFShji|MR#lO{JvBdC`_bfo%n*41^O zSkii+*_Q?2;HaaN!CFZ+RkyLeog%9{Q;a##Xw+$89EsxwO0J=@fe+KJfa=V0vRNI0 z@<&Rre(!fHQ_gHi!~P;ak|{h|GlaYTLnqq`a}M_{Ty{ZQuAGB)!7AcYrN)&wnBm@? zFT@10yrASi$_%+?j|^|^H%KL1bF)@a9=VlsUWf}2Q4-vybcZ(fj@d&`HvWAvgh^r6 zu$ru0NtU_^(xz2MTxTp6N$FsEnU$3?dJ1EXpJaY=Qfdy<*cce7PA7PHwWX8)Yn2%x zH{M(>SBs-LPI9%NtcQbn(T45O4%cJSy>m4v;S{7XT&E8iv{YcRL_Ywn173A96q!Fb zlBEtnyP2d-ULB42x9Tmib)Hu_QpbEGnrBg!+3vL{+?6;s`seshiBq2HwlCz)G(#-u z_M_uCm+uqe97)>xB1*UzG05iUCT}$w7n@tF&R%S0$A*%=^cSfs$uqf*en&B@cWm?M zuk%shTrV8nZjAFb41VeZ5XIVmHEupyULm5i{ctuqKWY}jZc=9FKH#T|T2Gk(p!0cw zh4QiFt&csUAcuALmWRqC4UQXW>?u*=QPLwqvttLe?Oj2);hYw?w#x*|wl5nJTO>PD zyuZY&^;Ueo@1FR@<47)3-C=;ZK$w|W5_tkR0a&+JQJN64A8S^}9(QIG^Zti{3kw50 z+f~2({3{n|BHC33Y$1D%uHaz0+O*9ej4MOKRnboSJNdJ-bzg5NOJR8G_LimUr1alz z8qaxd>_&VBAvf;hmRVC7Ugc)HJHzG}eUVLFOf4v`wNb^qGD z1pKa}eyTiKUa!sYPx+Z~R?-E(U)HXY^Kr!-G3+il`$IX7I1E?NMEWFh7DP#fWXf3( zMIDLE+jy8%UXefPS~yzGZ%VmABHy<$2LUQ#B7e0Vb^YN}p-1BL#S5~b$A z0^z610Dy5ChXa>vf!I?80l*ZE{r8MOKpg+|$s4gA9Wa47|3^=)hXMKqW@AXLhXo=A zW@G)o2#BkHO8~U(H^tEXZfny zVUo6SBVi~E)ldgh7NFXks}G?B0Fg#{Q~c$~HW7NeMwTpJuSay-Ag^%0_i|mo?A1-^ zs={@9%O-Js8xG7bJK1%5*^OFmmX9q|Mhlok5B{ynkLta2w40VNIoS`(j+brVb67;j zl}{=fW566q=eBZ)p07Y-tYD(1&PO^nk4?#)imPV<5jhhG&u;3QK2r z-(r(hjUSNmbC*@LhVowD>F4eyDyT7O5`m=k8NhL{)_!M;?Spz}%O;hxLFk9Nu&wDt zFKfD6q;dChPr8N5&$7)Ttg^31dS93B8+N~%ZP4J z1^6YflgI`XpC&=d5*VFjDW9F_e7l8$$eaBm*T=N_Mvt#nlvKRJZO7&bIfh8>g(@XwqLvdU7>5bN>@5 zDZuE^4!3kk3o7To1BAmq8Ez-!K+iMW70@qN-BI);ua@{RS$r^qj(B~$0u0-kXvZ#> z9{55B;@&clLHFWrPN%Cqpf+ZJq%h18_v5PZiCjAF3l^*jip`S1T>sle6bi_~i3Vux zl3{(*$q?!LLiPI>pRVLM2vOf}mtjf-R5f%!+C|=Tv_T1QfNW&7+u^1QoDPz1I>2Jr z2bR5F{5q3br!?}?wjqWV%-;X#M-V%JRYPgNamx6lOsNazl6tEsk!*seQzX4MwQT3^ zg-Q{czg@)j6_Y3k*t#sF=a5K53RhwV>=Cg53T}wx?9aDv$gIB8(19}aS!xhNpY#Vu zP)JXZSnh(Q#oeFZn7@u%g$hMCmI0MMc(SbwqPfus_tCUft>4)K1K<99Y<9GB93kBS z`c2rqZ2fDGrVUkt$gSBczvnj!n%EDi|L*np0<1f}fJw1QJgXNeKpZ8DQtq4DfPLoCC!2@|3lY z$6FuZz;~FUCu8sL7q3a8P-abWf4KJPrU4Wa;}l9WeKY}%f1>ep=;A@*;6NFT6taSe zftqy}gyD69fT8CU%#Xr|oG77w{f33#gC4_>fRjg-(+IEw?#pLL!-h&N2Xa^=v!iq7 ziN;kRuiyK%*eg173>NO9n+kBlAlkqx#WS&J9qC|Qsje^8NuYyvK7Au$@cp|d@Z8D< zZvOMJr^4^+S62;`;V;|iP8%QS4UDe>`00MQxF2pdIY`-?9PHxjirQM21KQriSzFHo z*Z9@!Ze6|$8u#|PvFjdwt(Ux5H^m>os#8ToGqBB!Vz)u5k^~U89dq2F*`>5y zvf=BOXV5*t+wd9ILh>r72vI5MzP)l8i_U7StQ+I$dx*>J#3%CmXT1Pv65wp$B1|V# zUnzd8dVYWO@?Q)7wqgdXLg$F!5lmLC(O!k$=jZ*o*F`uxkOOccX5&HD8^d9ZNgm>uLu6MGBV$B1V2hKM!FnmyT!`Y8LUff) zukkdp*EW`=(Kk;l47=fMoQ1->Ale=u)zA!{?PET+VZwMJQ56>|V1Cc3+;ikM@NTHh z6{Ve2lFhF5LpQ)sq(2$4x7UnS?CeEE9TH`AcnJCR>Rs||;sF}RQqo{9yE6^n2qRex zM}6Bt+VjP3th3bT8~n;rT*^nphl1P^B02SrI`Tu`>*|o;_WKR{3grHx-b7ZBdpTQa zFDq2vT@ETh-E*8dx&Fk?QSHSQ0i$rscF~*VUwDD-7 zT~sx>QWnM(Bm$tq+%L1#dH9R1dv` zQT%A4B`z$IqqmckI1eR}&{UhK9bk(Y7UIrJx-=5Mbw zh6gubsc2KDILWIa(Z*ONWd`0E1P2Z|IaP^Iz}aaYR2#FcvMKh5c1Ahpm9~6R_o5GzoybI+trUVzSW+ zN-3M_e?Vq9Y`as-P=Q1e=}Gay7}yAzm{Q@Zox=?6BPK?cW&r9eRzbJ zz~gUjr*x=%kl%wi1N5C=a?^+ROMkk*?oVnh=mvuM0iGZCm4iRq%i{vCwmv^xUl|0S zy9m2@2ci4`?~fC1w^zV5Jv)?n9zx3HYrpK1b=tZE?O7+olVi_I84dBGWk6S4^esESaHpXQw5Gojqo_jOX+RAV@lh zthtmW0RnYAY6hQpgZH(?lC%!rv8}K|{|;^{G&=8P`Bb%yK|}&5sDyu%I}hMHPie3+jYpE<GyxPgM(h^pgT7`d z@ozUCAj~|!S~~l!>?V1liw1uZBA-LV&HyU4OB~nQ;jT+aJF@*@DHx?${vfTYxCY`7 zL>Ski6)7L%Fg1WK4F$$VM?u~m-;$oREZGbLmj;;cLYCE$m2zfOg~~sG3zrs4l5BfWK|b+!-i1L<0R@lfW=gSDD*pX# z#TUTrmaq~W^5eA?NT*DQXyymvY9-fL_HLVxbm(0d6_UQ!(pR?e)}w z-M5L>K-}M2Iaq{B@tHbAg>b$%>Kbjj?LAjg(yd zuow4h`l3ZL>Lf`&xqdUtC8?Gio=OvCjczlvTkyvF3)`9URFaN24i7!2P9!SV|Zi2%k zCklubrxkiud0rZY63+b)>>|+r2wiHk{1Hey&kDQm+%3Jbhv&jG-TJgE{35@nk$Itm zFriz*Sky=gqyM)#&2PrxVCum~t0_QlhW>~Yodw-5v^4ul%TCviT>A~Z)6$xK4A~gN zRrQGu3(Nh$iqQtcMlj`iaH0zrrF8`Pu);SFt7N-B&x+Pv_(h1il&A(Y%S%m0HmPIW zF{2esnw5(SU@mBgjzZC-BS8lxhL+t?o~F>?R}$m0V@Y5!?MPdELs|w=D0zT!bcjr6 zImWR2`eh|5mUR?HEOx5hzPUh7SE&TJ!+WBFL{an=rCboJ#0zX+8Th^944Y90&`Sj^ z7@9h#(+b9FSN&a^l6IDoQk)Sskb|HC?{1C8Oc;^px!xw7Bfs_4bXe;9sgK*_YX%~Qk7kb(wc%`7;sm)dNtp4>o2*!cQ;qPz zt-=;O|9Y-TC@1TCuSHLlM?Ff&&J3(&qa`061SOlK| z|KKAxJ45b~v6OTsvkzcSGY#kwl#Ew{TIkwNa#KX5T$0k~pW%ES2{Mb-Ww1@8hKop z1)5dz5mrN0S#r0rDYPe{q6*sSN*MdLQ(+cX5gvhBov`Ng!_ae2e3*Cl1~tSX;jyei zv}jk|Ieq*A8j0s%Hx);p187xK#D?BRQhls7U}3w8s3l8 z92eScpoGLI_LqT=P6k^csi6b7cC-pO&&=rE0M|1qvcd$I_hQEVD&hAlVu zAbp07Ez0qCGn;Y6MUah(9eIMoIbmsXoS1Jh*NShXuLan+iDlM~&5vA^h*D;5VMIY) zBpP93imt)9Z&#b9s6Vh(8F(48Q*_KU$8Fq3S*wJ)N2N8dJSDy3Y60^LNdF$Xh+u9& z-ugqJXfWuP@8O;!V0G$(P@zD3Di;rDA^0VcRN>f2|4RDBAB@0eDy~L-Xxgp)P=@o= zK#wzm*bWG)lYv=r6Gy+_g3PYt^#BQD%;IIxX!t!OU~N+aZ@(E)R)c17f7clx;10uv zYtyK2P=o^6TqqPaK9#UdPYxe+e#8*faqc_hk{HQz1ZRac&PKAvgaN6idBknrUCjc7 z9NBmD{x=(bS=aw?S1Aa604rJ5N?Zg#uK#nd>klBW;^-hfZ$eyOY*WZLMb4)ze6WV% zE+;`jwfz?qGJ9U2i3OhAy;>~pru%QDf7KdN0tZ2R4P2}F;-<7;q<^hvJ&nsfyAKR4 z3i=ZC)ZJtG>1$lfueU)D%eF=!;cAp%;|3XMsAInovU`P9W$}QVlVbJa(;164bak@V zEVu&}v`jc=n}wL0(22CXPVg5+Amab((=SwW_t1hr`?KLgIO|lJKNWj=@)>btw;U#J z2~t`#!HWM{MT4!@Z?r<0*NH&X?#Y+j`1F)8|(( zKyQQ45BbTAk)~spul^T>Z7hGRMSOQgKjz-%xPBc({J^ON^o_d5l8y81?hQ%YS-X(O%&G*ME0;)J352J)_rE?o5>8I2X-EEP!S*?w+F5Z;)LkfVU zsm_t|9GXCZo?1TRZ1g;;L7&7s>^<22%a50A}YQ{y<=(s)q_lK>Wxf0Cm$!?xb{W z6AZH~7P{inZemrb;KEh>Ms0H>R!b8W3IGiu7al~~Y|&+pQJ~m0{Il!FBn8g{>ER!$ zFpC=AB{!!z0h;_(#-d}4J`G!lCw`n6juH}pwFxVikZa=@5%1=70WX0n0SO4@1jl3x zOQakg(>B{!tohIw2}Cfl|QzLpP(cw-IN`Vrx9YtAKEa!1MAmES94o!TYzu95Y=Wl;9&?% zdf~!8Rn0t=^F3Bkt#%js@&E+o0p;Xq#C4@SHz0>wFqY{GB_P$hR)jl-a9mug76ejl zje!bN?)EN7!Z^Saclt4ao$fekF^s`)nuCI%6qhfPw+eb|h zAK+&7vF09xOA-(!GzwsVLw3%?=_|nat;;XQ3K1M4Gwp&{<-!baoLtZyDYY_Na68vX z`BB$0z;;f!soe%@A70%OxuRsHS06!jhMpt7BUSQ>WqcQH3L1|$H9H2WsACtq&KcQk zNO_qXWDS0N6w_%;u>{~{$JmUl%?kP8doV$V^SKfvF0uA(;Y=J?V&}zPJd`54{$;ki zQ~6S(ww7hd;=*tezX!9g;_SRJ4=M>2JBmW`5Sj>SPbdfuvE$S}6Z;JxLUWeZVfSp5 z2a3?;k-8o%u}`&nsR{v(emMsaatXWeT!a!6L57O3St$!x^8iS?=HMJ&6yG<^k36P` zhEE+7hb1g~p-pimp0R+6bWM{^rd{*i1d6V5W5;;t1Gi~`FPbtyl9Ie>0l@6Nu+J!g zMg+mYZ_NRZXe}=bZU@1!4jTJUZk8?(M$C{NvDZYPWuELUkaC-U3)tV97Y@YRdx2PO zw-M{Ov;KOd^aHq3>$#w-9Q$m6&D2m$2=z#o1=souF05PjfF)}$a~ zM_Bp`cLf$n5{Ce9Ybt2QI<`3%Nx%3@&*8o2++-%Ij~d`tLSrJ8weC#vXQkep`uuMZ zl{5^soau^Kw;=~Yd6Oq6Ay=)|(wu}%~&>=83EM)W;lufQiOn^JwDXFeN`$^l_H%snq< zI{EaU#Yq5b2?{YY@>mmoXLUME6iey?XnMInctZ8e9ze&Gb>k75O~N{4Rt#?b`fex;D2^%r0u(xgmrz=tUNz$ zT(&6FMj`buDa+b|x%<7`GWLhPKl2*W>ZQCN#;?XHaIe$`gF;c@)k1(rNMcfVeNvJA%8x$?2xRm6m zh|fFhNClaUNyu=}DD-bta!Hq`3))y&L6EK!?{^gbg6*WI4WFz;)(`NHxs=`P6@8<6K<$+id$$V>5=^ z`mLlj4_|-Zo`$g`O`Vz+7syRsOeJ7tA>C-#D2DP*wP_bi@!`Fc?JPZN`z+1g(~Mm_ z+7zlrTIc7pX;vasOR*KvtUC=8$#zE6_R#9ccbwMP(i)2TF(7u^$*n;)(+|LOnP|+f ze33>UeM-kzt>j;}XWA8Tn`AQ`Q>)rYRrJub&!XH*nrPK_TYP*hY^c{r=BnTj|aw{u^_xDpZ})S+41|;`T``sM^WFE$^K3rPYv32z_-EF?Y zj(|>)j}Y2|Iz!dPWsf>H5+#B*E^%SSJ5*xJ1_GBznIB!4{~kJt?Q6qi)B&} zP?;DziVvn2*|H!Vv1}JQWGAF!R6s`)6$hEcfK+lhS6SS%WJ?VUl-I7~>vM)~{c?rn zp9r|!FLc~w7qqNaF699DA=8X^>7MrYuxN6l#hM&Ka>-@N*xpSdWx~$uB2!kHpZFB% zWEWkQ!KQo1d#x&!is)4VPj1%nWC(a?WS0Ac4-U~)IS)ReqQpbtKVO8>cMpU&4J_>W}Md6%gjN81IurV!;7#lOEImBL7hs9 z>ABxXX-p%tSRDp5J0(W(Np>OBtVN!);6x>adt_MG&N@F|+K35jbP5fRkH|#`9T!cP zb%+DA850Gtqe|xvKp}YP)uXVVrXmwEINQ?7JI|r`BeVq;tANC_cT-w;%=}?NCR|8g zQA)P=-q=6K^KF7Xl+KdQ)V(HRR)4A8WOSb7@Y-yF{fE#TkHV>NrBIJCV3EK^m(xIY z_n&rt&2l6ji*qd;kN?P=M$+R#pJ8qdnb;mr?vAn0%EYch(X02#Wyi4_BS7&WW+jwl zFI$tkq>;b6*ooRJubIm1B&~T2UeYc6zBNwLO{)ElAf1rzl$#)gG?`JTW@?h51>j$j zu#CnxmgoUG@M~DTpg31S#;+ahOq)&{9BD@yiK&XLe8VpnRbGS`6_biChlXNymLtQL zekd_b9BJSG4{2{5R7dbEj6#At1b2eFySqzpC%C)oBEdblySux)2e%O1-GjfA-@RYe zy;a|e;7BYz(;2r_EyELG!|Yv7<@5wu26?wggcOjzR-HUG=1fDyXe(CKZHZkStC0GXK zaCyDXPiry7!{pR(wsd_4I08=VO%7XT(ji4Fl`<{{UBSE+YZK4AjhG^Iv|sKcK58-S z=+>M%ve#ad1iD%c&FoR+xY5BsRGyMAJ8JjR~*P8hvPgw8OzP?m%Y7&=(s z$v0|O-Jz^1s*Efoe-aOfQvSj}&Kg?pkYnF@&6j5a7>wKd>(D|uul&9^$lOu7r z4V&o5&04?8;SPncF?=e7l94A^`79~3vz*WgH%6uQooL{GpsLv5|bvL3RDO_z<%q(CH%>> z-h$fGSTs_Oqq^w8hIP^@FND>Y!=lMqcA9QOUrWBZH#iX+Ql8_W#ir4Z-^{*wRlMWc zPH?w5-F9xul)NJgM#p)Te^q;N(&Te<2RO{d0he=&t*(kUkmw`dUD?eYg0G=ltD`{|@QpSj!kxglnU zEzHGdXPFEnYV+^v6+$>v!qi|H8JwD= zLVIrYoqsWpN)B9?0qwmootVmq-?t3XB5nyxhN^F!-c&eVN7>_tGTGXxB--EfWG(KL zIo4$tl#Movi^S%xIhh2HJaaK866+C3@H-)Y^<@NXu(_T0I-yzD2BQ{08oFx{8zQpN zDN_{Vh@vL}@{pXbolMba$i$Bl!^^N=KH9EAS%giiKucHHu2*)7F_sa>IQVKo!CpJ% zz3>?&c_dpPjt;M=es3)>fCD`ymAMU{5J8joFe2O{i^{)%GEUj&Vs`189Kv%>x zangufMfdncMQlYH%yw|x`v9;C=N#z88>N&NA+Z8 z>6U^C6NWfci*yuOaCg|(n!l96ISp*Qax9o~2c~G&Gp6)hc@3HdFTLn}6?>@1+}N#V zi#V0d#MDrxXdsa}a8n0=$sugW>U^4*pwM45hI$FS_7N~0|fOI~6DWdT1f zIcWc;QO89YO-S}845>O+4)r~CIbu7r2?o}+d#t?xPymICe5Y5SwEZsSD%iy zJrY;n;^2NsGM4sLXLQHqv%a{j1Wu^@+A)HSvE67e?sSx;L|Oq2&RvV5x)83z&!5G! z2!+R0lZw`~S-Az6`b@GI@LxxeXL84&a@`JD5`e8T%0C7 zrzfLHNsC>Tq+^5~<6vQnO=VqiPE-OK9Rs*=-jn+!I| zt_9?Rq9cYjOIfh8^?7|z`F_N%U0j8Dt;dfQJkQlXH+KsJ&+4_#7%^lw-)Bx-HC@>( zZla4#Jy>>iQvaZRreWGso!g{1VDgs8T4eoRO?Uq5HHxaX&1qH_kI^w0xIKW8cH`Vb zoT_{_#rk2zH@6BIKNOIXa4>q-;qWBNs-WKFJQC#jh&|TSk$Z?afKm{j6%2+fvJBgz zRikSQiG22Z*Y7lZKE8QbN$vuP7XSx7chC~PIILW&Aq;sluQGy1h}Jh zAEX{r?F_;^SGGd89!T`0qa z+)ST039Iv95jiFCfa`kW0ey<6cgpH1GD9wB^s{r@wo8=O;(H>G;zpe>Iu#c&1c->t zM+ak!=%Z1YCPRD7ROGxcyg@+oP>-88&3E1141{#Ghk(M@debf*dL5q}$e^EYT>G9z zGVc7p<3^79--y7+R026flg5l=SB=x!H7@cdJN>nny0#%6fh04nG#UnFWu!FNjP}$S z{L`+fzCS_a*?8e%c;SsC+-Wdg*DnXq40rOEJbGqZf7-?xefyeHY}31P({}Y6N+MC> zk06%Lo=iN7%)LfTE8TLBdkIM{VmOi0SKA95g$4|Ls%@WLIDKX`3w5o2XB)q^EU;6= zPWIiy_Cd2l0I|H&_CLW2i}M($NkGpI}ONV6^cZD_=O9Z4dtB zxpuUskuL{}0c>Lx;&yA0rb@x0@rz~y6Q;KL(wee#Qx-TTrYqg7a&4z2_A5v{J`(sa z#%iGh<`v@d$k}|8xbBD^kRJ2fV4Pkl$aUvne2SN#0nXx#FXj~Jo9YL08?A;r!&P_J zY(9IDsgzF~Gf4%U*`G`-B$l+~PE*OHtFaq&jZZ79cNA{zDwQ#*yTUxH>*W9VaatwI zpIaxKu8Qr^K;PwEmbpc(8c*{mhPsT@3eesyn4deCCoO9HwiIyTFga&7Pl9frWt}{< zS)D)31q3R+$`=@%IXtU>ryJ_2pOsClZBO%5RJ6|foK-5nOllpTyBiNNr8Jn%fPfn= zs#LqDHH81u9+HNcQ*JF^y31@y2 zp-b|SkQ4QjG4(PY6L2NDo*d2g$oNf6$Go-T@61Bzz?nkRCc@)eIG6D=d{C+W&4&c2 z`!nL=Qn*axQIZ}xUU)G*d2&ZGv#q=qbi}wAg!Sho@l84u`#c?orM)-!UXK13S^}gF zTlko+SJw0p;}0xz7Cl79B54T5G+3N(Xlm4H;nPLS$FgZC%*A&eVa#}X-anXAVPUz^ zkXb5M zC$l#Jd=d7m1!RJd!ZZGHlYF@0iL4g)DO@O8NE zTNebgfPO6YwjGO^J>=()Q)@`L58B<3LOu$WW7l@{9u%P;RDQjCak@kOk#hVn#O2m# z;8JEHebHj3QkeOmKF`_|Vti$CN7D;&P86Gf+4tCVej*9Y;+0fk9LcW$+@J|mYK&ms z6^$pgJKA011!m8^uvHa~a>f=wHmmJVk?>_Mn9l$-dl^fS+!*Cp7BamugV4YHZovXx zSL*~1y?s8Lq&dWdlWnt}p}0_HJ+bGOCS%qe@7;>94o?ev<`q?K6ZIQPtEL9OvHMBS zBMFd*x^Qbc7@P~f3x&OybJ>JHFO91*!o0c?5cy0QtQxvqoJnlngxdmOw6{nQ24mHZ zoEh=H6mQL1+2T{u>1a|DX`cewA#`(H)gCLaH!x)m^%+I_0)eX%%)>%<$^B;Y^wh zTZgfPTe+BA5qHSgxi!fhbWDUV4Kv9wYnOHzgVuya*qwydwoK;7oy6jl@Fc ziz9i|n*xK>nV4L})Clj~M7GA5GeaX|t4=pExSpQ~23`a8BuIf+Vt0lW$uJ^q@ll*7 zo~20xUdM&G7)hK^3?`d1|@Qgz>5hZ&OhO~K6Zs>igVp> zdQGeE)A?hXwmG`cSd7Oic14V+rfylJ{MzHt&H zxCj(J`=~1Wq=5kjNH!+(@w;p8)pi6(v_rgx%#4;0c}*2v&K3=p^Dz2dCeiJ)+2k-o2T*XAPTa6IM(;ISP(5k=-voXxcnwPLbMPhJtf#bMxno?Vhq9F9|OA z-dfD_a;lN(Bs!=Ya2^$&J%bC6%>p&x%FUhJ>a6mlV|F~rz*lrij>E-!Y zW$$ojw(QGKqXR~Jh=;Uu@#m+{-kD&5L1;`{lv|)=xE6V1)U=$eP?_aUE%0(&@#Pxz~ z{1qurF7WwDXz)!*{dsVTq{-pqAZAeu)kVr@D^9_216<;U>a85C#iX?ualbD_rsF|R zQQ8JsKqxW(8xLwsZxXaW4{RO?IGf}j+yLwoSO2E`QcD!XU&mtS(Lo0V_1^%tPbCSc zR*n9UW2o8cBFDchX<|CrKQS-ta_S`jv@+=tpB)jIZ0zybauPBA0g);NK}MKmT}Bm= z38i~3_;@@7u|Gwidx+=jgvxWq`v)V{IZINmmBwH@$N*vsVPCyI9fxw(gtYoTXeU_& zZ3w(<1(dBrlP590-ai1|!;NNg+#ecGAFl@Y$|mFQ+Ye7Uia7$CmUE< zp2*poFrw4DbUpzIPR;hgK`OA^sj|&#h3i;(7a~Y*yhb!=0;_m=hXs#adVAmJ*|>MU zvk6==q<^U~-7c!GojU@R`Ws-X+^G$SNjbXN!l%bx*3>FfLGjl@h0Zl(LyP=%so6%$ zAO@k?)(YP0i;ekP*TmS*%JJ)}3B%20x0+2Qm$GA5JM38lC@XCLD7U_Zy6gB1FC=kJ^R*aRg2zSY*|l8l{sADwr*0>k)t+C z4X#o|)sSN1F&86~oj@`prX?+toMWf~ zt9gy9-UQ@qs0PYCosv2!_eIv;Wv4<-oAzgN*9KHzXyf{FWCGvr=c1Nx#6T4d#6=CO z_a(a;XRxLaQ zj1%^rz1!hk%SWDhO|KKi)v*KC=+T4puvb74vx#m?xTRGiIICIIN`KDh;Fzvck ztO%L_xiy80ww~n0kC>>;u&8S&pJxe&N7^e#sM1>W@jneYsQ170$aqpUSU%^g%-AYv zNw}_HuuT|M<~X{{D(qIOSbDQp$JjDsn_WePwf7vz2~^wSW2AdRB2cSUeNYM^%=_I>^$ zFsedIv?m*|Sv{G2)Hb01LBG0b;okuI~C)Ck$|sL_daV()9iNrVY#~ zMO1$e-XO4ePmV7WE7zJmj5R;VgU`edLq*)yOkhS&vyv+X&}Z8Y7p&b!8K;lZxr%7`PqGJd;pq%c@u=3**fKH^nGxwS3tq zg(&wf`2EX`a+pcUttg*(2L979dmFmeo9g6JaJjr;Syp(7HZSY)7Ru2~iicJeNlB)J z(1y08@uZgHG?gH+gr0pP19lE@fDhrYjy<5Rg_+kC8J}eO+_)*yG%@y@;N6OKn~2xz zg0SnH480p@7@G*Slfky#IpVRXZcaNDdTcEWlW{cWup=N?XCRVfv)qcDY|lPyvq= z!;lOD`HMKnjNE%wEWvwx~B<+JB)K@bP6_G zC4Sx+xr4y~shpf5q;hz`vgyupQ$Mp^j?o+hX4H^8G-nJGCdFk3Wr-tH7tRGdL(e(}j==KVx1RSI2LwPOOkDYA8V zXaDsFZ#C@ns093a?NmTH#HPt#$#_*$a&fi2Yb0d_qWKIt;Ylk%1t+P%$3dv+si=|* z>eOqUU%{(pv;vTjA(;ien6hZ$+hMnb4|`YL1Ld}GR>4CcD|NA_mVCXWgT9V~O?Z*S z&bEy&Iwmo+c{;%2Eyi6}Wkb>U76{ike~oyzPJ!PLqT#qh7e581QS$A?9nnFGi&}~; zC}Hrg_X@VEoIw~MIUn+A$c1e-V^aBZK4%-P`ee#MROA>{P9_|c9XYRkv&ONfo0qSg zHr8V(UGT@9(|*MWO(RM8x3(1sXZ5-WZv*Pz@*IxCBu7c;xX$0f0u@GuHK)tWUj4Xd zboDGWm*t3KCj}TNJ=H_GQ|FW@FD#@qX74K?<6a$YRT}94rl=%W6!9Uq1*@n#+6Wvu z!uf*lR|F6=X1@EU_Oz;FY6VZ}nGyvv*FGe&U6SzVX8exTLpu zI-Bl|ZyYhIcF(siJbuVz1o$t{tNiCA|SwuZK~Vad};n1{5g1UCV2US*Kf0EYR-1HH zKQD#gnZ$~mgu&O)QaX1r59!m1vF54!c1>EKmNi?n?pWhVWaC!7{*IHwj0uIvH9^G8 zPpeaC(>AMi$v@v65vba}+~--Pjlc-Bh@207DVw_#-`!-5 zmQM*LB^=d`ZeFm=5J>rbA976?o>tR0sAYc&DH;P+)2a$B`>GRcYB=Z4qI}-mh!(&W zqzdCx(t?*HAWlC?io=>}&4Q#U!5N+eWc14n&XK9AX32~Fo}rglfzwPc!Apw{H!YKS zFx1hsv@{AH=e!z%`?{EBbmk?{kHuuBUl2*8f=l8i?j8T7dzO?W4filOZJBSUQX?Jz zCVgR1BUYKZAzfjYYpJ3pZ%IUkb~8>}!gB8swA!ZE!Gx(6HnKghwz=__&sKvG@UAgk z_~)FOE#4OlyO6pTGZIX^Qp`U%@KUV;KsM#3y)PDfsIDcPf~Ti=2#>T!6K zJ$!z-wNK_#A+7d$XJMN+ny{q#@?1lWcpvk5dnvoQyuz4fA_U=FLDDO#&p<~QQs z@=UXndv9u!#_(VEhb|*vJTB2=0jsEuS0H4O8sQkLL(4dE;}*2z$u}Q#vRBe_2yu-} z=@Q#pCYWfn(8dX237OkZR%=EF87Z1-YU9bna7LR^M4^kQ;~g%tsfEd_!$m~9_p25m zWPD31l~oGb+fpOWmFrcdD*R3cD7YGMjxFaBj`}z5$~A`Th6oo+%{2FRfZquhMWqn! zOxmX4vdu^UE%fO`FXGAG{ry!v@K+?)UnBXHU0C2-Gy{S}q^(B%ga7f~NGQ_PkxJs2 z&+Bav`}0b?$7I1s#!sm2z3K+zk7I<_ZcnusN;;Z{DebDN#z&Hz>B=HacReH8dzRV8@>^-%WOkSLQC;FP@sXFMZaTXN z7!6E(^{4#=%7n)|Qx3;CPu@2XT8uWuLkmUkpVRuR5v*m0DK20=A<16u2mOBqO8y;1n)u5d#*2AJ0h=akkHz7X z`rJqv*T7~Znmbr9`W58IU>|-ZCgoE=qr?tGljx_Dpt9wXp>T#99It|^Q&{xPCY=Z{ zo*2{#x8%;$C+SP-EsfVAY+-Ck_b6Qd!4&NT@D|`K>fmN9v_3*xv3DGPzN2w9z>sW` z(fFLKxbrR}1c?!EQ%S0eUYzo&d5H-%OP{AS5LJu)Y!$-B=cjne&m`D_eP6fjhm*v8 z96U*n?06Lgane%CLfzhGW>zm$bq_4FYXxsVg`C zAb?%o9m)ZZ4|$H;A4RCSf$&Feys%yDCGq$|hu^Xa^y)~i|BiYpYRAZD`4b@_x?(9X zaum)V-A)>lNj30LtzC0Neg1R%6xiQQrog{%aoD7lYchzvoakL^6I!f+vc*(0^1p7=DOyVf3%LE%1o4@=QKur zv;~{ItEGVd((0Vy>LZ1qsuv&C24L~lKdOl6Y( zHH@x)@b1{@h~z~^Il0b!h&yUAQd|3x{h1d(uHJ2swbAO8YRk@8d@sWy+HS>|kHr(V zhj2LJjjLiRmO2BkHCO7e;bUWn|M3D>otifs$EtiKTP$th)ED}1nHV+u&UKpry+P7 z<&O1N5?U23K2xK<6>a=nMSgn!td=;m7$Ox<&9Wz}hPcznH2Db}vA{2nR3M&|Ky5jS zG@9A@ix##PCS)Nqz4;khQd91%kHx^^Xb@rIei z@v5BiIOkT^=vqTZBFIRWni-}aigG??D*WbxeM%|zg1fBYHJJy~QUwY=9ijhFT=zcS zhu}6zkWcYl$=0f&K(UslUKkc3o?E0=T#lC|w;VIwW)o9o_;xcixmIo~H#?ZOM)KJJvm@n);YLa4zYC1z$)6gWO+qmh+9Q&|l{TVw6 z8&#cA8$Kr-B6+++(T)g%s^YdvEz{7})q8d3PLk&nOx>rUwrqd<#VTxzIANJk#@^E} z?HzF$=W=#p69-PE^}v(*<;FA<#}7Od#+euDk^38e86{bNTnoTfT*e&9Lu~$dUCNqo zW_|ZVwo-wcwT@6l{1v}5%ov@#OJ;)3HK)x$#UB=9bJa8ujWa_uY);~am{+I55)>$qmnL(ad;^@)O^s-+hpE6z&3`sc(Ti{dT2JuGCJMB2(tbmA zur;gP_Xr1Pe!s%2_AlHK)erTp)ox_YlM%~^`ZFCCaRSdc6Mp^L$z(s^V3YopydT@OOeiG^$G zzaI*2f8Kzzi#V)>R)*3@rsFzaHQB%QK6A*LL7$Fcrf{%5?vAMTU~hk#Z=8Jb{%iw- z&<)EGOQ5m1(##rCXL3*?2NMQ9rsF8#T-*BLz+!g78$@N7G=Q6>kuFjZm< z4UP0@?&pP*%bOeD6!E9b*IYh{W%1p_3yV#r0XrY?r?8tklru>FYmgtnT6T`Gp`nWz zj?H`%GPTcH`4(zG>4UeK`+fZN^l2Q|fJxKI@2>}fYqI@7%gjKFN1+A7fPUI=dM1;2 z9P3%#<;j5v*j9a9x&BNp8`plvW-3v;{ni~JTe?!mc`;gf7Z3$|Cja2x^mj=2hdO^3GGSFtSsYYi{$l!XpC#jlcgAtY&uuVMy+*ZU_poJe2xT1*D;-ODj$NL^h(_ z{iCEyu73sO`Be!tJED6#@+i+QLT|4X0bBxL0^cN5kN~DHzeiXkLtN%uz+SP;rY^O9 zwU8t4sDdL{^}4>1LsqIoVJzb^rnFtGT5)o3#HU$KorW@9<*nO?9M7j+X9@}z*)Ur= z;b?H~-nAt{+>2!~8ew%nYJ$+6*Qj_A3yoBH3e?s3RnHHjIbqD6LCsdIQr3JTkp)ox zb^;&HVo*h`D@_W`#r8zD?|lg)1n2NKq5TAEG`%iP_i7}M}vqNd(lH8W+js9vfQs%A+`HkkJUnOL|}VWbrfVb^aSzBS&*0 zMnj6t@`YetIAEO@B0vuPN6inFb1`l+Io!SX`Xf`Otno~xcAiBv(ji!SzG!<26bc7J z?tb=S`J@#8pK7>$QEHq0<>6R+NPnx;%sg_vbd6y~`oDhul~$UbgxUc~!#93**1X=L z;=*GBU<7Bgt4zv~Auxqdo%p{xEY=YO);;r+V2#hc@A!uDO3rWzn%eBXRktc6=#|{# zMqV(r%4gld+x;B2ejn2lY_r~c#1RneFLCc7dq@}ywsOe3NH6A=bDH?J98y``cLXcz zk$H<;I?Iy4kGEK1Dx>Aw@8sq~(lCaFJFV3OmMFyWVh+HhW90W2O0iZE#qu@Xn*PjYB*wK_&+?mFg@*Nq#|Mk3)Q^YMnh8YJX%Z zzWCj|1#PUKg^K5$mp7?)a(tGnx;+XgMQ*WVgR50R63ZBd)^#BMdDJO}dNcs&2~cMN zX^C*_lU~8(56OMpsQcxkUovySpv&@|;T04DomDh$6s`nZ$R#wOB2v936`5m$A+j^` zs8c7+_9VC==9lnwPV9+OJCSja(5#vcMVKhMi(mdu6;Ae;+iv!={7%921z#WWNP>CW z-3yG^Sa6z_q@l%CbRC-NBDYNB{=W4GNZ}66hZVw}u1BN%3vY^q~x2;aTD>sxb&9BGZEv+`LSOpt1njGrZzidpfEez~wnI z=Q_XJaSiD)_VeswH+^8|6allR&a~&cSusKaE^N+$C>rx2q~~rV0~d?<$^4AN&C^_t z=Cqtlo1NK4?cmY)n_xf#nX`bes9o9U$+NRIfkcRm`JEIES$5$YOS0fDTzry>!bBb2 zV2f9g9g=q2PhEpSY0fXG0~=hnX4 zY&OoNa+JG}a0MO?dAZ$HhE{PwaWuQQok)U5=rZpk(!5Psb|j;yUnzk)KRCh^lXTn2 zA6f&OP78mjNmz}}3wS(!*W7^~NKMFONZugd>XT*|n`6R4m9bt3r@zJEf0<}3_>)4U za!YRh3>g@>5y%;CP@8n$2M9h-y^Q4EO0wO;UUsIe2xbSYJ{P>hvxCtA*#d)pz^4EvG#7UOHWT!z09DL+>{6+zpuJ7KM;4c$UAN*kf!3`Yon zXY#9n+zEVrR7Fs1Jr3&xd`DIc4*t<16P9rJh-?haQ>F+lr2=LFz#nhD-COB;IWk!G z5nYu}D{`7|cBl-CCUwOd)Ezy&sDL@w_1?9O+sWtnWv&Y5uM26oZ4!sMqpsvv4)9i| z0(k>HUZ|G3_LkK|dR(1(c{sqtt;?tCrJo&kx<|}Kad>aMF1VnDeuM(@gwBd$DN2rZO_iZeq zY|)qEzLrEqH_j)d2Lv6HHe|CYD=6YM%u-K&Yd$%qf&y8k?t@L;$SR;D z87&WzA6Un{dp+!fcerZT>DT3`{Eb3niZhPKxg`KO=rj{d!LfbpA!C?M4eu|xjnky% zG9KmZs+GS0;V3%u{H)ODI$;Xq-<3-wtjRUKjnWG#PF92sBztI+$PrSBt>*uj(Vtr* zRAxN}=W(CHW8cm14cWlI$WBOB>87nxF+x>K0KS&=K$VH)fPh^m3N&4ji9ZGnDQfv2 z&HPm*SQITp##nq!br{FApkJ?2LTA0Bz5#q5T#lEhh15)*$wWC)13D^9qk zK1r`7DxxgKeWow=*Gsz; z5ccV0)c>?7w~=I&G>f$|>=~ZAXEV58`f!yK z4L`?QkhZry#qm&s%Z~6AFMyl>!go9q{bti7)x53SXR=r zXX{m6)#wRa)Nm&i9hPdYz?YwdD!hKq13hS?+et!5H4siUhE5UmIF5`B!M%-(u8G*% zu!WH9YPu`U$}@PVYnC5&Kc-cXP;tc+{SnZFRhZD+i!RsL>@f6NeC)uyZn3^dQGeD4 zvmSa}{PZ0@U3vxKlPD|BCzp$KcPnUzc5I30dCJ|Pu=&zKRDaiStc1!7Z6^3qU7*?y zgYnbI(gm-_I|K1^V;<7ZsvP$<>nwVSSl}CZ1?B ztAxD`Y(rj}u+Aq{;lt`Qp3Ttp=CT{9ZoNy*Ywqy%@-(L(>ss$o3mhQC*GpU!J67C* zx6>ZGpJ>Vjn1Z$rp_yuVNe5?B0LG=iXNf7CS0W#6wp^-y8@%klEz%{z!imG#TP#Fd z;{0inr!(KGHVj5t6@~KydZxQrKK_fF+LpK~ai*+?+A6Dk<;h!)?pOIMlL~7!Bov8G zwwdi4qxu~c$dlf~)d6s7_vJ}<-Z#!>o;RXo*UI17(wRh+^IPp-Gkly>0(j-EN(w6) ze@>-MwmQKFOSIz}+uYL)=p_mFTshx6td!%b5vw>h_M?|(mD*$5)NG{X7j$*KAs@88 z2B!>6fK#Q^uKiysbAgsG7&R#{3ppkKp-KH9GBxiNA^Zm zaR1JVSh_eXnL3Hu+dA0WncBG!a}hI&+S}MWsW=!Kn-VjMnYvjTn<`6+{HH=FAZ2Q4 zZs9`A!pTC+s3LFZY)#C}`CkbPDy~K@o(`ZZq-_n&K|iYhIru*VVbriRaj^i^7Goo3 zlryz62mR;dVq^Z_rNcH5EmRM)N3I9hHEi>*$!ANyomN%1RZuM~(t0i8YKN=B0%~8W zPz_-0289NN3e~@b)2e@K!2A>sRdWhotQlTvD?ap#?)YbsAx$II5oTLrS0Fn4V_=K> z<=mU=`<;W^4M*DEBx~A}-`_9O+_#x2X+I8A%nveIv!RLk_hWEGgSAzPK?Qx7#_lh1 zz<$!-j0mdaEwy&Oc7{V%12bT8Ho$bpW+UT1=%uFTe>ME)_y$tQ%<0ctv2Q#h7)!$K z1?PFB4|rT!rhAX2!5+N-<=Gse=ZQjF)T1C z+35}gP^Y<{w-+g(=0;Fwasx18`v2dj)$V69WPuOmKeGFqYbS4p>y1nFU7RYGD$_Yg zPoKc_t@b9SiT>RB-9QyJQXeXY`hbHmvfmV4ybK2edVgf2FMI~9_0m4>@&5NkvN`O% zGX?@rI~jxOmHa+F8^u+7@L*)Uo^C&~7$s-e&VMJ2W|%$l=wVSv)L* zgV#f4+8B{skybAOpY%z4=Tba8*Z)^Bx@f2ZTWPfIFUBt2wa6WSl$TOcFo^|@v}qaK zLb6$Mie|R4+N{a9>b}C@ZTx@SJ|vQUA49E=d8iXIG7*Nx^(C3Hr}Ex8Mzh;OBnZ{I zIJYi1B5zCo6@#5-mZ`+L`!Ax+&V;>z=4ZqhHgxS4%To}GYs-eR86Vgn1}6%8v7IjW zxV-_gP+-uR=90ke{y?n2y`Zz;sz;fZLDsYL{Rs{Kf=ahVXMtv&SwyUNmSW?tHRxT@ zc+{u;w`zggq0Qhqv2R5rlbKKOHdt%jAtI0o@a)WHzde?FOu!sK^uFUX;2{*uQDc*Q zYvZ}Xu&-WP5$?+qTLI3Zpjh;HK}m4Xq`)O1cTuvop0(=~7GfmZQ7Z_mr;*7PFOCP1 z9Hw{+!|eWZ+L0+3)+NoP`|y{s;2^PTDCl|0pZhL0ki0f9a$fLM;m*tU-J!~Fz2~+6I@kb+XYa+D)J^Nb>cPfTJVH2D0 z#TtRF%4eMO+0EHh$6eizpWwaVhpX{I-3V2J)Wel^fdUqpJ+~L6Z8N7=+$WPiUR*>+dp9nQ_3`Q>R_G6z$RVL@u|D2-wQtK*mQc0OtZiwJU=sp3<9I*7uyiNwwaj7l#c z`Lx9^+y|wqo!yKPfP~9%c_Yz|O2b=x5=2%A(h!gy4SaqTsmfk+>F{dF1VFekeaiRy zld}jTlGUlVSQ-!#DEh_ig;7wL&LC0DsV0P zHGwlvh*yo;_Y5fwq?Hrd<1U@f+Ce}=#rvOj40JCy3r#=jSUK)~If%Y>LZR#34h@s0 z{}L*A^r`DG;sBQP+1!EdjY_&=-z%E;b%IznYi|w686jc=utMS+@^>Gt7R!og+(Z_) z%arfkr5`P$wJ%BH`J3=x6uV2i5KY<-zA+hmoxNTFDFg$*7ZFLc&RYbKEr5(?+(`DN zjQp6QOSgDCv3waY$7@l;OsS+_*UdXlUYZuA#H|!Q-`=%evIqFw&tq72^bZq$&asHc z_FKGEGeWDAT$+F(1-Yw5ls1) zP=C>>L_0?KABGiySasyp!yJKYxX`q8HVxG5;Kv{;q>(J0A$-ix&7y9owyh}X_! zVt~z)%*<1Mu$z|}nOFY86)I`alhL-a_g@djH<~ArZZIiRLovC`r=3mFzh_Aq=}jFr zmPR0B1BcbY_rr(801QE#1krG3600XvRl*~{2h}x|_K&W7cN`;FNGZ7A;N~Iad-y&u z@u0_!RlP}+oV557Zt|aTn@iYx=TU`)hsa4BJjU11&9OPxN4 z1oujn{gyQfSpvq-_Gazx^I-nq$E+0Z8@EVae`IDRfM~xSO`{TMFff*A$i5uDOF_QN zO}@+0!}H_3{lRwxeb69;GPPllz=UA1Q^COcg}TAOpf=<|9tlby7Ray@Lu6t@fx&zR z4f+4;7uf&!0RQ8EVbO19V?81fiBX)S(`OVg;`#(<%)V8eM?v$jTmfv>!&tt=WnrpIa z!xo?qaUobP7nRo+xmFL>DE5B#{wtEit(GeQWGHKOwxTeQSOW zGNSizY`Qj}yM6zKnCGL_x_6oVsB#?AgE+nfvSB`}%552-nF*)VfsEkjK8W?Dxtu^k z3N^mxBdz_a8@m_ukBq;8FnINirSSB(S;f>$B zm|;xe48ACXrW04&IFckX>R#~O zY`v4Sl1~3C-&9RaTt(Z~xREeJsUeTmVR8zRhu60qGjbbG|x|BQ5W_$k7;XJHf>Q(N>9!aHWBkzQj+)6ide%S$lV;z$84?64?<-3B zbku3Y0zV^0+kwm=&uS=4*3k*Pfu@R?c2tUMDOR%b_hnhgq zK|JIBcIZFxhHcn^tlD|s&d;V(4qLqjKVvd4$0C_|kW(tA!vLI~yK~q96{A%1vC)_VQ6-Nq^SxIUC#nB~vn-*HB>Yml!=yHj#6SK=fW+D;s0|w0Fog2{@fo051ih6I zZjf19Y;63sOZX6Rpy$VJl^LCH;)Ov8XlAhugYSQ zhw2lDX7|uE?Ahb&XRH073(&W~o%e%w2G0zBTV`cHf%o=NbM1=tV(72f7Hadt5XgSA zkN#dP;ea6QW9#O~Ogs(dq1lf-j_XP+Pi-0Fn&F4u;q$Uc;pX) zNFe&8mnnG$7BIygQAz=+)&21?k2E`%N1hZW2qY`&Ct?jP^3oQ)&7E*-zemP^NJlHx z;9$>GBI6DNlSP!@;PH^=n9Te7%;fhO zekI0hmaNo0C{Fao&`!-}F$ z_OY;(`2uJmu@g$J6@n3WhJIn9fMB@y>-Tr4#4MBTK!;+aMPz_ma~!D#h<{Y4cKhgC z%O|IPCI)tTO(;Axyu>iIDOKaKnQF`ssp=2wRG2xP;0{HvrzJk>}-j%juaeCN< z0@vf4UIRSk*H$o1^N{U^TK^0^8=01Tw|XwotA0m0+mLS;@@ee!S^>H4VD7BY<;KX(Po`&2Lk`P1Cy;2lxl(r z%Yw=4r3NebY{=0r%AxO(xC?fbJ?_*BpkWE4_%jrEc*`JtH6@_D@Ajx`zS(|jTW~}+xox#2yFm*Zs#Y+{SX95hLzxn%10fGOb+NPbZ z7q?ZFv4`o)=b6hJSncPevX#)7AR=|! zLV{r4TLmQ$g7mM#KbZ6dgk%t;>)l46#Ra?ZfBFExI{*Dc2nsR3m8a0|Acr;(lUnW< ztR`sp!|^!v*C6Ek5R-Dx-TwCOchQ2+N%(HHH7=+_gOkNg z*&gMW0U_-lXOnLZEX!UnAahbGw=Vk=giAm(YrOksnn>W}QF4=MTW0ke)IaT@+_5$| zgV8E#1Fx+|=6f|z*qNi4ULh?qUJBEHz)oOls9Rmo^>`GdL8BQxng3Cal<>H6=|i`2 zR{v&}AJljKRxq$Kn$h0@213zcFDU(-mxu-E6Lkv`%GwGS?lAG(K&%Op1B$x)ZJmr) zn}2D_LIc_k(EDvZN~XSw7V;mN(~*OeGP$e_8@SL(BmJqCLvN(SgR5^Zq-? z@2`3Z-fC-2qes1wrur;sKJ?nI8!w?z%fZq5LSo=yI}19?t#ij+2?C3MugfKf@d{MI zt7YvowR=~-%qM|piC2)0`aiyXjX%k-6q`l(_ulzYw*T7_86db8TB5}C8dN)R7O?mE zJir8EX;5-fz+Tg`!7;rB|K*xwH8{xNOnA<1xgBh;oq70OXI`pvZ&g^z4T%4G)oEn& zBqmw?2(=R6DirXG~m!fMQ?Fx+xjFAvWZcHAD>?zP?XXgMoFUA-TGr6 z2t`*KcUwUkLN>t`56E!Fo(j732GM~WVV|^T5F9<=qK8w=araP(T}9b!17uGw;EVw0 zy-%XoZ9D*zMTvy9m~}qrO+Z8RWHp(+cnZo6Xc;*di3)P5jv$WQIBberJnBWOL1#K$ zf+%&0CP2^zdre$5TDpR4OkI5XJr__U@CZg{r<3Y^u2qw=1axULHKeR# zk)-26pUe*H-oDY&HRXXxo{!$B|%({UQJ{m>?e-W z4;2df)AP2O;U!w_6I510IS7`S!AisCk68?s>b%23B2T31A3Fu3&n`Qm;KJgQ)ePkkqHC^nthoQKVT)|nSNlSWPWs0>Y!D@V&P#fHM9iBSXr_DE=z!69wpBh z=29#v3sOYJGC#fc-VVku2>W1(y%`KDfi=$ik0T_if9#m)T|Xx8B?C-|{vd6|eus!J zXT}Q#UB!9u8w;Ky4qET^Xmo45tv~Tj+G|4{n6amV9w6t#MbGKM5Qheh))66fxZJGu z;sMZhnxSNc8UIP!=h{ZXT`Z1lAjnfsfp1pm_o``iKjEK8dR=ckK0G2vVM8ZJ~UM-BZCxt61+P0FpjZ-;jQOH@x-+pAjsQJ z-_R|fX8#=PN%v}cKpeF$F>`aR6TLV8Rc6};MF9(QftwqQ3p_1PI4~%&G1P>P>uB>f zuVm{ToV57gWoaJG@pod0zruZ`*7CB$5qlZMdF#0fNL!Zbrh(uT_PUfNSf#~7? z?5@S*GqSiRZvD|>>S&->#)ZFakO+*miXs>*a8Mb5sx_m@^7Z&QO;qmhv2{C0DkkFD zOA%hWq;ays=-w(({teNM44No9<`aR{~a&{a?v_3r92wN$8C_N)S#-j z&h}czJzo?p259%VS82|q`7}C?MPAD>k+07}T zzRRGQ6ZjCBmc-&%=ik9tqxzvA%WJW9+1qu4 znag1;(_ZIH-!d@rP+|Ql?6BjVv z=u1jrbZWa`+V&~Sm7z{4pqGi|&JY?U6giv~j6U#TjBJC{+RqXbf9m=t6KLmY)fiT(aHC=N12M!8~PFy+Pz9D%}h^ER&6 z2|vz^*QGHkPVf-OuyO&@FO~+Le;d4W!Ch(P=c7U56i?UuL3-rscWM?kNGDWCfX6!0-=!dCSkVw6qve zr56xDbaZks{$h>jmU_IxWVNLEzT+GY85s&05effbM)`)&0OR-J~0Rfy|z9VBk^j8K#B z|5o476?;yxz{z>r`81RKf9^@Lu}i(Bqz?(G=F$B6xWVk5lWI;|8>>Xu^gfO~_E=2e z-C{N|x_6H51Uo*;OYTLStA|(gQe(+C1@+_N*Xp_xrSECCyl9WIOI%XjUf#N}yw8h_ zrEe<3B=Y7%dZ>t#A#SiWd=Vy2#2^AvIY#vhzYwc431s|2LylcJYoTyP3bxvQp$-3mOzOmE9u-Bwm4apUZA?3}l^&0~_s%e9>wIURaWQ#4$BpM+B;&S~4a`_O9m z5o`+Q)?Tw(dP_h$T^Z(vIJn#U2sqYAzE&a@udkb7$riqs1XHXS3X}aMDpX zspaVp5Fp9=cT78=v28_|_73;AN>36X*&4bOMrQcA&36BirwzFRaQuLOwx@$+@Jwm1 zbHney=x$A>{yBJcZ||3L(Uy%G=Un>;ngzVqA&aZl!Y}u5ul&q|tO4t9?#q9$y+2Ez zZ!XgWdRx)mchuOeDXpORV~P>G$$IP62F%50q46$n zybo7*; zOix(Jios^0Io@}24+kmxFr6tI2O%dTy{T=3DeDh@u-a;b8QR8qF|J_sI z|4=!rFw*K|zmOF2>T2RP;;&CoU}k>g(vLgY+jt`)kNdytdW55oHfR*V=>qpb2a8Rd zgpT7=efibB6H|@>J|6e$k1k68`|afDfIG0<2CcPT0Ax)%Hg)>Qef#7qVI|6Wh11G^ zsWAoGexzHK;hVbf$rJCJJPca1yT)larCblyE>xnv5Zw8|LNGGI7K~(ue zXMp`+%Yn(OYFU7XC}K*YDbTyX>gJ@f5o<+f%K$AeQdP%d?we9y>9|A_gH!;xq$`|B z78;kF=MJv-Iv?jl_?xR}kJ`hg>fjPud0yumg&~Vv{mAmNDLAj~^m$8Oi^kkC zMD>bPUQR{_aZ6)naZnF#DhtEHe+Lok0leWhE@PKX0YisZeidjEt!GEe4Utw7g^%k$ z@w`8e_nAE1o!=FpIX9`a*1#EoS1TSwy~W0+)=`APUJLtyX<(55zbZ#V4w|e(V8&u! zitRS_3KO)6-6KLfT)Uirlam4}!cSnK1*L6@ABiGbizhgOPXGq+`awc8*#7vuweFU^ z2I>jhvVAv)_kG8=IBhlo3~LGZBl`P}SdrZ%x-#xN>ovp0N^MhbSC&=_Uhb=UPb(x#O?fQO+*_n%|`h4ebnc!hg-;XmfoAP6Izna z8~^9z6K;~msyPOo*FyIdOo$4zlBc5A!pHU6Tu)TVvfWM=@6UDE{}eg&rH&g?RpZn+ zjX@&Rt*oUy!-#zDUvI$D^lHCqFC43X0iM>LOCD;avs21%E29kXiP;Jv|8I5Z|DZzu zzX~bvKUB8GyPlcRsa^fQ^7-p8>%^b%pmV@Qlm3UJ1ozq2&Xr^P&u&;( z%XXOq-RHJ^+|iGwMG8_3(lc$u5efR(bBTiH=R2tvLB-Xqhz$#~6CMQo-{*{!`oA~4 z9HX5`Zg#P2U-m;#+JUAAuU%;@Gob0 zHcx!}1x4ZXWRH)OmCw5=W%^87W;7^YFo+o8%MbK{Bc|H+#pl5@z0|E!T0YF%Z|F8J zKh87;GlKHlPYQl+b=TH8Qdf!%bYZgKQ&E}k1M%tb2>gDBlE)b>?mQp4<$DZWzLi@n z5qTM-#Prs_m&D9J$+wguCps!eSevSb8CW)b&@K4;Y)(~byX8}M+P~MIG9W3=dn$#~ z&H5aISC|uf-lz+)?a{8A&WcAvxN?A}^&#Hj5>a8B=EHZSYW+CtnA=}ac)4$fHLLXA ze*~BtxR_Zm)plAt(Anj!TbjkA(F8FOF8H7GL zd+6%1cGQ_~co;52zwyMITWGmYP}`CHYA9qtJ=GtYz;yp?6Kb(8}*L z-_guK*;A>xjBk@jT?F5djk9)6;2VYqfEJ)KY7&J^KU%rl^N`}%d6O&T z;%Yb~iQj(g7}_SokzLUBUBt^!{A}nX@EFV*qAt@JjbkqO6RtHaG3hX{nMRxFPNP0UvGR z*Ju2_KB&1c%9Qt{`TK2!zsJNLGE1$XC0#&-RFG<8cyd{tXF2B_r0)@z=4QK!cj&aP z>?h%W@4EJ#995N3mDMtU#5kKY`Ot9M0>RW|dbq+}_}pb21{>1B&X*VaP|B*Kgl_Wl zTtE5Qkt=sYK-zBma#zaJ*k1pNAOLv^q&?lT@=*O0-FkofXfz!xL)=D}p6~^&egw+| zT{g6b2LDqcRa0RVYlO#C#L8Lq)16hJWgp`n&36TtfU3WD*)JcyU1hBBZtq@=e#g4O z=>BGtwC&%xbDE)?dU$R7)$NhmB?K|82R34IfYF>FO~g2!t{Q7n*?vW;!U6axI&9>R zaGr*K5A}hL#V9D)`D-j6=swGQ+uoS@_ah#SqN&_O zijOin>w^MKRIQ|XmIM;Gq@)%AQ6$NsAp17PJ$SrIr7s~N>HUB#EzRLDmWgvQnXh6T zr`e8#1dN|I;scz?U5)d>mCCn=lQKlVa+}-f>^F*w640zJNba1`4U~2CJK>!Y&3Z;&TFW$s;EkLCAzrMvTJ z&UCxa*6G)nFnZR>OK&DBclejla}ZpICVj=^h-ODOMWQB{QcnH3ztx>@iv}_XS;JaG zsR;cJ)WF@t*S+)nFfNP&2qUe1C0mb!PyAj%@|_(=I1W)3=)QzJqL6^3VMju?f>exQ z7%Q}MNS{I_=VqXQX=D{zmFSqMrj*Xlt!9H;HeC7XUUJP{8FDcsTvRr!QjPmyKWOD& zFp+$uJpr9ArT<5rkkeF*AoB|v=JfOu4ri*)%*<(j!nJ=JbjuPf5F$n>n#`0m|AX3! ze*werlMu`vZm(PC=W9H;D48%z2+3s8ABVbOTwfwmxw+_X`j@x||J|&A9@?@1X_|e;yZGPm08_Pbo3%6Xi;2_wqW?=!851veJ?YcXBROIcj0AngOG4vj5GsV3 zaLD=DtcZZtDVF@0$C8qPvj@8)!CgH@_)G@b>9!v*^1U~U@T<6(-dw#-6G0>Fk`)^I zToa7b*@4LlmygnW2nBtocLfUqnX)V@+Q)9hX!nYI%c?zibATQC!#!{LKt&lO-J;@N ze3xT@FD)fRuc8xfJ41AdE30E4e+aZhV@LfvyHqxNjHul1k?-6{-xJ^x&=MNQL+yftSfZNb+;*F-#6P}q9wuCIJM2MGt6vmUq6mJd4W)=Bu={LQw&;lCzyhPL8REJpQ}{`PB3>f0|z zvM@{z!_|cCV}b#(B*tv%1bK!{uk8^+;}Rw!e|mCZ3;e*qr9&;Lr;`s*BRE!EyD3dF zTiX;;_H8`^)p@Dx%Z!+XA_I^U3o`*oA_S z+3W5sg;}A1lxKCBG5?Z8@zUHH*gt$K0)mPyxOi@a2ES2+$5|$kLOgI)HWqP=`(avY zKF6@SyPW(;^X2@gA3;hk?hee?TsX%i7(BmDLf_+qcfBkb6l2d+Dll!UakS&jUdv(7ibtEL}jwQ_JsZ(~~Iw&;+`8im?+-K(5-36GO>;#@28$ISRDE}QI z=_)QR2liLc8tC88uO3WRG^Hlg8I1=0SWcM?o|^-pu4Vb;z5uCoh!9*VT@IfpblC$QQmm1$pRFou&Mnj1ysICV zW6)D8C`qf3c|S_Y8$17uce$j%W^m{Ck;8Pfm59%1mRByKOerT9E1nsf$R$LT6w$+y zm>oP6kC#kgX1D&8)gHUuUd2kd+c-p&gsNe<{YH$?s++;>L|$v6u!{KwlCF|HG~v@B zq*B6%G$?Awj|q@VknjFo4^%mU>Ijk!;AH>L+rV$@Eksb(qj;Z|H;h5*&bC1a`<@Wh zXJ8^nq4jT)R6x()0VLXz)|BcRGX?ypd;#h4ZnW5Fls_@lG=39*czg=_4wT?Twm)56 zU8>~ZGGc5b0DMo^Xpt{(4osXkN7~z2l#}~MiO)|B+JHY@On@Mt_XEG@i3>rsF&Xh z`#9wZuKzyX_7USvkv;aG8R4mvEAIX(=^9(gAj)`ox?0(FZBorU{3&G>e~#2yhnOLw z1kuB4IHK!qO>0N(xei(5fzVEF7Sl-|GekDK=DSlRk_GsGDp^vIek)E$-*cAr^K;rU zvuJGrnO)s>oOHCTlX4zjR7W}#ZKJ@OLhND^6x&^X)wh~|tcGNSEvlgly<*>q3(C7E z9Gb)WB2ci|2~{iBjgOkNshTu;r?T{fQ4EvpagJ1Q#Xwcx$Z?M^5HQGm{7oZquRE(% z)CQeg;NSrGSd549q$eeGO=JSKNq_rB(+{U;xFWO9khS6QWB9TolCd&ai+HewWmqkd zm&~R~$}{R0mCF&{ahhD}dmLwBEnHNmFZZ(Vil}>}Ux91leWxiHgc}?oC@}SxKa;Q* zUb4B=#>M-nCJ7;0h) z&6ga27ni?C(+!>xf4MM#{nx-y-lvq{jO8mw6t8BIJQB^U2OkE1hx|I`=M|a&SgMl% zZ0LC%SbkHc2lT-Y1ybqEm79ZstKSea+q+wp6v#fA*lI9v((x&{ zJ3ns_&pg^zQBy(sXWr_~BA%r8Z>d|U`A^BTrkQUIuMk6HTRl7wDSwj`&Z=x5nb8K! z(U*`LOBvaE9*5%tE;!si4j` zReX`45qlL8eWnfDcex1;UPqc}(i;5mCy;t{#^W91;7dG0Zfln777hyUvqH^zeBY^C zKrqB(Bwv{`FhEo0p5#}LJVaNm;RYpr`ICXnUWTr$d|E0++8SeHf$1kbx0~|@$n^F8 zIieyPG!{7WK)WnKnUt?HPy43=ng4z8Cja6kOu;)rqoHUKL!u&&JA?oui`w6XddjF0 z32d-4)5S}|)BS?82}PuL8FZIc)w=N|QF^mXyN~klQQr?}Y+#g67dA-L*C60VE8CRc zE}*dgXxIuet5`RKFuxIm?^XR80+be)bSJhd2UN;@iVRquI_LUzZD?%Jb=XEdx$W9% z*{{39_mb0AMm1$n2HQPO^=z^mft$nkp3O6R@=Ha%Lddz$hmGB=8%^H5=qi`0dS#t+-2(W}1Vu>KP=HM_yvLYz zG*`7CRMdbHWWOe?DmYY3-{6Rf18zM9u&^)e8U(Hsr_Egj@vvO-45CPQ9kYJO=)e$> zQcsX5y(249)^E$eZMW~Z;+34eRM3FcwO9!Mo3_7s8xEs^Mm#s4JTokl<=&PLBk-(P zWa0vg!ATVp%M_CE2{A1^2LJ`g6HPXrGbv$uN+?N&`DWw_Yc!(w3e`|z5Dh*DAw7DU zJ=N*d&m7GxbC?qM-egvGBdn%>Zg&?}*+Ymz?hHAn?Vlz*h4=%bJ|F2U(54c~Ef97` z#1f-RV)Bs}T5|2LLQfHm|J(X)j00jy^FPHMuGJ1eP}BcXK7M=Lvd|olaMX>%r57W4 zB6SWK^09L&CJ1yY{LIIY&REj^mA15bb}ls?oPP#Am3@RrE4VFWE*4*bM zOIaSIbJRZ@X7%Qpy_>$k@Zgw-#@T^=+?1+8QN-3TvkGHFbkVqeD>M zEX*|?|AwAs)%+g)#7Q%zlxnqs)KS)&!*e*+K!Bi+aFKR~o*`oQU9xOSZIA^EV?K#r zO44^aR;HRNl8@HLKkM-UZu2i?hw&B6(;~I>Z;}sT+)RjzWUfDZ@~;OmjliZFkL@b+ z%MuyF{f7F}^9LROG>UqstO|pD-cXExk!)?rFqtsDqBJROR6Y@Tp5Uu0Gg1Ho2mAc( zkyf=zUgDbd+GgL-`wo zAl;nll|-MUjd!ba0)p|%sX^CFX_ZtfAqx&<=!ZKU;$H;h6~6XNQ*r$`56gOj{UkLY zqFwu54%|WWyulXg8KD0>$*#r=EG2XOweP0jX0sqtXfV1_{?SqrF3hQ&hq1ns)qHt& zN6;Xcvd^Xb)f2(H#UufjKUZ=5nLWd{W$F9CQ!q}H*j!y@In5LvH<^J4$M?0SmZpcY z`0AzW2OOx?IfwC7Kw^kRk^-M3%nuq3pEBoYXgQ5Rduhw>3*b{{?1v<4Hf3Sm)K9om z=T^+ea&2Jc;O5M~kX6ul(j5@0g>?B;yLi6PIO^#<8jyjp-;J70tSa+YML@&Py@2ep z3Lf{SKJhtRqQ$j7ywkj1ZzNk^IKm!v;&ZF-$dRZst;>>8JLWy=*^Y0J8OuDWb^&=y z_p+Kg84N*rHo(`*srhGvMW=b+le2EwJ$fU}hs7tphk2gdhGVQZzi?%2)A@Gtcca(| zvpYQRTnWBA4GvO$%c7%>JRcGYZ~9$_>ptR2HM@pFE){PUji zvQV-&i5q?kCT@ySQ5Xsg3<0otI(_FQ`{|mSE37MQGC<#2!2rHJU*yF5rDaUj&;84a!&9q@8zpTifEo;tsuY6{>m~#v!Y-@JHVP#k9dDKG_KY<*ttakxfWcXM>c00Lu~h`n#vFl+uh>hu;Yt|rDt1y zc(^^Fy61MxHT!&TlJK(;(#;X_(OSd8<#V&n|8|KI@w+*U(O@wX)t0HzYb(60Rqk7M z+4rpS*w4A`13e-**V2dUqeu%0$f^i>%S`C`!EAD>^)Z zgaiqUYTvN9)7#jiwT7$Y_pnz63`2A-4l!Ts4Yv4v)=G4dYqd7s0BfBF$bi@!+)kB@ zd!EVLJFCg0wX=&p$jG=xz7WV9tZ8cr4O@lB%00%2O;7}d713@E_K#2g|}$`!m^k5lRoZ$~kvT$QRy{E5xa z7pTp94T-j*1m$+7%{S=M*b>_wLJcTQ$(Pg`?rX>a4)ntkS@BLWB3!IiI z{MQ7t`~RBvNOC5v#q=I!>azRcSiZ%u5Z0_yAXUTp66q#9SL#NJZdK@ z$a{ks)tcr`R`_{1q((dT^=6t>8Kh*CtqbqM1KZ2p{*HOrKP-(gwYPi<-yoy)d3xS1 z2O6H}&CrTf79a28w!3=%JidE*zF1)pe7py?hUV5Pmm*(KbKOR!N9-N9WK%RJ(F*qp z-uf?PY3E%AZRc$K+A*%odqlVJ0JB2Zyv_E`iGRmd1zyg&ibaoZ?sjo(Z4BIhUmstt z*#ci>WqP^LGJd&jcjX()dSMEPMXhyFk2OVo*xz)#pC(Q7GnK@2rd{)te8d-sdCUiv zc7Zm#EmZQF5R*SY;^Yh(0$!Ie_aLOhw&lhYRHYd(S8Lxs)KxVfd|UhGa-LT$^q$I_ zJkqREDbED+6T7V{Y?pr8u^L=8-$%1jeBF%pzt((nC0w-gq_wU)cSV`WflRTtAg_gM zp3b+b;Y<9Z-h@=9JTo3tY54od=My0Bj=`N}X@=s=-PcutIb)&nVfS9qPdB#s-Hy%K z@ve-Kw#*EQ1r_l?8lLcIQmzu`DOS6bHF=!aM(_{hqRm#tAM=sGN}=Fpj%Q7vt(L>m-rjlW;Evj|I0gyHC$0h7)OM%EI=MY2O> z(f|^QQ=#=q;&2U;tf@qg*n0nUW7Enmh94umDEk*Tlzx644GqZc$UoqVi&PX#N`m2O zwLb}cfbY&ptH2DcusErtS!$N?864jjdz`jc#S$z%TEsARVx&CzR+_GDzj$EJSsW4{ zxmH-8%E4dU!Y%J^2f%Cfm;XYZ%ei$Xe_xL&b&GmkoXU8^gU2~;Uwur95=&4IlWJh` zmi&)-C|10Zgs7AhU0BZ51jaat$YQwDpGOxSIx%IZH_zlx1=*zJcDOO9oANJgnAk=} z869s6+D5`+(izq-Ji@)Pc>73{q+uZz#0gPuGy7Qd9$F@xNr3c&dzEg{ro_fKx}VaO zBxHEkHKi8>PMugCQ5V|!>AeYV@4HwKC%ubODMaz!`#ZPXF~aO}oxRn8JH-Ive3xey zY_S71FQb(6QB?bT-e-|!eRxO3$`J}aK9)NH)~e-Ws%&ivF>!dPi%4Onm|%IM1Ep0& z5yKpdN*;t=L*Osx?Xu-?&J#CDh&==f1$n^957h9)8cdhXsQtpu4Lpymr{SCcA2QOU zP1&EN*6|`~6*E)aN;9f>?vyn}AKiy#kTS>|e_(L;M>;$Tl<8!BFpPR3Y@jXq@@mBiZ?vKEu~<@RRc*z1=IYsW#!X|qriqY0{MMop zb=yn-)W_}QuUu4n&{q>crag#PwCW^`-;NQrJ1LkMPwHdc+dM)wArsjRq&5((+k|{i^@?0O2qW~Z@bhZ zF@Xm2mnutr`U&_47~JMBt092~Ot6vBZ-s7CSAu$<-<+V4zZRj7mie`R2x={Tr63CfMYT-7uV#gHePWt zz@!Z&SG8t#ydH3LBFdkKmIbeL^kDM#!UxFFj3NhTYUjvpYf5 zUmh49ppFy=O~m~VvN_O;v#5CHqwro0dt_-&h_jo3RrUhFIFzT>z# z=K7_vLNbqEE6A$gFhzhrqi>T)k8_D2g~Mq00yhkkn2cK-`hU-AHaR5Y$1XC(I`BR5 zAABOYE1B9>WZx6}sbzV^;( zj!1K?CgD4Ob{H@1NOsa&RU`cDJk3y<9Q%!(+*i0($Wm1)51ERMepXX%Fwx;n#hh_W zwhhc|!Qo}uLBBfn3P!P#lolHVt{PGeEVlWe6CP=sutwLP-}3;sE)tozZCsTboggLA zC)pMTFM>T*Y=f> z>RP}Z|8?gjX|4g_R;yHl`_~cbW2+LTceZT&RC`V?ZLE{9kZAeNdW$u=;k|mh0~#;` zWQAr{_3F{TwFihAVsb&oo54l^J*HQjdFC0MJg8n%T+di*6N=(J^<*jWK}0E(RtvYH5z<&l@Qk}qdZU_4Q~=SEsFRfsa%>$;1o-%g1rI0 zY*4Kn-cG=JkQtw;!_E0mJ5}ULwGKAZZ}Vi;f&sBpy=;=5e%tZ@?e1mo1QI8A4d<^C z|D2-d$=b7Km~b&z6VO1vO$gBD4aU8z4IAKOgx@N)@nWxAAD+@kpL-Y5dwVSla#~)q zhRD9fALS%uSfKZH6(J8J%5*>ZT5orw`qD-7fq|P-Rkne&7DFHf>ayI~_o3 zbHEI4xU6aso=or6UtMc_hqdX7&PYDMsr2hZoYL+EC9^CK=oELO*q*KW)6$6=xc=xG zpt1jfz1Q(5$&j7jTn$5p%KrN-A|5apq`VuQ*jZUHOBr3fYT;P>Vi@YWclg||Wgy6o z_?Gp(8}1uvLqB-s$P4v;I~w)=RZBEFYMf;KUY2-4l!YN?De#5W!QXFB1v@2sxFj)t zuhxu)rd41QzHjcCbU8BQYH#5-|3iOoGtCnRNJ(jYH>|(P2%p}>6x@kQu0`+)zNa({E}a3QPJn1 z?a3TVIHh+NHsW&ky-_m~u5&1;zP`9hRa2|TrHAc@*X421=TbT*6s!*nEIc>ro-;FR zun9x&n#Ct3Z*I`B!uKF4p~*-9NZmvybj~ceqvg!oUx66lG-suS53%DYQD0lXP4nA2 zy@T^$Q7(hMzaTQj{HC{@$w#nmy29eU*7D4FS|{+9;$?J@{z`;VZk=nE)ZTvXO_+?^ zMWuC}{Z5NgyA`@d@*SCC$*my&CohQqZGIm(tB*P17#0d4!P5u)P=kk}`>)cY1PD+d zP5j9GpK0Q;?mz@Z{oB@Cjp+qn<>i4l$k1&3Q#?y%9pJ1qR^)KVffuwynK$)czfu-2 zSP+)@=?zFSzKsm)W2m|dzXR6nUjP@Jdce!`{+d=28As`CDN+G=nK~BKZ_*;X%v(Es zlzCTmsq^=?p4eu81E|l)XnXNn@p&#U4`j2RAF;>G5K$BCX$trRZ&PiS8qKzaDctl> z-}n(JJQr?les?ba)L>rjOfKkU`uIAZTHngBe$G~*`5eInuf6s8^2YR^%?ID%%eBX| zocFvSX87E+^9|%kwM%!FKMWmTuPGQ9FxArKSf&_P(T~mmCSAbICv)1&8ZUW73ml7! zL0rYK{Hy)~8nhpPd{v?VF3iQ}MS@{ z9_RL)Dv7l+BCEg(_r9Ma;U8NTGMkh9^p54`<1uZllF;-}Sx0(g7GAj-mfq+sLg{PKrv(B%@nUfV!)#iAldfMY+TW{fUb`Mup&1*k}+(Hi_}+Pnl?lox&)$V0W`n%#2K+wV&P0 zR@xL=bcd>Pb~Y{TmPc83>9Uk>3PqQ)Kp`+ar#xV&;#%hAx9hpCKQw#gd81fP)mXL4 zFD6W%|A(z_jIONdx{W&S*jC53ZQJbFHcqULZQFLzv2ELS(n05*=Xu|I$N28}{_TCv z+O?|o-lyu+oNKPN#umx^)>X@VwmPY>$Ca4qfX>1ek!Jma!m>Lj(J7l$URs<2pV+P*2+AliBElXCYQuF4C4Kd2ECDz=U z_@IWN{Jgm+O537{gasR60R$U!ma$=)7M`752g)E_kSrnXupg8x-C1$&MaRp^Prse} z_CRC->)q3A6VQICrxAUa{8aRo{&~$Gy{5q&tn$YYA@6)wirzV%SXSpGju;6%50Vuy zhv9A9LS8@bL>Be4T^77Nt1CrB-Dv!yL>F6=MTfHVIxlcB&Vi~a9@Ih{%H$@223eSY z3`d|XgP0C72E?1iJ5Q(u`;*BzQPYZMR@%5SaOxKUgg~CbVKnk~l4@pA8w&ER?$)Hq zP6GPS=sCOi!6!6t*wQ3iwG3)F@x&-#NKNzEh=W^_u-0xKhI`9hMTuJvaZ|v1XH7nP z(;&QgjV+~y!f&oxVF$}#z;$DhR0IA!<^}g<-}*jsNL8dlyZ78mV0$K<RQcX7v<~qJe6^|0ICM^7zAcFY)frE{ANKCnV6ao8_C=$zi;T%g+XbH&z=iC zRw6)tB?$qfZ8bO-1p9Yy>dWY4bSm^fqF<`bql`GgA(8y{o6h}qPLq1;H2Y*au2LDc7$ z)=ezu1>LV4zZ*l@6*+B0IZqTB#2W#LR8k(AR6_V?>$a(z7=-=5H`dsIpy5ASG+9!= z12T_)!=&l@Y_1{aI1mj)l%Mp5ApbFcu;i_dhsci?nryuO8}B1ND6+HnXN*YQYZ&Z& zH!v^e(`CWNi2~m2=1fz6UZ^LF7Ugf;hNRUS5q{ILPi0ygPu}sq!*_E!Hh$5nH@RY4 z?0e_VUvD|u2Q|eVvg4`00O>ubX({%8)Jz(o<7?EnNR-ZImEpOls>2v%F3?Ozy5qPj zT+qnDezERop;^FUdy*saC22g%(ETmL)aLYjR${O9US-I^w$W`P5gd22;gjsFc|}^N_^iG?{&SQvUkZbDMN57%Ib z;^INl(NgZHyn|S4c`QpVa@RP3X(-~S3)c%Ft1DvmU98@)pHJ>hxQ%)l5sEPQ8FQbs zUE9fsfJrz71MclDDWzr(SR)gWbYoq?Rk;iiWo9{~Qn-M}2yGtk7V)rcGv@v#_-Bn6 zbT^s?M35vM|2_#&>Iy<>#|?5^6Og<*6AhQzKE_$=!GwS^RuostTg@V`<5+|Ds)Sz) zI(BIfcEBRMOx~9wVfE@7sD15GJRN^vdhx5%6czW~7&w2;``r!{Toh2Mj9qd;?rOjU z?K`ebLI$O^OH~bm=+^h|5^EIMe&dj7!GM}PW^Easl=}%NuHH>=s+k)gtK{dAD!)w4 zuwO&HFduE6r)r+e1QDCm5?~1arpH?OC+}B+nYaWv%N(f?K=$n}SFgcO--6uB-1s=dqg;j&n}#Zl z{>=6s^XCnKAk|f>*5yL`jLkCkpc#`s{0pV3`o%r^Yd zqh{jW=p2pn3|xbIV8}<7@k3+@`cp(DRH$|;5Oz9)eESUh5|ghqf|@mh41TKCGro$f^yX%t0C5a)^)(Q>PI?? zDqfmB9wLtv=;-a^`f0$B~6 zJ|JM5mCatV7!)OZN1ol7L>T!Ysnj%2l3x4Bff+IJM=kjSd`fxDhnUu`gNmKQ2BM94 zB22x!>WN?ox(?WQkfMLT=-;whFKx&q<{CBmT`Td_boSc2&eI2P!nH*~YF(|n3Vq+n zFpXWR!`*dQ@tYHnpo=96p14W+3V5GiNPq@*n8~(z4gAbIHCcC_iUR}Rj^GrKl~Hc^ zPmDS0?F?ee+sO3HLFq1&TI+*hxBloWW)5;kaLkZ}!pkn~jI`wzpP~(N_5D!&Y}f9~ zrPPsiYQ);N+dubM?02|1Mh3e5rZW_k9t9QJ*$-3zQ|ni0F2ALZglGS|7r2kmZoouy zZA9}?HG)XXe2rqVTS)0;OqXiT{(HzHSxD6>m0LEIPPxx(q~aQL)c(6r)k5G=sA9pA zt)vbz`(ar)965MbFM>9QMB~$@qsR(OeS_HGE8FQ6CHjZ z^HIZeC|LWUqG1+->(Khwtr>&Lo3n`uBm1N>^}Wj0sVwM~o2F~OE-A|WIsn01Ymkos znEmgU+k*z~Pdz_+-p}v6BPCN0TlRfpchGr4MP!pO?5V5knqD*N5Pl1TmbB?{(N@k_ z9pBkMsj3MSrOgF>3Ppj@rh*QN;e`>U2Q9CBMu8;0lvT? z{pi2`=WZ=k2N4V@RVon}vPuI5CJV;`Oo7hE%t6G$%$0ZtL7rL$1?B?F!pQQU51A5~ zkVzA_$>715*;DH)!4&=*@CwiNpG@cCOu*dbslY_*%KsP$0lQkoU#MPtn+^-@w-f2?^_A}BH<~06t;H7IBq#Brv`?XO)mmiix)48K7*cO?Mf8?3 zUvsbYxAk6GDVDo^+B{J0+R*p*?6(l3nEn{Q+@Bnsh0JS5R}ZlmYcrOpzBcc@5N|%* zzR*A8)oA$<6bMhho9`!QwC=kGcuL`a>gZht%y5e(E4KMap`RFdwW@XL5?37w5r zPgF#^~APAZup-4$WfPb!OLcpD`0v7QFO2{b*^{3=enXhWKGNdQcQ zyCBCo<)_kwI1L`~kUW5cQZN#&g+ni58_k;1?V@*Gvg1KmO_et3lFZjTq;# z;0z~17o%lpsa_W|G(!WtY8Vv7%nw$8kRf5{yS}K*o=6_f*YU>hVVxr{ zWP6pRbF-?~k7 zT?l6Gaf1hm8i<1Y`MU+*jAj7-5Ez^)QI^y1{<@Qv%~DV>u;j*bn>U#xt*FIOC(y-| z;rT~VG@feeDg3r51FsMl#m{!+bskf3RwBzp_5R#_GYOF^zli#f9Cn=q{qi8=6iVQ2WTc$T#(7rARL1Ch6MiK2>>lqS_ToZA8e=D8+G3Hgj)T<>=?!h@#Jnc zFleK2du6jBuZo0^_jp1n+fFKnOP8Dqls2*2L{gX+^$3&eSro8vuC284Ax9-Ui4lWf z-h4i~7N}u_8`qGUbP0BC=i%X20@5<;g5 z_{&92@{4&bQDT5M<@@`u;h{I+6GT{7tnc|hV{@Lf`|7U-`LWj^3o5FZ*%|Q?mk8m; zS>ert!!bT*bs@laFN!#a$(y8uacsV5ya2H?z zic)W##%=opjTKQYlg28?tQz;1;^^#7<6Bq^s&B!g26`J?R6lu<+K8b{bXfXKreRm{ zd02U)wZgaSL1=h3ryraWRIB3s`g^J60}(y4eSccH`>QN!d&ou%h?-Rv$GP|x%7fzT zj-F)K)BS2#cL}%9kygco?C6&GS-N-$VAjGt#hBr^AR*XX+Gs;CHY*+bLGWyBePIKo z=axy*5}Mzfm!|CGM@_VoGMkoobhS7%r5TSRyVv>CL^w*RYwCvFW^iP@RAeyC0OsqY zZGF_I@QsLUd1l`PWJeS$gfhaSwCdSgSJg*eksp3%WK=20QH!IEthlVbX*J6Y=pUUt zc1On%+}LEitZ{FHHa+5QgYHbvR*oc@Uy_Nm8Do$JOjFpsf!jAPJ$pN##ttE3x2M|s zC%s>45w?7^(94;LaMNb;vYpQGYtkU_X`c(b9Z|uTwkklS1z9p!`pd{nC2|;451OIM zeh67-W62hsMD2r4Q6%J3{g?+F@lRGy#C9g>W(4ou35e;ce{AeVQssVc=c*xd<0CPViA12k^WW=w_H9d1ULbGY3U_027^4?hQepb{Uuxw z8X;oDx;MLbq-p>1!fs6=m=;hMu+xC5+<$7&$Tl){Q1|sMIncU3m0J;vAXOFshT9s7 z2*xP@`mes8vh_qB%oH@$Rv%2@e}muo48W+tSy)(8rIf%@0KvQLzlO2f>xRY7>@=yS zgpJSoIG*qC&fYoPP|aBGcCHR)6uMRi?Fa$h>(L6(Cvtc6pA{j74X50^;K03N&XpQ~y+gGVdi1STSGUTf{XT<8ZDvxU1gEc788!$vMa*wcZ0@+-v!>? z>&}x1lF63oI=|K^o%Xgk&&?Ky~X;z-%C6f^&})naW_ zM3q4!$66d-B5NsaKmH(c)Sa}=${T1A0uov!sXg9vI58hfF%Zq{o(b(2TsUjTgBeLE zzGvyX;!buFoR28@AWSJCZ05w0WpDJssrU3lv1k>-Ip*%Yr^qkub-s&9TSBH+@O_tm zL0E(eU?0Dy&1%Q26nna}R#su{@(-H*uC4@bAuJgzl)K$r%h>gFy`cCZf*Q=UrWXhx zpVydSWZD(2D~&G}8xKkZPXPEVTNZ>rX=ZKY>n_=g+vK;bzsOxb1-REor5a`~cCz4O zQbxj^BBVh4MO(^X-fNWO`LXHulXDLImZTT}o}YcGY1xs}eT+HZ@PY=_>U2ZZ%|c68 z>1yu4>gyy|ai4*mc3eNQ&?7?i*ZGT^?KZSrHp|rK=~PSeeSjvtaWk z8xvH?J0TEDm6|CE2-$;WsW3ql;q|1>GQv$6qx z#S<_Kb!lU24OLL3YJZ>IQk2_X&eCe=mQAHf0>eD{U|5S@bdeAei#B=Mqt;5d*(v^Z z?&HVHm5SBcnm8t+5Z$Lbpz$Z9kLstM_y8p?{Ij!TmEJn4YOIxmz#PZYey=UhT{>rXXvi;+Hk~-ROPB z@+}F{dGvYvuga=3t|=3DIW_m@QYkZ_ylL98w}GxQGl6Bmw2OX5%HU=H=n`Yo zcuf`sQ4Sa*9jjyY?WF#05~F47TqJ{fJ_%MOno`HX%8T1>C*b}?4n`+ienAl67Yfd& zM~4QPI9I@i~(Kw>__h88b$JVMIJjTrTT&Y@a>T}Xg3r73r$O# zIR`3+%3Q^9b~oPtD~Sj1JH(nZ9wMV+?^Y27)YOs@oDs)#u+_4tk)+<73g;a48;In5 zCri?`f(QYNcQ2w~qPVSg zwL9v3FwL2Rb5?NRT_NM)A%}o$!6c9^kxDkD#+2_@JP=wvN6eXiu*pt4V?+ZRs?T|a0>vgNXl<6NM3Uw zwfdsv^W~FOScR@gp;>&v)wJb!rXo#VMmj*GW}as})Z$54ITxd!2xoUGLQ<{avi9$Z zyMosygNj|wl*nO(K}O^)%$NbwnR#UzknP54{JN0mgoCIh0*^p`a>!+Kn4!nHf5?qI zasW%}OQ`V#4n!6?UlvLgw<3vv%^-=Zamf@iECic}? zx<+a;vAs_i4S_SPVDTEB;7!LjKI~wjpwlZG=hxpVjl)iU2EcX>G_J^CCAeXU(6(> zDY4pD7PeYtB!8ypWOJNk`{G1I(;^qyyoC$dw1uosB>Qmdk!5yy1lKQZH0R-Jq?|nC zra-;^f}T(=)=@wpGJeq{G$=U<^FKouk$%R1J+e#`r*+Jy&B8YFKY0~UH2Lg;r#_4W zTY|BxBA)j}1Kaa)O#B2pu?1^`9k9^X(N|YP6S=NfS&+BNDkc&L30cqIJm}iV7OL7a zE)=aK92yZ1iW=@T3+^=yxP!s znYDk(y6xps`xP(sifq61l7XjSW}qAA7|rR$`3#pq51_Ck zP=xluCy^z5tm4#nFXiD&?HB%e!5bX*!Enant?e49Z@0F)xMEAL3%_-3a561CuuuGf z>ng_kdx=8CdK5at61wkcwO^|0`6-UN1N)x94kJ{d(D_d%hRG{A{)Xi0=u2fwVtk>A z>^IZFBgKx3)WG2ua7d-uNJ z+jBLgTv(T&>8G4iH*?*MrXj3v#%K>w%G(*DiYOu=+fKE)5UQ3NByZ4-(lHM!dw-E% z81X00xx1=!oE`bcU(D5dWLkgrFW42Xi-e9DTcX>eB{_49dGvUN3t#yj69M44+A&vN zkgH`Q@l85MIS`dFs4q=z*OYLL=DstVJ`9PVg~B2VOJ|b&dVv>0D;7hmxDYL(?jH9d zGg*BT^IYWt-Pt_5LRW7;_$^NMz4B`DnbLYW;c+uwIa2|Hx;S!A}*GL zGDP}5d;V`{rDIZIwZX^%4e+sVHk_)^?^3)ca5EmGrF(5OrdB9SEB%dpmWTI^-O49> zHVW8HY*|-abrk%?g|wryWXo$^59+@eoS>YcNXL+g@-IV=2b{SZ_NNw@J-Q^^Z+$`= zdCX26f?3)i!Z=#mz{&6NU7niYk$!aaWa!1h*NT@}$D3*_<{no7`p-N|(X1*&oQTr3 zWU-?Zq}tzE%?zZ>bBV|#=83t|s~M?B&?|p}$qi@udQn02+Wm0oZyDf#+Domq+3wDa zGeZD%K!(^NlFE-~ieMk9lKWZwB&k3222PcIU_Nk+0lp@fCtH$lqrNcn4>M=Ua=$P} zK?2>f7Xyjh<8SQ-l)rg(E+=PpZWvf$k)oTvFVmXiJ^W5Wb<#q=oZ{Y(7eG(l_>?Ujnt--&joceoV z09(tEt5BOc;Eq&sYsS2KaSJ19cD%Z_d|CST&y69-sHTY3r4S>47Wo;4U+pqvGPzco zDhvXzOeCn#-~s25AT_ypIf!J)k}whzIz+aP-N+u1j6s@hBDW(&Q8W}m*1IoD0tLgcO)s?T!-7<=iGs2E)t!%%AGTiJm&-BksdGGYn{9ngd~QL0(dr8LNpa1oAeB zR3w$p@{vSxvV}PsA4sf?UL+B2^N6Kbux7lP!ko_?lyx|s`VEF)@0B35Q zxwQ*{GAQC?UHo>^zs;oZ=CvlesGb67GNi89f&H&}6WZ;8I}Vc`6TWfs1 zRs$u#!(h7ZcVXwkS}$ayQNy}JXN73tF^T`*k|DF*Dh|2j@fvO_y60Rhm^i3Uc9M?` zw)=RuM;wyedu>uJsH&W&6H4>Slttq^b3Y(u+c&>`PNO@Vv53Q?)#tpZgk6dsa>?PZZt)yl8_d?y1d&=M0l6m2c{^S6QiNAGVK-woR|wU5hg6n>R61I2wC1+m#Hz(m<+ ztT!rpTFP#)(4-k`Ryn5{BWww*HcN@ySNTWom#V#339US7%!aD>hFQ9wKdSBlL~Vvp z$OYJ{D}sZ9ga1Kw{W*RwH{u7LVc#W_VZICas+zyvH>}6Ed*$B#XMa7g>X0wh6CoZ~ z`1O~(C{4;lrQnMwMoPAjV$I@3fCM7P>ZL$5LuN&4*!IkV`=!bo{oBw)Q;;=-vAq<< zGWsp%dL0rQ-Y51t?~%&UX7;F%w1ZB5tm^n9@tS(0ga*V`@!{T~*Zrt1%3%P#Wbj^# zEJ656^X(SuF1TycEuYEL`4@k7ELlwqvAH(LXieZHtcmJHBn>gCr-_OHK$3v$a1aj0 zo&>(t^d7`tskBEw0m1h)&*T>|qa!?7_of#5uWmT z5huiFTzC-aWOx51H({IkD-p6(y@ur}BF5i-HXcl^eT3&pl<=*kRlN{=w)cDG%U(+K zXGA90XrB6S{_?E-$f;CBfI@8*O;}8eqwT`KZ)IY2Jj5X;#BjB*7qZmqYVh-D1j9+8j-E1_xqbZVCOM5NPrduwAMu{u$|bM;?*L!dNc1~_!+?VV1P^(3LY zwd9~XWunpK5dy(uv6!eeSAK_?ThKVsJ5Z>uKB%|D88qLh_FF-%W6CtW5bS?OG&zd9 zwvBiX8G)OYU*%$gSMN{spYd1*dkhNxKv@=4{ll*ep&SUx-Fq|jrx|YOIv4`7vwVgA zCrpHpgARi_z(s6PZxoiGL}v_ZYdxqMuY6ucxh{}_qG zbP6oL0}Oq!V_&%}0?Ml__P!VN5N)@lN(&^?AsQq|-nSdgvcUgL#Mkdt#_cjY&z*m) zAjq3zO^7MNx-|l&D5FCa)a1&|dq6)3%TBWYz za~uHh9Q@)BnD&F1Bis4e(rt2F1z>9^6pT*p=sd30^HgNe=SJ~c%RKQ9IVv$=x-8q` zoELyK*q*W5T<+a4z8lcJ8RF%8k#KuY=Huwx_N)H&aRJ^q@kpaq?E0{s$RVlX15Ja4 zaqf!waBB_)zsQXW+!96%dI#S=|j#zS-m260RUgoKVI!eIDkL672*rwnfa@%*m9H*mL`e#prcD3AeZQ;CN$A7 zi6Veqhw@Po{=k++SV%B!yL9}!AtsgU@PvjPu283tFwkaXef?{ES9-M$)eOM2!UpqW zp^(w4<*X-r^6MH)N4CFaNSb9OXG`pL4q(9q(}_VdmCh$OZogxgrQKhpW^2QhI)#t1O72yX;1>WJJH3O<{Oe_#Xeohen^A^@tNqIJ z_(2Fd%GgaKbN<83`%&X^MpPEILlBR+F2^qoMOfLpyB+g$wWV1<=WDR9lF$YlB3@J{ z?|LdXKRdyw>7(7-d9_-soN;cTe-FCj-gFL8G5|YZ+-1(fGy#(eQlU2a&eQ&eMGo$SOmx0LDAnDcW>Hv~O^r=^%D;X20?**1LO-TeF(Kr;TaivEOE; zaafU|-S%SQRizj8@APA}%s`)h9WUuBfJ`mW>&u_yX1o)*O`2)q^@%0zQ>>S7Ua8Au z_;%FUfpiOIB;R>L8f}dUiG{cX&hs__Xv={kt6!&`URdv8H|M6aT+6no?-hP>wNzE# zqU#m-?#qo?i{dPF z0xm%~=|*o&xl^#i1U%kSiw1Eg+Hs}6#_>b; zuILE0;t@KV2+Oh!RB%#m2?KM_VUtmU2X)qDAN3k+=;k&UYE`d6x|vPm}seMA1*9r@OO7cz2G@1dEp2XEUKai3S8GfDe>5k^Zi3W&w5Hshnip0 z7Kebw+Mg|`TfvqR_dziO&i})YT@1@S1Gx>MHyiu#@W>_S?-uH0%arus(PHxt8ho z-7ZH}e`-mn>`G8y+u!0cj{LNqoyNtv%fB3w418uyg?op8YI%79zpe2QSylidTb}Q` zmkRKmtq|`>d^hPiOg!ih$2(eMoUT|)w7Ilo74C+2bhI!o(MdT}Z_2QCl9^Vr-VkYj zXU}u#!)SaBn`7ml<@APc<(%xMwqN{rxYD`#Uah4D_ZYW^9TD4onU@r$-z&t&bjE+l zMR-YBJc*Va#<{Kn#>w0%QMr5(gL{UQRu_RY4n94hDYFKok%c3Y@^h0`n9w3V7h%SQ zSQ1tDSk_E88!Q*0-s))YAyKB6H4=NXxjSfQkj;6ukmTAzd)!N@k3zR}`h0p-b*8s9 z66Dl&NHuLbo~ercQ-90zCH>enWu{jpX2Nq5J$ymLZ*F7&5d3dwaJG*YHkH6+XJ+IY zE!oBimb+Th>%IQhgYvTr{UgxS3)xgUmp5y=;Z7wiix;Ve$+>s5o6E+T@?mKVoZG<* zyEKIiF^N6Q*rUg6WzrJd~5&X1WmVZi%FO22mhV}IXpPh zopc5ujvWM6&In%-Z?!SNQ{DO6bKIkB0aWmNTK^u4mB_{(ci=pB<@D=Hk)Xwz(SQ_9 z)?%eVsub<@+rb@JWZKgamj40Fz9^2tQN=RdIrh(KUM%w6QXjm~CJ{n&YKIW!57!d- zg`63lq{3_Eafb`UDQa8gB;-Ac0tZQKXmnS=+r99qAokkiN8~*?lpmZcJXd3&$a=Wo zezFm|3h>{gVLUtR>WD=UL>Z_`Nwfuzu7o1D@e=lz@;aq&+j_zP;|M9+Z}ASK>($nD z$Z@Hz;iN>5DLZYi(+RUX&#v)Np9ZRWSRZ1U8IF|}skxB82M^Rdj}S#A;2tkH=MmyJZa{XCvE=a%Pyn9#KKVXeOTfIpvJvqW- zx;_U?`)NrFe0w-rpsidRlh)?;-brjayqsfsWeEGTHTeHUXj%J#iTrQ;od5ug28@d- z_1GRP9YFk=B6bj|tCdO3Gazk^VV6SxF_korS;M7*x%Ylhjsv~Kj`WuCQJ|V&8+c`s zz>^g59XDw9r45t4TEcx#y+HPOmli-#1M61%uoL);qRt+-K{al2>sL%P zD5@g1F_k)^#4T8Y+gL8_BI8s$kI=pZ|8xfBq<7zydoOri}051UK7 ziEHYQ5r8@i>Po(=?~YeMQ!uZ84~w79h*bIRzAG00Lq~Y8lR6ynxX+IXn)a0Pfob#{ z9Lqy`J@8#2xBWv#+~>T8mMK@bP=}qG1AB*M^^DZgP~?>KeeOKO_F_&iVOxn^6gXA9 zH6a0p1C$5}VrFgpE%q#c z3nHA+1|dADA?kPSjV~<@ZcVoAiefbleTdlG)ABTwhV04T0e;9QI9(hfm;-jkww0KRH^d?1TRc2Gb z;$nidB;6*e<8fk%|5HlBFSLuXA1_jIa2dJK#c?tX7}RVb%_ZR7CTwAkKMnPI-)7&i zvMHIuKs@`=xP=b-*-msshO?j$uln}@u%Vm^gI8jR({n{6#A*vY& zq;b1mUC7b{?ii`s&07t-#am1r^&Cj!WIt&-gcgkZI#Tq3cOwgBYmpPs{evWZwfa|f zy4x%YWkG(2xX{WgZBaI^3aRp#i5Dww1+Q3M&e;XwFGY5qusR2E5r!Hm2snLHK&Eg_ zTay0dy{^L&g&0GPG^BZ>Fflefuopis0`wb78owhg*gGN2Z&MKV1?Q zxN9ri#!x#1b5^|j$nFIozFHodmSw0JyD<}SjSj52(~@RbC|4@=kXSe%e(XO%!k8{Q z`xcq5ubTX23+Lm@uF2BMi>v!2H7g?yf>m6AsaEX20UY>0E(^KH0t5*n9Ex-1A5jJ^$PQ>eNvPsUA%Tf z&Dq5WgjiB$jA%FKW}~d;oBADeUCZ4J)Grd7GkzV7tyd^S+NdU1O_>dWtw#ZY5^Z>t zBULQPG?}={0WRbk@a97<4f_n?KdZdRnP~?>CixYMw(MLOvY8cI$*KF`tSXP)Gz={D z8kq0Q-DTvafD2-{1B9q~w3H0k$N7wmh59zU4$2?GeOm8z>m`&>3vFD81F+~vKSIm( zbdIcS3aETwv1%)`W+YRSzXFN9S1;m8A4-ytq`He0~y{r;EDwv46e8NFUCD&9J9g%efjK#;o4ducP<+Smvx)eDL4A)XUQO9jP{I%O=|BJgq*^m&rW2!hm7S3*j7kH3$Ckdk=Ar4 zS`DnG3fU%N^yITO| z&6lo|4Q_Rq+Iv70brs2cKGGbaV z7#6FDj(NGLpC0ec2pCU3P5ibD+YT~WQ81sqtZs|#B~t!w}sWbL*7=Lh~o4R z`l=m#QJEF-GYMMAUAUH8`5XnXmWpk ziBM0Is?GJz=ua+^wk;>aXQx3C<+${^o(>b44W>Va(f;n=dcDkg5xrk}N z=9rLkczQ8hw0G|Y^5=OrGZoQv$6D(A1r%~rsIGzZf zXb1BwcdB@jbZ+5Ye|;k1Qa*v>iu#ni)F)GlBJujkmUDtdBr)-Fwv094?-?CcH(^O# zhqrahPj4A5p-rQ;(04e1hfqyK4zwN>S6c)NxckWmPnT{>t0-BUZUZSPA7ip>`Zs5T z6p7djo2yOtk?smAs%?jC_f`zl&ZT5e#Yl~atht~A*FQ<;6A4q*rdPJ1nK~-PzKP|U zb!nH?H7UlROwJ)gFPJTHbn*&M4>`v)3D>dJBcv?^XUQsFb0u2<(I-t3VBErBG0sI& z<>eCl4BVZUJYk;ItErs>wIbYYARk6 zse(ot87Hmr0DWNtlgwv1UJt%*&S`;L_qC!vD|!2Yc7ynYPJG22ZuKak6>+|2-`h^D@vB4t>WGfDd1&8H&ZRlkPGm4gmx9ARPx~*ez7SfNyELEF}Fav{Zq)qj7HCYr-E41+t&M6|iH_C_Sz3Mq_u3SQr+sHmdb4wX)znJji?`=(aa7g@xF;v0y!xGJwy}9dx}ZAP zsqTU#8vX7&2QE|ct9Kx$zJ()(L5zmkv9;3!v}fZyO~zrdOCSa={W?>LHmsNWA}SfxN-arK89;pWhCGXr&`IE@luj;exl+J-t8QuVRJM zMsDrV`@M*pU~_Tj*?oF~0pz?Fk2Abs3hCpbTBxQyGWWwn+<#rXKUacK?11`P>K5o| zO(+AOFRzMU+UG5?!tO)GTDl*A1Fi4b&_OBE7kTNP{o9?II2L`&o4pe0K&>TxiKV~H3QZl^jVX^MfAZ_J;vMy=pfqfxoO1S-QH3%xA2 zPX$$p(@6wc1FD0p4(+8j6T>WYow}JxGXCmSEy}t~pX+JQp3vOX$W_B0hQrG7CB}LFTnvK#!VRS801zbTiD=xRgd$!hapxJ zg`FkLa>bTj4V=YuXb`!8M|`>6B{b8{GX@2nnQ}bYb4TvSZ+{p=Y{hY(jPgXllkdj` zt!OslyCx7WDUzSx=a^oDzgjg(mw{md-01&2L6H&1#y(W%tcT~Iz%Doi64@rV{OfAEAH zwv15Mp9u*A#Q%mhKj0n+-d@xK)0)?XOJzgES*k#dcndW7gS%=u>8*jNA9cANzjk9OOGTkgW3q$UlKa?48zdA7!@+>2kE>)h}4zvif;qz1Eu z@exh0I~D`NxbD#cjO;QPNbp@T%Z7B>!PLdnD>*4y!@ z^NUwk0eHn*t5D{O7@#=@Rgai<)e66czzGoXAR8cbVH~k>^P*uZX(PRW7js79d~0JM z_#@t%J>Qq{C!S%2E6PVawGK1Kc@mC_X1MJhVn^Y-YvpvMF)wyry`m|vgU->F;>kL9 zSU$pIaT_EoGN@OetY=0k(@;x6y*#PST(Z$SV6fQysDciC(=TGQ>|`Op0M|1LQj}3J z2n?T62Eq`8`N)z02kp}7X7uZl>ndtJrdftbLSqhwTVXImLgsnXv%h!M zk50&y0>1iBqxfsL=Cqe3JTKn>Nl@*s=K=b`Df+b(F}XCT8{9uz>x+i+d^F7RUcn*g1w*@@?xrw(XA9v2EM7 zopkIK+ji2iZQJPBRwtdLW8<#>KIg;T=bruCud7DYtXi`sMvXCk?;|h_h{2LiH?3Y~x zLstM7MhEo!_sc_@Il`wkfuDvKg)b<3Xx>2rX z4{k=V3sspm=%006Ea6n~vr1io*mC1cxclZ;9rM&~r;LaVmzA^|xJdkIGgr?RXtByjSpZa8 zI@nmSXqq!@$D#hgKRm-n*Bs?IjC92n+Qsow^}g~PwQD7ut4dFO?6M5MH0J0h#cUga zQ|N8+DQ0C-ZYSA+F4{R+Z;sS$Xn0w@+aDdiSpi8lZpv-)s$MZ~q76Any1uQbnqo&{ zpdiW~ei3`#Nxc(?xoWu-o-({d{0*3*b$|w+#=r8zE@L!MHEY8}+CI_w?QTE-O)kUb zs~~^iGAkQHCoTPf!16aC4yU76lSieJsEiCYILGIi78P_xxzax`ULt$J>zf&liD z9IM!}P}&jW?|283krD$__uorg^EOW6+t}QcifpEOda>Syl+t_h2rCv&a~5pP+9j*Q zc=gdpY|O_Rc@%lPAScmj^;SSzxEH70^~<(n@7`0gLvcH&-fOO7G0vPJJCCyW6m|(E zK~3J*x?h%R&~aA49o75V^OGy*~>cE4{}@kQCnyZV`}d=|%>Wz*goSF!+GbinFaO}lm7 z9jJ@Rt9^g7iAQ|lG0j)AT=U6PF@Xn#v3=>(c67`|Q0uHTR0coSJi; z^U#n6sbl$e+Z_{Q8HIX}sh^!mg z{nMS-;vXu23Pq#D`2$}qs~`GcT+1eF=yuiCb$#kM(AbotM6!lloz%A2VD6A-k=?il z-?q(EV#44!EnNo`*hbzuFc%)I5(H>4X3D$B2{3-w>f&E~?)i^R7$JU4H>-gK4`!%ZT37ZMpMHADVGW;9hrH{22kW>v3CzKMoz{xf900m z8Li!cWU4$ZX3uy)9FAIEwKSKqfWE;)j@`G+5Ci-NG(HQS{IgbA%=xP zv5%-oNI1lhx^f}VP@cvgHUa;Y;W7Bm5!&NHrTv!kH( znYT#au;xKC2UvC{sJ@`x$~I(rij@4$WbowA^~iRu)Hx^WL_833FiD%VR{D`pm2XKJ zK%`3IlsZx*fgR?&TMpUx%DU70MS>2N>$9wQ z%$YyK#C_FuUwl{|q4T%fsU@6-%I;U*39VyAYTYdcQzV&$oAb7y+raM1B)YoWoK^IB zp0H;1@~i;--iMHKzwky(2L+iA%YcLA@r4`#V0(BHak!pX@Mr83XVru40}l|q0?sa6 zzuNjJzD}X(eVVIR3L+1BOvHZCOXV}W+|8=#Bzih{qrJmAp=!cAh?*Z+>YKc09@zr z6%XGR&fi9ygqJbKN~5c&R8{}1m~J(NpL>5qlXo;>mumlgbj8X)pEt!=gJ_j_i5Rn-h&-n~&W|m?Ovi`o*(%|^WtWz7`QaxeTTLSoC zRctRuG(G`bZdT|%f?M)?I8>6hv`4=F<=^|*Oax#0Ql3GWpBj>RZA7ErbyIv%{nlnH z29PM?pxywW5JMd4n>k=gU|h`U0We^c|HGy0$pt3HaS*w>Uem33j@h01Z1}#kf0#IXRror|ak0#|IUTP0;@G;`t7WYpk;_6;x>R&1| z8gLp#>TzDH_|V5=QQm!Ce0{zS$HIsjAO1DWvlIV7NJ)+iDkO|F|MGGSG3GPu<@5VG z*+*+*6co5&aa_BM&WDuq0!%hupZyDu?(#+U9{(s9!(8${hi^KF*~{{2`LTF8)t4s# z=veGMwttf|>46Am;xiqH)r<0v6gd{{c=e)%6Zx$nbDXpyd>9bW8s3cQk9KKOg*mn1 zO@F=*f#!xl@#nPSRmQP8Tq1WOM4b1wAGv+}9(}TM^**!ly5kF=S*P@u{o!ZcqU8pl z)S$9;r+`0M0G{tr@3#`eJsD#2h{|S19%Qf7NBybjp*i{Hw>lSwmS6*V%J+t%JbgS6 zYfi%a@|uZ_AV!vVWmo&zdUu=@n0jdC43-;q1P-L26eAR-jKH#)%)HR6&fY?f^gm=R z>?>Gx=C$Ifa+#~Ns9?!U=1gO#XoxOK))@fX%tb8&;cYI(lF2p%=>VW$o0_fY zRfeZC|Zk7-V>dfS(9)H+E1mw%C(K6OL%-O+oTJ1JMdPbO@75ht(G{b$JKT zQP_@r-dtzYmQh#n`@8XsdYhuV)e)CBL$aUQUtfv|-P0Q9h8*%mv5jb@;sCfFZ||#{e{og64V|Vk+vA$DydUqA4N8V9D$!sHI0Aqt zj7^ozd7Q7b)&VR3(tn_AaB?|aA}J4nqnggO_B3O{4(R`_c_dN676@Y|61bozE8GDg zSuDUnQ4uht(#<@!%D$?wtD2!WDmFSDw;q9W7_7(QL_w{vS~qYU0mz+~c_Z)LW&Iud zv*$W0b=rvf6yew`?Onh4&Bm{SaF4qoHi_u(x{jbp{-5rUzSehwuQ5;e02M;YPfJZj zBtEon7svNT)bw%;_P-bOSgGkjz%C|X4U+57FB)W9nMNqRd3oDSt7V*lFV0z=WdrOT|=PcjyS9$1{6!i>~PP(>$0IJDY0r||S^X4NfKtA(`1qd%; zJAnrs7Qjfpv-aW~ckjOm&75QbKk&^ZfQV+`Rb6_4S9KNuUpwnRF3=5RKkIC)vJ6;N zZX32yLEDJ|fm#NuQ5NrDX{XE4GG(VJI)*W-n_`dzw*Oyu?33#%TP;CxJOg5+M*j;> zt@!()d-L^=G1}?=ABQNM#lpjc0Bd7kta;?|K6rEv` zOxETqGfnP1zRmIAM~a z%~R6{-AE|r@S)B_%vw^T$#>_(OJ*ssOUeViRQQ~7!Q`6k{WT32NsGVm~kI#e_Bj=_FT{!CJ`=`c_XAq zlMW+YT8WNLdQ;^QHs>hAavNZSl%yaELl3w}`NaPOu=VT2Q2O&cdX49)lK2-JQFRXiRUf zaV(z%1tK`NFYYygEr%$Z16)q!mID#zFaj@htTA`Kbg$<7pmDQJgN;ZGXIb%czm8BbibY7HAT_Xz z02pfWsYmbcME=*Rh!c`--7%6f{FmiVXZkvmE(Gv(zuo^r4U33uxcaas$DHtbN!=t# zQ5mUo8C^@!{$%mXl_e5EN$_^<@=y&@D9x?se3z4ue{S&c1x){4peUO;`jhhXxH2s# zrGb2Li1Py)j~H|N@-U@9nIYm|?-6RflG{s%9|6zNG;ZhSSOsWs3@YWJ!Ww?Hrc1q4 z9bP#2)p|x4sgod-;sidP%o_(-E$(+OBlCy}8DUQo1LuLTZly29p~e%Vj+3 z1^Jp!zFWC~&)3OD#R`g+~d(d-2v!$MXo5 zc(|a3sTcQqYSV>rZtA7XOGh2#@kayRG^@RBu|FquRwKLD2K=0P(+SJR`zg}*oW1n1 z0lo!lC{K^LpJ(+964-y0+!plcy1#wUDtmo{25`-g5Hy8t+8T6*uRMD}mpm4fz2@i1 ze!q0s(gx}fqBYGoE=Y5KFQVw9SuQ<#=xir|&ZT>?*T%KYN%1>dR`q;0@mitLz5C0y z!bK|$h+-(&6i+qPhcfu@nHicf&1z=y=r4$I8F+e;L*z>FKf4z&f5~mM8fobl0ILv= z8hp0|=JDij77yEI3yS>YLm%MW>?YexX|C!0fN{-xo@OO4Gnp^I&Q^)#`OhpqV1D?H zS0jx}FA3wL@6LUeW)(Zxdw))|{^cf4?mSNG zbfXt&tN&Q;wQ0w!Q`8m<0>DEo@LJ&2q%}t&%qI@Ry3_RWkRv?DOV~><10JZSJfsep zYx9HG!-gJpPF<6Vw9q~IPSMz_$&IG1xF>y>of@B>^czzyxhYjf4)?$!mENrmAW)4# z4uO+z)U@HVjgZ&1oowVCFke$0R+D!5!9K+;IbsoBH&}f%=P7^@KqdKdu)dVLqtRY6 z^E{!lPXbRPV8j#Q4H%6#e`EEx$;E)RmU~5|D0fA?DO@LZKoq=Fbi-8qW%?%?r!id7 zB`Qi6|DXnGrhO zbs`aqGD%Wau9fl@;JV6t2%(_^1oxE=YVZE`KZbpke2W%GenjPeRE<)%OCJU|*~g5R z<~8Ds>=wMmv1{?0pIadzJfy z0N)H+&Ia_nKPQcjl)#8DLU%xzCDE{du7qY{ZeYq4{1+xIU?C#zd{mVMD0IUBZaHFTVZMAyEA&Gbn%D-%%gv#c4zvy=(m zEbR~?SYZv9%}EO}>wxJ3QIzr^r`tPru9^!Pie^%SMOOLr4}xT?bsZ;ZFoZ_p%L8nT z*msvC`?c?&0MH=R+UnwsKe1LMw%eDI6yL8^3|}d5V(9&ktY%CMlxv(|@ilviqe2!w zZ^?UmkQ$~Ge-LK+=z1snO*NGC?Lzpt+s9`1RjK$9+2%+gTF)8^!e-bEI zRxOg?(}E0ij`X63?GPH+WY{u&v%wl39h3C83&-!8?$4;lo*-^1&#P%k7v97zbV4&wg#Ey7``M$E0E z)P3cql$9b)4J}?QDn)D_|Hqeq!PQr@d0U^K-^;^@Du#LB^`@Y~=WF;TfWU2$a zCiCxB;@<4GsL?Be(ot>fR7qLNc;{o=ZedUGzSe%?N9euLew<+&ji zlX+UaveeUQ-^KsIxcx<-uhyKfdg}8ItS>cW%+~BPzu{F|s%r#J&1?|y)$eFF4!d6$^Uwq17O}!ZgNR4z4hO8*dbDA`_3-^dX zcdnNgr`+g{#jZt^)_TZ-Ry1JS-N=emYY>Ks9|hYjz*rE(ywps`vSz2s{RsEo2@0N*RDG~wH z*SB)ZF}QAixo$fVNhmAy@ve~%Qb5L$sTH@d<3wIlzUvmik|^01f+&hW*bL<`1m9&% zUvk*ko$&o!8+ZHsRCObla}X>`yXF_q@G#Tj-yVc&IKMy z`OR)Zml%hwFDj=KJ^02Mb19AL{jh$$Rs)#si_qWQQ5r_w*!d0+Pxf37D}GKurrbp zYYLUK|9I7u`|pUkE{tMack6f+!s|z+n zQx@}$R+>mP*zi|B1#Iq_hIYGMD54`8M~|_bVe3&)r`y`^1o5q>yGl-~AC6w?s`+{% zZ@=9J3qW^QdLqTgym}myoA^KoGP9B^`jjBg0ec1<@jn+jX~C$>&+1jjHZ%8^x(lrx z>~sW@&lqW3ptu~o79nn5%v%+|x2V`|+9|S)I*D7u{HAfl6`%-5O=xu!O^@g}SBn*R-A)yz;j(bO{Y!-% z3~=ZqX(tnJ6FChNGLRR>URoE_$n4=mYVMPUuTwd)7`Am80fYk6C#GHxfco$w+RAB$ zI*|$&moTMH)ifgDG*RIMeFEf5+9(9jodY|YG>kCsn=H7y^sEep0YNU8 zvXj0Pq!qN~O1J!YEWb{h(CN?K;p7_axVU*YN95~*DmRe$>kFoc)(5L7Z+{R1qT1Y2 zX!s5WW2~HhhGB5{k(wqrKc3k#8;f{k@PWjOzL$cta`mYs4AQZxzxk1}o;I;Z+O8j! zTDln1eb1zog3h}?DDCT6x~Am=(^k$OIYw$N*u&! zK`W`l6JM@#oC59iZ)Gxsh+R~TQKyE)KYmNS;lCv4^56@h$qkNL!p+9SdJXXg+FcQ= zkX;b8Qn#QsQP28L73K=Td7Ynrp9kwOAW|#dNykU3hC7p7=f35YuTRGY^g@qU9hi(l zUPxJ1wkNMI%RNBy&>4$#?QeE2>E^$3t+`A_c+Hsyrhh7GATejQ1gkN_0?8X@eQLs1 z4VAZ9>Ug;CK0(2p(_(+{BV$lBWGalD01e^0SNMd>d= z!M2xEk{hXlVm7iz%94NsS{nG4q*{Op`|Ty~c@8|xX>Y#oE-dsr2WU3WZ!{kdyaY%5 z=f5*He%b8!X`}uwWZiPnz}ZmS_$eKtr+E%5{alI57$q=s_?E{rR{T^)Og82!zV%LP zKj113LU#^@s6)C3j+-^?W<+tU6xf1(Wg26{V#y{`4OM|e5K`6;(DKyHt370tb{^SH zR+#@9I++`R4d>-!jAOW2YwUY;C&x=;0U!ccu|lOH+NJ} zg<_d6!xLYhjbP|}%R@IMQT*_w2q&%^QplgEx_}z~YRQQLcrlvqo3J%qh5|I`ohBIr=A!eQJ+=N#dHzENRgIj@6ZBZ5IpUfU*aOqzqDMi6kg(X=b+JXk;H)An7%F= zM_JWJsS{0HtLrzgijQbk0spit#y8{g?D;2Qd^BLqtm*pRGr(U_m;c&<3rmb0bIPV$ z;{zoRbjlh~Lx)`z_~HZe4OCZ2GcMXAK2{QwTv~P0b(sMsr}}#8((sr3LMslPN!j?p zns=#3Q{LrZ-1(xt6QmFzdQi?#5MIpO>x#R4(QE39)WQ6c!+v70LO^>0Gy`@W<0{D9 zvKDaR(xW%=js6zK*pMk)O6!#U5@+rq;6)|&g()5=nktQSK%=9Fb;DMG?-OIu8O<>5 zCYlZTd}-ExRYefx!N@VqimRnHxSZ1bUblZzw#~B@d;vBu*3(!nWD!@x;JmytpIs)f zdt+Zn-KU>BEgO99h+F6CBEGS^TH>#N&6V2T|uL@s=OoYz~-=9Bt7c#Z?( zGcxtYMIaK4B%16)>ZA&!)Jg~$n?47T4}f9^xVN>%4R8JOR-&|T`wIJ5~H`a;E-+)@?frJ5RF z?5In&-9kLw-N$}4+eqY0VsptiYMIs0Bfzk^DQp251L=Nh!dt$Mp7mnEZ(a zsBpnji^e8x?|Y+=1e?a~a1DIZcMbsMkButgsr69YbRC4dYpss8s|QrS?aFZ^a_r>(J5U#Ai0x{mO3 z%Jms~iA9I~Q6E{p7BK$wW#LNB0!L_p50i;!-uQtL@wKvh!scG;rqaP)OkyumdZC}r(^YdkmI0GLNFv@ zQLFOf zXABKU|7le|qj(VR21#Iu&dPnaEFYJZm+*KAv1?q8pdQpXFun*vK>^B`-{jwm!8^dC zjK*qMhHpF<%!q7E@#32DfsB60>X<$-2n-bg0qrd5Gtgkj>D*Od{P6!Gv@@|2vjd|? zfmL9Pz%b$e5=8pHsO%j7MP&!t2?u~u16a7ZIQ~tWd0TJY;kX^u?@4p(6r^TfWh;QV zzoqLh9~Dyq^7w*q0uod17xZ9ByELu7vgT#0B_2^U#_G^PMQF-P=nEjf{VV^+!EKwP zVjq7f!HoFy^Jjcn-{=0VVLmS|=2Yo!e!Gd0sFy!1P@MS>1-~!g>-B!B?&9_V(2F~e z5f**?I+(fevj#9aDjJ8fl~Vl>6!aq(j`yqUzvG#~zp&7^49Hb~ekmca4pf`HCT&@k z@sX{OD&l0`fjFB_-_tX&c5T@9IFUIMp?9!YgkfQ4E_ur2P37VwS9S6odttGstS5B1 z{js8F5uM-$g!mcYIZx|~+vcsW8vLP%WS=7+TNK4<)VR(vPZZ5WUXMPb)tQnr zbOtp}4;Mx9ssf(-PaAvfqC2!Y(Q-C?tT28na0YjDHq;b<=RS8G74@DgNu8$K%I;4d8DWYaAGeaDDOA)H zAMwTr223*_tk3zI`3!Ym{;#**W%9rLvgJ;^txtl4bFbQ%D%>A4rd3A=n~pk&pA#R6 zsdL(;grpL0!HA8}iBX9&z+2#ne{OLIv6PdGNiwl7zm%#$k)_z?D~gM235brAtOr{N z7XWa(LKB}}KoLW&Mm#=o^}OTU%w&cTcS(X|{)!;s>`EwrejoP|(@`EU8~vVQm#;X2 zG;F5}X?LK9E0Z8|7BMfk!QwzAlXE-ijNT^2!lcd+6)7j4Q$@3=_!bj7YeqV-btb2_ zNuB{?nU@J&8Ww)*+whytixw<03=cvMGX+2`WQc|-JpQ)j(COCea(S1DLVU`G(v3g+(>Pi#$!LlITy=;Gw_2&zPXL{ZJjcL&k2_FJNP8TyS2QTH z3qgfvH5wviisaXENAirHnAuf8CbfiOp$aM`Jg#(dQiE0cIHV#4x%C`X@dBl=6eJ)} zM5I%$X^1#Izidt%EV6=>B-yDVAV`8_{!IIK^WsUCteEhIq*|6^Q3^E-$>c>bD;RSo zXry@8aK$gPL0Zw+pn)fs#^B2e%7y+4ERlJ0f$j6LLH&cJ35%pN%Ir*yW5UEp(N#h; z4{1@J8?RV3oTRy$b#t_18uZLsEH%Ii*iFYW(s$Fy>baYqY8Lzyn}&9$9N&C(bKl34 zgV@k?3t5n4q_51DJpDpcdTc^d`=6@z@~e+&5Gz=4#sJ~+AJ!~p6uIWSjAX+G9f1=z zH5VmXU6F{(M)NFoK zm05>_7C*dvZizg$O>5e3enFgI1t)NWbQKk2m>^7)xKq*wJe=ho&affZvB!_^PoU#d zzq;p?91Flkv07^#{SLrRMRRQ4xIf+`3;61^B~oKlhCui%`05vY`+2el_$EKSiv2@ zpOUZ?l!NKhtuha$oKx8AcicwmAge0v#^6`dJ=x&H31?g;iLP=M56Jd>@J}buf8O+c z__2E{jc=PB`wTEwJBFuv<0cRh;#b?mcrQ4hVvbQRvR??h`%>#pzu|u3*qtPq!)enCbr&`z_py1^Tq9 zVH<~p87eb2U9M$NHR^D|y?p*AX#X6CmeFiBdn?fnK|#rgKiJapH=xyp`fnS0#535s9VfTLmxJp#-)K71*JS#;z;95YZf#3)6<&md~yO1DwF-=DvIk zUN{~DDou?ZI!d2~VwCKztL!+tnp$DsT{d7M8$C_ukyRk1^~{n;7yw1X9`Agic_ ze?HK4nXx8}d8bObQ6F)I(C{U<=;O9U_jJrQbf$l}t0zf}d4Ovuem22D8v6+_L(|(M z%SswSlgCwSWy``gBv}-ebG>2}`ZC=bhe4gn;Xm|ePdxcUCyhvD2vN3Vox{?#ZwSEQ z;GQFavy=#jtBT`ZGzXr<@XM`nO{O~OHs5A$_Ee-@`t6H2;=-71>*dbDGpRu3 zhRG&Xa{Ym=M)a}2f(Atu%bGp?$q@kfR4*5YyhXdIcOV7-IC_mi!?X6Z&#T*!`VgSA z#$Zem28A1%D=K|Hr|R8obJniwLb4Vpn$l56q=J>l+I7o{NsTAh_Q9nApso0Kst1*q ze{4a>;4T|=n-2+q{nl~%$ROkNcMCH!v{?(T-LQH&)^yC)w2nC|IZBA(#{jrFv7Z;H z?iK4DjZ_)jAtO*o5Ib85guP|+o}5i*FY}&^f76l6nYwN`om*|Gcgy-lMGU)m)jzR) z4cYpwHhu!+T9Q?7B9cH!*ikCpln!+Ck@w-303(s!)6C%{`yAP>@MHc%`p1>fpr3g! zX76Tu={;0Fj{_>GU%&EbD<6RD^&`i;TNuXW9-%p`cQNTE65l+ljtKBomK%$^9d#ZJIg@h0Peo|b98Tw=Nq^V%w1j3EWr_9WoN#ox-H`H4j;w#Y#Ufd~@gratOdt2F)&g;s(iiZ?Xv%&OB@4@-ykm#ij z#+=vpQQ2T+_m_7@>}lq#O?Jlj4KQs;{43$)YTob8{$qC8KS%$i(ZtEc@^9Y2 zvZj6XCKJMEp5gvn@GJS|Equ&CiS6Gz31dN{E?%51qqZ;PWWyx3=EpZ`y-e$SJNVQ;g~=HXa*avSo63B>t_1TYvUL+0_*cT<+rw_R?9! z&;+$oSvrGPi>Wcz@>#YwvQU^K7zq5HFJaes+u@J$Ly@V!T(N|UEZLi@FSqxpW#d-w zW&-7lPe?uU5i7&hQkxwYI_1h#EIW;(WIu?B8w4)^G1e&7>{Y~p070*U~$lfRr3gy=th6L_TXO`V4QULW_!DBgmk@1Ploatd_g1O6#PzQR7AsMro;!47M%4Fm z_(C9iIb7-r@pib0m+p!zcc{@_`gY&qNeV(5ZCkTMh*cviW0uSJCxJrM-c-{xu0Ol2 zW+Uf486WRVj2Zarz9bP5YeaLwB+MFTido7ONQ9R@(b!}0Wb$#lX-^xjxm{M3Te7lo zh->-2Y6|Y&i&88Bf(x$XVX;%#i=7>Zm7dE8fVnmmLI!cAM`4083q@}7`I3Yz1;i(% zAQ(bempus9(jSUYihO$xGuye2U$}HRrnQ#z%&VozMP5?7 zDJYKTymYx`$;bChmzh(x3h?-w+=%9Hy(MY+GOp6xyo}3tDV0cw!@>?jS>q@odJ2Mp z!dK@dOgg_!tzR()%Y!4KG_5F8hF+~Z*;{gZN%T1Z#F1%I^Nd>U%=pB!WVfZBy((D( zHxKxNhb}kkZ z3lmmW3v+g6E;DvuCMPo+hrs{eLjT{!qp1l9D5ZqNJS`L@6x0a^%EToM>0w=v)F_S7 zEnfsi4x|NVpp?IvDbpKR#wDDEAw(jd9t=l1U&aTX*ra5TRNSsmQsNt;2;vtqM0Py- zz)3EQdpv5y(FJJY;|+0A1+sLkU=V#hoEVGH^j46W1zwUq1q{1yr<7eimnrtzM?UJg a_8<<3jRBEiI`J@ALt+42`us2$=Kld8h3hf^ delta 86082 zcmZ^K1yCMA(-Py(q#9uLp=v1nb(oAg3TnJP>k0tL2oSez%L>#QXn2yUQRX;i!z9v6~v+mV&i4yjNY z*ME(2gZ`g`MNSf=FKBMT&dFiL!D(T}&Th(X%4=$A#=*v6#?HxO&Sl17&MN$WH1Pg^ zDyh5Rlq|@S^iyETd8Q!t0}R0X362L2Le~JX zasLfU(bCDHii4W}jnFNi3L7Q-MKq4lM-9X6Fg1I(be#S&`#582*Lp6IrPU2(JKy7IUL`xNjw1RSj6p7#{N(#gWz!wuQe)bZc#zc@H~ zGuN0Pgi_6+LgCp#++4gMPBxCF3n)QIWUjv>#RlTy;QJdCN2)8lXzC6eL23^ybW;Z0 z1q?hFh?9%;UvpDD>LwHt8;FC41H{G23gX~R6+;k9CB-Ian#DqZK>EwD^Zv)q-|(-Y z#8Q)R37W)lSO2xJ^YHwqg`GFm6iqC3hJc_clt2I+`ESeLnfI@6b}pX(^o>9i4*!?s zVE@OaG80KQtrOit{H54<{-c=cLMoX`3<`&51F>=aWjI+=#Xyp&7ohOJuCa0ceeADm zY+R{qL}IBuWd9-A|LZRs$AA1yBA-oVrX)t-`>W2)17c(SZ_Lb;1Snh_Y@omNe=Pi$ z&aA-(CxPY#v9q(Ks!>Y(6A2Lhsr{V||GHMAq{?K$1xJG5%P!fS?9v z%_PeJ$H8U$@0^il195Zy@7urG=gBM>fzSZw`!{!J0ak7{kgzbq-vRqKUOsu}`s)c4 zTxfyQI(HlxUCfzv7~(%IXkL*BVo<@nsJ=*D&L8Jlwv~YIWlb5TPVXKXrZ*xYK+ayKv#~O%aKp*? zwkZG&X$L`_ZoKF2+YipGFI-8ZhfSiVHE9|Y^)z&Tb>sEoVu=~6_xv$&_wWow36;Cm zUBG*E!Q!zE!d9|7r$$7N!cW7dCAnpu zlDV!WgmNujZZo7OuPN7}Y)~2u*4LyJOkaqJ%?%%3y*(4|t2-$0*X_uhd}B|vAi8yF zvd@Eb0{c@&7LcsTzd`C~-?A(cOQ22cro^SHfK&FM798ST3+#i^9-x%Pw z@dfHr#;-~{Aur%WTR{^;ms&nB>8h*p{d5Iubt#j@dSm-<(^Ql*8MszJTI*vDn!c z(?lC7Zsr0ILM4bIzzEwy{c8~l^d3+U$QkWNkz@~kiSa{J6MehHJrNIr%{SBmfBET5 z3O)xzJTZ}7ZiADgnL!V+AoZ9%{)Cwh0xBXI9qz&>Z3N9mZ79tFZx(dy(UmnJHt4wk zlQ!$?CliyChvcnV6ytuwp^0u((4UOBYeFpK8()@+GZp<(LiA|tp&MbvY`9#G!2Xwt5ghA{kZ)i$FW~7Rf9nf zZ9Bn%MQdJZj&Mh38Ir9~JOfm#Qz&parB6-ER#oY-kGIs~@F2%mw|6gw9k4rBsQ>g7 zn9&xOdgAj?1=F1S8txJ%q$kS-rFTD$4Ath*n zH9GMjeZ9>c%QpSF25rWwhOWY?o_d<;TEBrQ>y&}GO@Nt?TZT60hBC@9|ZnLsZ}&hOc+?S z7?N6+!~x8V3_7TC%ssRg@~()@)c&TY+6U5zIjd4q!NhV7^BoUAT1O2zusf*PH9zTg zTT|$z!qHOz(m|fKqO%F$Gj+F8x6&TnXo<(2LqC&o-;^UvXPmW9Tw6oVz51Ee#v^Br z2s1WNqUnPjvv{Vj>4(@Rkjojnjk0~&jE%d#`FP8nePu@K)3md@I9m5sBT2CbQzIu4 zOFR1+4gqo6m8=xKruQRHQQf-J@!=y99228$^4Ewppc?(U9xQGZx8r%P-Ui`rGo8P1 zTNyNV>-Kw2NHF{+AuBlZ;wB+lhEp{&xOJ{|?)D{XuP=n}WVfs?$%_V|$moeERm$X}v*0~S?>rBh#W%|=v`oCG~t0z2$7 zCincD@WP6O{Zzs-iMEQf)mZMiR6u$nTrlNTMCJ$~C&9_Y7| zwu|Y#3lX}xrq*4ji?La@`}4kBre|6*z!f^vd}UReiM-s!2CILG7piXb2sL+bgincM z>7o^bc7t2C=FdXN2G;vwN5&UIpXO6I9KTsfY_>-k!|`nvYrQ*FzVXU8r^WiY@(G#t zAmoK4fyqOa82*ai_%7+qu7t7gk*GENE(eh;>c+_%C1!27OuvMUh;`3hu?JVw09{`l zu_~1Ecvb(!UoElJ_qn?-eD~;y6l1|J(KO^SYCdT%cjm1luV`UWX5WTW`OV#|QscIt zdi3huT3Bvg>nmK2r zVY>J7-91c6;OTkRF%)j3XJKmF1N4Y%{kH@!wXuJcPO^fnayY{1+c{61AKxRFRQ~MI zxfzUGE4SN>Y<#sOywo)sAxY}RkJyn7q!PQ7$;l=xwY-Nh_lpWJ@9lZt+WuKD@ChH% zx?%R`)7aY|$m}1cTmLQG{;#_2Z|TJf`kz8n+BWlJ1Ogvm197smv2*^Pdh>7P{qXwe5y;*u0-mGA`cUFB$BVvIoK#83`c zQZdMAnvqbfobg?VMpA03YHAHd1}xes+1}?Im{7HkTSvY?&tu`E#NJ~yu(`x+U)S=m zW=#zT1?HiO3ULtM?P{_4l>ep;zLE$=SxqG5{{1qF;;|E6H3h2Zl)KjHPdqB3$O;%c z4Onz$Vvp$q?{g%!9@qc?IZBty>UEH{taI|+Eb$fHkj5nB9(uegOE^q6*Jb}M*SWgq z#Sv@{xp&EBAZ?ancL22>xV$0D0`7*Bd6rK+aU2v3Rf7-^zM`8- z=4T|X6K#+lNRV01V8Y%nQ;*)qqr?=7Ln2k1b~_@dfLh+fN$ofR>ie~feQrmhA6Dxk zD0&X8u(BZeeP$gA_=ApbbAibs@hvav-{uiz*v<%4e@F(cdJO3+LF$7JTnW8lYir z_-OY_oLV%TyjLzAl%apHm%WA$)aRTrF1LC8JnZ+3U#Dn`;jIyLuHkbf920xTl3G^7 zUAO(g2u#g}xsX2aDSpSizY{o~77l&y&z&*Oi@#$w*d}2dxUU~L9%wWT{tnIV$^r|z ze2F{eM_DvwhadSg)LP7lG5{HCfI6?~l@-0$ddx$fv^?nOQJeCP>&GUmP@SNWaC`RN zcKG2ex{ce`$Eyf1kR(XE3VFNcss_s3pmlr20*CR@ev%pdxz!rRDmhvbeT=)Sky-r~ z$IL%fM?V#XuZl_YK{o`Hdvxr1>zIGkC0*{IY}8573qXZC&+zQ&-USMhqICja-lpbD z5j`%<4DHI!U;Nk(`3K&Z)zK>m&z)GzNcT#4g(U(KUU>Byj0FkX0qrT+yV+;~vljv( zz*AYoI1E`-WriOqQUyyA`V&~5JsFni^rk2EpZDBLV-9=c9<_sH6V70ro%;DMJm z?QyKkZ&{tS`Tc+rV!`jS|&T?%m-)CrE!0Oy8{&K-{cw=h^)T*xZtM z3JDfLEbLD23O~Tsc0eyb#fo3*+{N5-OMUE|Y21UA(eAwX5JDZHlY$u=kl17CHPfF=n1>I&@GwN#Jh(;eN5%m{Z&5ECLO zNb28tOMMhZOGk*zM0QKO?tydxYuL6Y;*G@CX31og&&)>;6albawG{2$Wb%U7#HUZ@ zE~(AP+OkaL-ci?#yq{kmh-(l1jw4S5R$Gtt9M)l9!GyUpP&M~3gOtZ+B{qySnRe92 zc!gVc-BtHQh;*JXj{JET#f;S}-%&`C0|aZypgdWiXX#+5L{Qmq8^~dRuMs9cfA&Ct{{ElM%j;YHWi+X7!n5-erWhu!Hq`wWRH zCEn{C9)$%$;~oqJWQ~Zqvr5^`?f8B12qKFre58xf#F0XWx$`XG-5(y-}@JhX&_D&yt%=5iFhr9})vKb`< zkRF;I$CN*fp$QrR(priUwGZxIEu!my8uDq_*^B+x@I!^Po45y5&#zUia0hYYY(j;l zLcn$Rdz;|HkGFv4Gcf_pXS_Jj3e5_Mt1HQLm=qDlasv^SNYr07rwt&AOf}ezUIrmH z!7wdzf;B8`$ux-AMW`ov-yjHXSWCj}Wh|sIe>8+03I$*!oDOM(L~-~Lyf4_H?b@-I zm500bSY|lQvPCM)@<84y5W;qgc4eSAed4`gY*2IyY5o$#JRLZeiQDo#PyODE+?)<9 zAAJ-Cx8CyaVGoXf7$**OAw8m7UC?X|`A~drIHm9z34pu+v(bledEg6PLO+hW(%yWb z%s?LUfCElM(3lx>qp?&=Kn467d^QS*dLo^Fc>BY0xA#N(_5Fiq zEhzH|mmm{zIH1lw&-?K?(L2v8_VwAH$Qn(g@#`%2XF4r;qWFet4ENh7Hsy4m*Ln<< zlqUhHh?|w{kvc)IU)KzC$g;Sxu&%=MJM=-*N4MgOxO=kdf8T9|u}0B3VzVmgyrX3F zz(fE}J_(Z)RilOnWEj*VvT54$I>+{R<{@yQMd%Ry2Bz8d;y$uIxhJb&UQC327gqMG zkiXHF1|J$wS9$hGuA#5>uRnju#GtBMFeIQfWZ9%uO8+Gv_r-IrbZ&pn>qP0K{?7kr zf7*5+b>U{_p2B@Z0CAvi_f+>qx0$huakeuM>s)ZDwr#bI88lnCy&eI@^dnKyvbdEIkNyB z=kGkqn(nGE9hRGhto;j^g!H|BhWzGl&8abcY=~ObsLm!fr5UPkR}rKvNKlw! z8B;$umcQ_j50np6xm38~3lvT>z>x=-w{@^GHz?CKC}=xsaAlq9KL|cf-BX&14mK+2 zT*nr_C8$vzz4D|~3DR^d_C@Y2xu^IOQ+Y#CEx+X*3`bJuQ^p>Q+InRa9W+jPNsNtI z`xi2a2>kxdWSyCB=-b+I|Gl+BvNQXmC;?6ZZ*jk62lL^z=dgaNdWzKE01l3)3K{L+36;4Cz%-&*Tzxcnk{ zCh_F&eb%`IU305X)9MBDR06YeYu?cIGJ;Ef@%B4sA2H$MeKljhiS?1wjLU5Gny+y3 z$z!gpDe>}+{OIYYN?XA9U#VO`q2Qk}w_p`+*DaO&Ld7>Ip+7Xfg`QZzT7mO4rRk?^gjE0|}O>4{*tPrwBYrB8#EBq&&5SLjKgGw%BfasaG?DTZSB*{<}$*4PY~ zh6(*bpAsvwRjIX+D5{St99TXPzXwn6BJNQM z@6l8oVBgUD#&;@jft*XG19G8c3E)%E_+(L%y+^mlejEs`D9p*hj8W>jKy*_^?FK$! z35O@{&;~$|_KqCLxaItToUSY!6&b_7L3~dCBOOEoBslLKj( z>M@n&IdWiWPMsO`St*nNdxkmgqx@JupDk;z|>+FX#pw8c>RMz^34=mC8{ zuQ?ZUFb{U3IB$~_X~RERl+77uHBaSHVS~eTC$r1F>t$M8ud7SHK~{}%fpdYqgowH` z_MCOqUatiBsIM^pM)QLA4~Oh`?^o!z@7K4fx`d00K#fR@m=0%&a1Ph#PwW>t7CBbA zE4)K`%YGLJzV^&+pOD@$I$}46D$nenh`XpIHjb=Nw`MzX_6^cKaAZf*&K6(2M<{v3E{%OVix9;dIfz(2EV1f}V571l>Sa8%e#W|i%M?KM2`XF}8T%F%B`uh77;zw3BY>Tkja zrq_hPY2^memBiniuduH%Z>jmFBB?B+@DGTu>2Je9)X9 zc$R)3z$c-n4Fd))EL`5Sh*cAh+JH$DJ}iRlisLz__3DwaoR+Det$-zr30US zpOe*Ny}*imD}u^_Ksv{BP%F534lG-v-pCTr#OFX^Z-Tlj_ZB@Pbxi+9W2aDF0qmR< z3-j}6h|z&py}C)s7j^q){;ob7cKvF2?jHjuZvGglDH@%^fE|blPkwrI;^)-K3>#0K zM$l0xvmxRSY|l%z0KI99j%J<9M&ZNE$F9Afu~jekq^f)_GdpAwQHF+ELVt4X?Q01E zH31CicoGh;jVE|a8be?pKDBH?smpfl4xht%Q}8uI|AX85qVr|_*LJtbZpn~B2D5(m zUP5}6_O|cx=Htc>tMl*okDEQaA+S8$f_GOGiNdY6w;3aCPM8HgHx=i*#PLc3-seHz zeW$kqUr_~b9md_Kd#?5rSbAtFiLq=HbFf8I79QF=c5l2JwY{eJJO2zOx# z7{wB^3?*cmjVLtie_gp&|LsHP)rlqWK5ZtWm!aTiq`gt)&QM836Kwj=qW3DQ_8GJrSg#GEIojUEg|I5-cje)Rxf1_}V<;o^XeyexU zqpo8V(Ms{6sd`jJJ%?&r7_UDDKqZzR`2Dh|hZxPQ7zyw(}Rd;`D z?aB2J(#ff7^rM<6$|yv<8t?bO>~a5TC97Vv#LJWXQ>ED%A>r|Wf*s9se~xHfZ@6Wu zovXdzct5L6YtQU{@}p#8SXrX;YEoseh(QWoIf-6I^8m~^%%qdsxbR~H7qOdH786_F z1#8Y8eAn)u!4-E;d3oC@Km$8$N-pCHAG%gF0`67%)rDFM+(3ip9d8{uBmN?C@~SKc zq~n8hF*;cP&HJ3)-P>sDdB6-!V$f2g)V>Zm@8!KeCHWeI&gLE8C*^F6Pix@i!Gl*o zATNDLOLCF$5$kA0W6b*`iK8jo3wa?sP*ycSHKvhRZ&L_&=<@LvKsMT99H5;DKZDgC zx)H`pUx9OT^771Dy2;6SAb3?Z(%3d~Pw3(f&gsc@35V8{{~G)R{2chT*4<#;vUK^;COAod@2faDJD;aO1~d*?<6jg6ns$#sKO-V-dHxgr< zweULB$yf`|4S_R{7()YNF*1c{TKO=f2EdKQq~K zuHT}XTopkOwpNa4E7zR_7eyFA8IL7V$CCk`6(p!bFi=CL);zxOsX^!p^MS+ zSyn4wyU?lHW#qnC9$cbtgd$RzZbdax=$_in;XO|n#4ka8&90Jjo?zhvDTaZ=#ikZ+ z9e5l9DyuXWbP8j(Zd7iO-~X<}Qb(W9q1pMLNQlrje35c3(GpXi{}kwP~J|MwLuhG2rnI-yt~XJVNohEHnXNU9;rvyNV_Oy5hY;{ zkj#B%JdW}}O#=yqKC{U_g3dpCIG28CIdeDyPU4~NJw3BKJ8@rGIIWI`F}F+vcNIU= zR44qI0|gcc!^*7;!OG4j3Crk%uuqy~4Q2I@JvzVnoG`CJ`++v`%UI^#49ZUCJ$O7M z))s6IG~jqDc~`e+U2ilg2Hny-w%+dOz9S2++>H$6v}dZw!?7e zc$1!UB9Er#V^i-PPdz3lb=#ZckYM zAZeh?B`bO0Gm+H+E5kpah{ETaK#0;?EyRbLawXzRpcrvI;H`Bbl1bPf{UrY?wj~g-y=dkq6`*4tQYN_Gf*#A+}0luu>}!QrYELR~Uw5yf`}$JyE!?^`F1 zNS^oHsc&p4bk-DaBn^-a@NA@N(W5dRqEP5YUl|eCb;c^LnI9?U(1XGgQNdB(*Cy@M z#{J7f9PIqYzzBqu{a|j+?G>jb<~Fi~!N%s}Pf9z#0tAhObG~?zUb|C{65qRK{UNFf zKPS@=biF1y{7nL=!dCGz`XFccuC4Pc3_Dim=O&bx`M!21Wmqo1DAT5p_$@`s)%X*# zEq+8;1T#nKicn11FxT4V71HPq`F<-g zFnP!6($87u@+Zoq9b-4-QI{ru$*chBCG`3Mlyeu)v_RJY{3YjQ`d0Ga{VO@33?9F_ z`-`Lba65IWw(|#VvnZV%`q22T@vzCCSmRwyKvyHrrvAbD^daJ=*&B}6$}|<&bHl8= zYPVjWRqeh6Vs4DolzP5)jkaOw>DSX@gmQH)x=M?5B}c8?Md=o!8m+3ul$?qRf`!&! z$F6+2fQ?1!M4s$tk?a(1jrW5>mfgcp46X)tr{?FI2mqhRhWZl{ z@MB1n1*274bSTMa*J%}dvhujd#nekmSIbvv5k*{E+uSyb*_N91OJ%mC?`*$hP|v2A z$u4n>e=yo(zd&VG-(i;C9(}_@Ggf-$+fXU@`^5Y0h-VNxU*|V77cC!qH&5O|nv$_a z?A`UJb8l2GHHpGTp@mU7&qWe#8KpoN;Mz@FM>~E}nRZe&H+}_aj<3(^)M#gaa;ETZ zZ_*{v>|A^_;rvgYi9ijwxcrZ#rJ`o@@V0f=!R0cCsOhq1cnBi3H6r+aUq@B*q&5c` z+AqxrPqNs~Qk4+GmS)-VGDa-iCp%g>XrIs05;`UE8S`GPQ%ySMGToKF)0)E{0Mp!C zx`g`D{)GB4tz+*ZfAH5CaydP7*dC$Z#f!OTtQkwVI|F_}>9hx>O}Cj}e16J}R6Q@B z#pEUC;})b~ZDkbXQT??(dlJ!89u%VEjgWR8jQfIAv34CQ*jn9?x>2EGVxi}$A?K=f z0&UJD#G|csZS0{vAyBnvo}TtD1$ffcG4GnE-!#ZS>r%PJuxl5_7+f+`d6gIIa2c6k zuSt4-TG(Ba1Uy-yI%;Wjj)jE&)ON)9<0ml{4V-lf&oDTMUR9!eC6@QaUc;|rziE@c zreEG5c^~YuQ0V;mc_>4a#Riw@N*a5Y8Iqy@y>FnZy)yhT8R)W}e@aw82SSB0$FD>t zRCI!Sj@rU)foG1lx*)5GEVg(ND+?9KayV<`S~%~a*GH6egs4iUs^P|jbIZ`8wDTF8 z7fu=ddUiq@v2VA#KJ>X3rBIekTi-RC#q3nog0!->4&}+hAskebi7U1ccrLh>9!F^!Sj6%N_rw#&Ns{#il@DK(J@W+DlWwQ-Rx60 zpLS8!<}6zsKrl!!Lf>TF%rP0=M4Qfmg`*hjPbSxAC2L03DJpg+2?&s5meTkTm)+@m z%#X4C-NCdA{}gP2M#`Bi(hJ{%&T|5#Q*`$>V?6Xt*2C=9iP#$Yr`#EMl5LRz;N zKyU**tnLWgkuE}`N>x&yXKQqO5R4+XU0@1#*mU9E8s1d#5Vzrs#XawYRR_#wb|W0o zTzh4GNC9A&Zv*)e=;b(Yp51oQB%By|k1fWMFP)asCqvY(U))2VWNycNK&Rv9=SLqX z)YO%3D!r5ui9pjFptypXqRVZr@7{?zGbO90aN4z0+(b+i4?nhzpV1G%k@*f0*=Laj zJ#NC#sa*Xuzs6Z#|ZnEfY<=JqgD+N!MSM?b77ADocvvp^&6LmznBq#7@ZF$SR=rA~_4f$|OJ z;yl}3kxNfKpy88<{=oZF08A`x*24$Mi=l9in3DXVP=k;Q?aM4hn?$3 ze!iun8LgY38~2*X3x`p;kPG$(#I0&;B5k2YCvwy-%@fTZ@rf^l*+l{Rd%VvDb~g0H zqG!hhodhCuceoc=1?GmjEM7wXaein$(**QaR53pJ zJMM+pksUoBT>lR=;mGNZcasmHQ5QGj1on7Fvd1KvF@*!-8>U)}v~A6`u#DYujbkO+ zvgbP|Kh%Vvq@Lj-(%Hll?>lQTEcJ-me$8DnGDc3ssPMY1>1b_o-Noq;;JbgQ=`T-+93=ewRSg}Z0U#< zW#$?@zzr2Iiv+H{Spws`RT5`3c-_m;&>AC@fqv|tN4%-7$n)vW>KidV`VnFMKl+#Z z<#w?ya#Fw6QYQNUL_n>=8jdQks+2%T2ma>eOfkRX^$#(EiIQV-ZJO-2xb{4aay*XL zo`3ToJ%JXmWh0j6ffMZ>q_|XAc+A};aTCghSs$gF%by^NupsG_A?`P61dA<2)sW^q zKyV{)fpH-ugj{|*nqH7YCkk^WM`ee61qffttaQT!UZ4WxNuore@!m+fa)Y;QDE+dr z%P$c_{JRL6n|y5&o$f$9vaqH!9~Wtrs;6U4A@f%P0TdTf@uv|5cW0xL51?1_Pk86S zIFZ^g`ZE{Qy@xhz#w8g&1P+imBFwvlDW=zfLmVe?O9lw)fdSXT_}>5LV}OyXl~ zodv-IJL%Up@bhP|wPD*k%;kO#z$ILDZxB0v_LoKbTuiV8RBeAA!LOncxu9BT23B zpg>|#m?@qnaM0PINV0|(0H5jd|2iJ>nFIbbn)e+OuP&--vy;}~-wAj4?LHhOISM1e75Z$erDfe^kl3WJ`N z`K+78_G{^aDpw8?C6Qto>v7+`w@)E+0K?;UTL1xAw0Z@2S@-*N%@U3>fo{0G7ZYLCjl^A`XC->laluR42% z^|UV;g2JOo2tt8+&N|NC&WZe!>A#e3;S$gYhcnu_DV=23k~+C;?Hkt+#(r5CyOkYe zk0GY$(DW2mEB`747jSq8wXj>tO_|(*JPi{}Qd{_AZdO$amUAMZly3EBeCZe+rKUcug*t z#kEB1@>?%oO(&A^t6yH-5ir8-Mjo_~X_Q7MY6i`$Qvd#*)w+{uUHke&@|k(tnkhw44LF`FHSZsz zFugiQYTHI>?rL^GH7tZT2R>bCD|`bgr#B+Ao=%ODcE-?Zfnb5zz)u*bN$DiAz8jjV z+B++8;CWj<_zb&iL`w$dOERZQ>wdI54j;rtwU=CBYz%?zB%Okqlaj&4pT4Ft zxY!MKs6Q2dqWUEp#FWHmc8~K&Q*$b3T$KZaY>xuoqm<|YSYc37&Qf9)G7oa6-;z?; zcWoc%?;WSH-TNNNt%HQdS%EH7Pu@qh@d5XbI^;l7#5;T{?t;=w?wf+?-s0cVy<$?Y z{W=Glhtb#R)82c;w3PC#v$}EE&2Mri@k#FSY`anwW1DmHuKupAt0LE$dy3LwJGuH7 zCh#+H1_CUA&F0=OY|+g28*<}-O+9`*Ox4n`$a;E=s+=~aUol*vHf5I04A1;-V_((e zqB;|9t5<3~qOP?&){}!T_bT;D&KUQqRfErDhgFU}GaD)^qSfCo)g$t(*`FsYq?1YA zFjnRANa`B0pDe3PaaIAiXe2^Y0RlL?R}wehjhSZvCa*VM6=P#(GPc`X?4jeWJUjNr zn9*y3dy1_`cFHlfkpkC2#t*`eMr(QMIrtT{OJX2l@RI#j>69(x=5-#kcz4!H>Q+nG zl2{*8MeZyaGNDYuX1RDe6j%2+-;}%!OvmTFyDa}a66xndNeCLsBmX${Avi$)s1@{V zYy$xcL~lw35ivT9b(8_1pdvG`{COLmbw`c~4oAd^N;Hd;AL6Kid@*NBbi>`_vIhrV=z_gCtu(5Xw_D^vv(~_<*yykY>g}n z3vHt~8I91Na}||Yb7e7%;ocyp;WdEvl)DGyn#p1)spPcXVa9gWzw~AJ;=932+I(ZM zY+Bq=qN1vRRJWzSq)5m0qn!1Z>A5* zI`|YPg(KvgFu8~VVC`b<(ujjAxK>vwu};-zxGqH7q3cEM_*vxZ^Vdn_cv+NQws?V; zaqsPCKlO8_TXILz&hJ+t+5XZ<<<-QqfJu$D_WdG{QXPqiwu@Il`NQnvHsG-_T&?`- z97w@_?JQ%}B@Tnq;WU^8PGPssoGT1WO8q+I_Y%o>os+UPo30Q zv_zPNYqu;m(&`Z(;C_6b%*cml=>yI(GN2U1`dJNIOv5cz#T`QraIE>31Vp$2J4_nN z9dH><<|-aGo@8pbYbq!97^|LXl{bS07{+U7f}&?l_fHfyIb*@!V8my>{W@BVyd&K?Qugn~cRSmV%*rZ~^uHC#y+!En=W@sSzrz2Y_ z0FN$};3f5qYp|Ml?&wsXF_l}`H^XM@CGCsk*2i_sQ!@6v&Cc$gEsTQhxcbLJf_bWkKzyoR(vj!%-QKu)OgNQFR^d^ zS;NlDviN-OMFXcTsP*%LuU>#a%erI8LJ^nPc@s4J%-|h=g;9yRl=O?&f_V^{od@)> zw)W_IXM)?v&x97@GyWxSgUyEG(zRta)Rwi3Q%GZRlJAdJ-#aTL%KFYn078-wE)8HT zfzO5tVOP~djSuR4_GS2hTtEa$C~x6XcIU{5i<@616x(!jC$>HYum%**22v9RT!0`1 zM;#6LM1k2v8T%kpo!ab^;$V~O5su49zbsW?}cC*>joG2?J{AYGE5dO4Cw&&s^ zw$884rgUAxMt|fC>mKF{rEagc=xY^=vdcoAU%i@PIgObVDzQ0LEG&eT=<5%XPD{u3 zFOT23;|dcfN{!=|V}Q$0*sau8ra8tICQpZO&pC#i$M8oF5yYG#YKcPA(Pm42t7s0+ zILQ`zu|p4P-u!G%1-RHsq=s-L(AiK+&T@FB2R-}WA7pA~=4~Ji_HcAU#9Ls#ShWB4 z@HDY2b!f)HW01~*;|W~7pzp1xlu&N*nnCzR8b7cj)5}bEeE<||G?ej_N6Q^*9acbn z#?|4Znj#LE(tG47{WdHpxsLCFPSePD2v1UqPNEx)f%w#(@)D>VrGezi)soeb(}=Nm zj_rH)I@&Ob;f6>Diexgsp^y-_n`JbOt}d&cXYHWHsRX+V_Tb4M7};Y)X+a^ok` z4w|^y7FCS!Q?KPJmw22xD6@CAuRT}gt=&E^C2{o6v;YGBwDosW#Kt+}ZMbK)^U&P| z9GtazZ*H-ECm$a#a6UI{M)9{jTiV>OmaZjZxN5-Eq3=x-0_}adMMRJkeil_Nc8i(R z11n+Fj=kS=RlAFAG0XS)WN}aKM2;=06oJb2f;!-e_Nm?OYUd8^7oMV3KKHQq?Khub zWAzD&p$dSf_}OC^4S*g)dwf?*xYbR>0KkumDVi)3Kap!!X)_>bn%Hm?{QYu@&1Dy_ zy{TA`(WI54^fd))IG|*SI`&hIG#X`15&8nZ0~32BCS<;Hje3(6|2MVYRnp}8S|o*J zsOCbIx9Gxhnr0hNfn~FRQ)up49>X{Hp`l-9hr2*4&S6QuKpa>|LkL5zsY?;%f?zQ> zZj~|CQ>wGxCH*RK${bhKDt`rd9U+rqi|AUva-*^2H`@dfXL=&dqTNuX0ZG;GiUNkZ zl-0OP_80R`*bfMG@M}lm65>_b?TYIPMLfGPGL2}r|r}AHZ9m^qwcu+A; z@ALvuTiX2r{Pr<3L_!M|ZX@Nh_@yi2#VfMK*Ix0%;TXIh_JzmwPYGxueIJ?`_mp8M z6b$PLGdH7-$%HC#{_9pVhmI^QThap}GA~6}m8CrLbjSL?lR~_Nt<`SKJ_20|9mCAS zG`_D2j_{4Q$^IB^AM6}#^SPpDiQYQGC(VwXXUq8I}^NsLhw^-*@CWU(xTo0V{6_}&9b#6yhL)D4fJkq|y?T=5JlR3GY9I2T$8SS`K3ItJrQYjBU zETJ_XF5V@Zuo+goaM+d=>#>sGkG>N)>MX}EOG_rD+=Nem#G1v!W^G`(B7eOeda!2A zK5Z!|Iw$q3$9ceA2F0C04C0O=&IE44uMPRr}m|9dxHsb?SM@<(K?A$-oBl2fjrlD*SN# zK{qGW+qyGv;OeP)|Jv5uG7)>kN-@)kTXFhH^&?2sxQ5t{DCZM#RuQQ+Kzv!4#U^a6 zeN%G471YJm8z>&z7Odf0y{^H^>S?mmv2X<8V0XIE>sZkSEv)dy2(q+qLb9!}4I!5h zD-zc?rByg5&a%KG%yMj}@~kk`JEcCi8pv3H@<@lF(?V!(aSEf*N+*~hxat>}p!yLA ztzlphYhN1o{b8=bN5wfAxGx}gCYSqdf?33}%Y1^6SQl)(NiWB=wMihG)r`jV95Plw z&OuQvkuiL4j^(WH7TVOSS1ga}%U?2?HQ-aAl|;(afb8M@< zcJ6oXldUkXa^egf+#s^cD>% z&1Q$iLvJVpMh&q)fRy{Dxrw+R5;im5^8eMPKe4_=>OZV|KpkVe-U;LL7D(v z+U>G!ciFaW+qP}IWpvrL%`V%vZQHKDzxg*4GmF_}<}x!f;%4N1&iSrQi4dL@BYmxh z0xcLWLtY8VY16~sKhv8n@XPI#=QknvvoFJyxkXb$YJKX}EVo&v29uZQv~+L=s#cjJ zs$%CLk&c*9<3CYc36xD#%m>VdOXemb|>CSU`eP-jo)<=LbI#T4ZF3 zU84RefHj^HA-6t(dg?FjcMRC`(Q-3{34rvDfTzHtw7$Ou-dEGbXqol1wcDJ?U}j}q zqqEC58xoPfqki1yq^BEZMwYw`5rf-R1Y!MNMG|(kHJ6}F5ACk<-ryhVGS@dqH6#(( z`*SL}{O|k+J5>43=;akW7bT4v2AoZec8aJ2#iw$$Sai3Jt}BHPHV=d&h1}b2o^9^` zz2Ao(tP1oJVBNwF-HN2spRHbK+QaP<+$8Cx-_2q8SQZYOKIKwyg)_3Y>VM11P4$Lx zw;4!jS!2smt8d#LVabA}lA?UW(`9{nGfB%$69TdYhm}yk15rcYk4U5=^yOF%2979i z*%!__(xmKXk8c~nE>Qn0K@XvGt_r2twkOFEx|Wa)C|oVsFDlpOh}V9!>)cUv{46Rg;yeLgOyl{W8@wRNYi_r_J!bIuCqb zROo%V<~xn{R3$^~Ts=Jx6879xNWgq0K>#0*;h$R>H&XQ1j5PczX>2LEDv^%0H-gj* zg2+5|5LI(KhjQ%&{eu%I<*sQgGTf7lld9Q|l~U*ZUYK4aE|Ql6RIq4JzQ{L<)hiZH zVz7dJ13zwJDr>DpC@x$m7TJD(OX)(2(wNH;neKXMmlCj;fCPrt>RlU}+!tvH<2YWZwKUJPfG(p<5}6gbmhn2#lFG-I z?mkSD+qApZ=b?|PAu+MJv^y+-%ZcsY=fG#*uJJf!i^*v$@Xi?B9?)8nQFP#GO>*sB z*7n!#LN$@V`|&J{jmkbtuEAvy4TmIN{MjGtsz^sY*d2TT`vKjt(Jj|3H-D{AZ9_ue zt4*Z_FRo#zPJ8{zQ}mMKvTj(R;#sX(EV zX*Kf2(jgqxo`6b~IjhNb+tbK; z&?K%={fV%dHhsRoFSk(MEAMp0NIEWy70*O!Y78yS__oy0r{WJB`_X<0L-$kqO0c@7 z;}lvwNLre98vwsN#9QxFk=jIQ7=%V1K%4ZN07vs6CT(H(8BlU6k}M%$_^YZ8{Z5jd zixZ07vWYj@ro2bw?VhRwHHN^=~F-JCGWywOn_u4zoJ#itgv0`GfW?FsOZu3ldgMYaB+JaJLP_PW0C*IO?c77*u<-`IBf{A^1Od8=WcUB&X>&IZM@^7s?A z!T75d-Z%*qX4w+yDGjnuY(_pd_z3xtV<(>i5Em?xO#?+qg2`5CmO=Z(A|fK`G!-nH zv@&%se$846TSZ?=Q?J$#D#Fd>F}#t7lv{#T>cY`!op4B*+{_! zV73_wI2~H=^iGVEyT|N)m0wLn`(C6}S#>13t@CtBug#0v?i>^-0&a!}ZlI2$6QRwn zfZzZlCUYsH8B%c7E5WR^8NwL^tOe@ImFcCHy}*ibD!-Zf2KiU^>{CF?`keKVNzoRR z&~jk@48JWvr)lHqujF3zeh_V=fz3?<)KMdY?Z)MH6U8=VH{)v~GOx&J=DnV!(78U4 zu4i+ZajQB}5}DsV2c_bdBMs|Cc}Tu7y^+}DZF+%`$cc9qse&P!W@+t((_`; zF79CNrm#b>Jy35-OUC#K^uw-w>5-`(qx)9IORf~XjF$f3e#va`)RAsL`Et+DE-!bEsOvP{%;>xitIfW106({Odhf+Y;S%eXqde2%$`?KaSfjT;-2H0_ zhsScXU2AW);@a`sTQ;E8;NT%bpY*W^qmOM-GX8B|!FdX<9FzT-3@n(hjbg4M7_7xXi7(_@c=5 z{O`Njl%bajPYGw$kJhIamnDO}T94pPlAc0O6^40Psuav(py(VxC_6E7bXcXCD7loa zo-UpY`^!O40}E!_xKFJ^d_{&Oc0j|rAQI_%`i@KAAlespf*%S2Z02DrDCMv1D+FbD z=ku3tynZUuPR3Z`O_%%qAuEe3SbU18-rF5PJO;W*3s0-5^gt-B_N!N_xSfHuW0zSJ z^-UtToAha>Ks6XZC_bMe|98DiYrli2kmmkP1hyZ$Wh^^D@hhiH?1S?Me}DFDlFayn zcQC<{B}2%p5!v9Jt~=t9TQv&DlJAb*9cgIio;hkqbUKp$?L^A0=Il=XWZpCU?W7_V zrTjrT@fi`@a!dKI)i1kxS)-J@J2V%GmEWvp5?;; zjv^rj2xQ3kddn!5wP*ojLf<}zV<^R;R%H}Ql&f0F(rrtjOEOlAtDk@lz2Hy`7!(7=8li)k?kd z`KNSr#|{+0VQAlG@w(tMjiN+Ibd@vhrvvE|rTNotY5c{-D8Zoum9!-eyk@SemcFvO z`~7~x3wGQz|L;nw>sy=g+43mAL$qhvjG2xxdNvI|g=UdI*OsLt__F58+H%QGX0hVh zxb0&5Ox?)qpPz|d`%rzQVwnMj0gZvK_P@(h<=&5gih2JmHFWG;F0!W8_SI&Jr)L&f z!?IYFnvQvfUX|;cz-o;9`& zK4xdJW#o^*s*lSTvn!b`EQZBI)oHYvC(T&%5a*)B<5L`-_WKdbiu(+P=#yA>&jlmT z7V$B_L_}Kawm^GHN@)%AX5zcixp#R2zpA~#B*@(>9M^+H&DdIg@Sw0RX)ZR6!uBWW zfh7>h^L6Y}f|pYUq`>5Ora(!PjDvx+&>@$B2`Kjz1@+7$om7 zOx7n{q%yqOKF9|vXV>@y>@n_n{M=4DPtiO8zIZGTTGUHINf!VZ2+^6n%(qK$c5>HtFFazVmY^73^F^Y(SB zyDi;XjT)b7+&ZzfP=)XCXao)br&-t;78MrHGr@1#NttpaX!_Y4hxg-w3$QZU`6C60 z>?X5zSw>a{=W~GQ-m#^a-*^<|St~oSC+gYCrw)7#qh31U(>&SnmqI8mEgtFVbLgWM z|BlB0W+RLBs7e&y(ZFn4s}1LIoZ5`-{ygo98m&!1QdPe9ktDp=aa~F$;I|=eTMG&` zBRP7%WRn)1F}z5<(r@cjp3&12|2+iAVYwdvBkKOe3;UV-%p-Y&N+9s_m6CM^(ur@u zEV~u0j$J8B)qWbE@a{#oJyX-&j0J$)%E;EgMP+sbD37-Q*PlUst7c7;eeQkx zuY#aw5-F2oU<0D9p3NiFhQnoj2v=WAV}-#1iSP|sLew#0a7TzHsF{M?lG#Wk}b zp3hw9IXynN#EGR9`P}owF(&~+9x3*5+3MQE+RNdAVouUSO{+?R)HM3a$;h7CY12Sj z9aAMs5>U-?TkxCdSa{`m<$J?mVJOY^p)~~G*gZm zWeEOJH^zZP?Yw=22>!)SLKg8@7DClP%iL1$KHn&bK)LGWb5{@JJhi^UI}7Ffplh^j ze7LKotoTdn*}$^K0Bww58eJfl6an4}3Vr6IuK(-n%V@av57BvKCbdj+KXF%r`kqSO#Z7*}@95j?gkKI{B}A54ZF8OggjkN{V}4+{{7gP2!AT>bv9hM=DtiE?#9+F4Fzr zWyFcx;T=$v*G;*n7hPuS&G#D$Vtl{Sx6;|+XQbyQg}go&kAOQ!8&GHFC~buFi*DM< zPCYIlQGHhP0fRZDO>Blc|ee3tPk?Cd52zjh*PVj`t*`46%&xJ$KO>H0V z547jKaU$Z8@PVgC6`w4@Q}oGn_e<<%&`np<{aA9TUg!5(bfSD#t?wPlps&v^{SWr* z81r9oem}s>%}9Ug9RQa{+e0wTUK4enx1A`oQS_Q|7{tiq7J=xEZFpwSeGG*z{2-{u zkcUDl2w=uTA|*^Z95$FK+!z%$R4%M<=%e9dducjM9Fm)8HYhG)`-yv?IEVQIeo&uJ z0N*v?q2putnR~W^+2!#_c94b1^UgjDQov9@&Hr zk&Xbtq(AaVe3NgitA{HFiTXjZesFC6_hgV5wUVB3SmP}?w)a)!E;9;d|9f9LSe%lq zmU%eMC+wEv``~!L77Jt0cSs+RPs~ZrJjx07i)852b{O-4ADK_?xpM~d>Wvz(hr;03 z>5||mIGQkagF2s@f(hbl8G0*OuwxeWs1CIg$*KU2B@CC85zH_3Y{MkxEmK4A`#lwt z_$w6(0BoK2NIR?mQe2DThk2m;iX?5K5sn$|dk(fRO8+W$CyuYP5tN_V5Nx3{OFJwse5XB-Jc>W?4;#6)JF9FX{gr=1_eoY!9Kt@)ves62E*@L7+!nnpu zbzfNz_)nServ;^2*n|!s0zC57U9)m3XFn^#j2;>;PsGx!2}3=z@S>5NZEnP6Wx`4V z?IO+54CMBiEVTeA(VjZ`2g02sVV1z13it zHOjFY=en4XJuUTkayh&tW78@iv*8#~Hgh?>Tr8F&ntbiNd0`xo!0^LkK1^y|$0oZi zq&FsK6(;T8bsqivnCTD;K))!94^AV}y{VL?wd?ah)~vFneyS7vOIr?}Q@R?e;*Mlm zm~Mt=%YK2kGVju!Aym_#$IsMAXDSkb5x%1l?L?b#rJ6CPS8DOsGTB9$9(ikYC*M;v z9#R9Mh7e^a{1pWdiE?IJL73`gVWjQ(4`#TU`j@=SdD-xh%v!3Q#%)ZrRmu_E#NZJ` z3(5?PHz}SeQA#sx{W=;DYsI_!_eSaKvdHsW|D$_MHnAiB7=PtLRqPyY6{V&vVw=QDBbQLLb7+3t2;{V)E=VU}1==In14RrF{{yX)TXd(2xfV)Y6I5B} zT-86r6|FXuhMBLPOvTQVS7XX$N5i&e?d<1$VF>V<>^>2O1+IugS0w)?+2a3~e3)_z z;FELJvLs-wkBn$p`C+L=yj1GSvGod>`rru`TxCSdwnDXV3qo2mY7E1mXrO`SHxi{~BN;{Ax=X(VIKWq)@+ z64?fP^JG{&$&H|oZT7?@MwRo{+xh&q_Ey}k&Hu5PvyVSUaR&7^B?59!H^t0GYL%w@ z<5~ZUyD<0ycXO(jd4#9a42;iw2XQ6M3Ek|(z%1u3&;ztb16&Vd(9?sj4@1g+uB`~} zo$7WWKbPt1=8Jl}VA{RI7kJK8D?7W1ZjugQ;oKsc*<2=^$?Fm{qs5oI@93M6&60XlQS&OefuLgYkz>QHrm3eE-wvY)7BXhL6X6IT zNwUVjouZ|kn(jT)(WK*!*=)$HrbyD}TI{Q-seRQe(nUpfF)j0l8ommxx|p@|T5#g5 zOD3kxQ(}{8_scV-c1t!7i*M4RQcwehH8j!AkJ1`XWLQb|6JF0N#yf3qcENlXq)1jz zg+3fnlU}D8e>Oq&)^fWn1G~f)`{DvP5xb$D{_+DGCNWkN_l~a)SO-Rg*lH+>d+p#- z*wsU|Kx<wu1k=#s>cgY?8F+?9y2WloQP6@j@Q~O zjvCMdVuZG8Ka@90JaOJ^_0F+lxwdO4&21YVPM`T)Lk2wFkN_Vn+>UK@vW5fR?bgnYf@zC^d1_wPV9JWs>F2zi#rc>a5q) z?PzFj(9zx4jLTF%Othx1#M!8HdOKe}KYu?LbG0$CDOwLSA*ml8%rgKuAbiG9Ae8gg zJ%5_ztyj~X_1%w1EVVaWjEq_uMhCjqtCzk9Rrn_qjE7d#<>v(Gu!2}l)Y);23RmGgt?|U zp1P!Af*s|C5}6KTCwBnGBUItel|mHMHLn{w_Y{lWQRsWg<=|%3Ng+90cl%bLvJYM%-*&Ad?VvM-beEl-E^;SWeyZ%=R;k!)O;l z8f02^DeUVAl$Nfgl<#r#{X|h?|BB6UUV63|;U!?7rli30JpTq5bVP92ywxj*X>I*= z9bswny(Y#pQ4-!Md%-q7Cr%T+TK(h2DK>(ty~UwHlb*%o&|)B%CoYN+zdQWgkQHx^ zeu9CY0OK6V-1yMg7>2OZ3Lezx?ELWHpzC2GNTxlg+@ zRRcv!4^a_R?@tPV6bmS#?E$BD0clS`p!LJXur$zaPT2UfEC%Vlyx+DlTGK?dQr;S0 zs-x>TV2<`2!36)E3X6BuTh`4Dv#rVzBeM14I0o+fh&W4}cAgm_l7$mw`(52V2abo+ zNUZ*PP%^3UUHO)Kv@_WQw4#o%Xm+#kO!E6dV|T%3lieGT9OFG!NW_QuqO&tOgGSpw(Ul?K? zQp`7f9#G#Ideg>85xrSH_je2Ys2@A`meMQqnLFE{(viU^P;W6vs+XErg$c>e*>- z5AD+NqN?%9)Ks$|Zuq#lJ8riW%ojX2x1!!ck(v$&E3N4aZ?ki} zALe6wL5i-l&mP8Uy=UGkUo~KFF&#zh21yLrx_)h30I2Jz9!rmx)^alfQhx3^>*<1C z&uP`jySZQw>hu&{1d>d`_rVplkiCdpgp!iN8*mlHl0_pjv|k2lm$$T%j5L!Hr9?8w zp_L*J1&pxPs3e%lWDCeeX2Nrn7)Vdv(0P>NypF-ZW(Er*9zwGc6~qou@7R86>iz7r zpL{qCQcr31VEDkc#<`+N4SaQ_ja5}WegBFWD<%G4JI9)W2}IuL9lU6pDoFfq`ZVDqY!ZE~rTyRbz-0wJGqbjglUO;!uZnG-FZ1cC491;QtOc z%l$)BmSPy7w@Fsd|M7TCD;44u;rCvS<(I9xf!rX_sDEG(+r4^Z@Yn&j^PUL*+JZc{zgh(!wP9I^y$UOA*eQio5vdn(t&+QGT@WB zy3hXtO#$`Hl`~@QYcGvn@?TMuH;I}uQP|TwQ)r`M%*IC7n}HaQ{#rB*7}8(f2jbq;80dSodZsUN3&}~FD8LOu z>QPSehNgF6<F$bWsg75O(Dknzag z3C?ln_=Fh>@;v_Vr#t4aK7WbPbCp){J89UAA){RUi} zt2RU7TNu8tz5b51G1Ps$0Y!eGf2?og{ejhjVTm!U-NmRLULsTQr%!C)Yk`ad@mxVK z)=kr^|9Qi6+kTcGSYG)l?x6Ed+3}O3?(xOBR^ODocLBC5P0L&DA?sK148>kurY^K5UCR z*dg0AeZ3Lp6wQ_31Tja7;os zQZ%wzBi|Oj39s-9(|QEcyPxz-C~aes!2hff0bYf#nep+i2SqN|&#$f;=o-tR+Od|@ z$w9ssM&XEfZkcFw;Pmr;m0dpw^*r(6+_#Rcfed_Qk*%%3Jg_y#cjI z;P3sN?eKj}eO2^`mQzDYRu)fAvOE47uC*2c!qcDXOdKcckDZ^do;O|b^@JImfyAMA_5n#@eMEC5Jtc=ysXjYr|J%+&jC?4^G&cXB>1%v><}5tbec7ZyvB}Q3x%vmh1r3j zDtMnkP*$#S#{N>Re4NeWE0Tt)r1`vi?a+{0=GfP4SoEH5f0h6q(#38S?OZBQ!^fyY z-&?IJ@Hs?gZshGJo@Nd8^4FMRpBk7*s(oBorIf|zLE@fqse&2iV_TSVz%(C2;!i~6 zFbXt3!52coy7%L@D!$mkUwETGMXSGYuXvHaXG>5(pOo9F))~Q4u3`9IA$xmr7eo z+uC<0z8u%v!x$F)1Q%hq2!cf{yrpda%_l5et3>6t(NtP9)tEEMWCxoY^**b%h-UHn z9RISS>+$m`q`DUEoAE0SO+v01A?J4-Wkw^UR7*4E2DaafoT;;DK%)Oy zz=HWNeayebfBu-%IW!=${|IDQ{)af`pUdXIWJCYNG5<_UH5fqN0QP@woBxh@ztYi; zy5oS2|UM#lE#gY~X5LBWjMF06UF%hee`~9d+4sy5l_-5*tLD0X0u!A?B+5_-@ zJLh%-yj~IPK$+(uq+C1>xj$N8a_S&u!Kl&E@{MqYd(2rbuQ%M5JP!4oJ-**Bkv8SJ zyw2e20etst`7UqIN67o>@$J5SUNaai(*ZEX=a>9#KRir;IRL^>?+^UT7isZlkNlZ? zYi(8!-8}PN3y+&`n$Hd9`}gtf`^QA-ifkc(d2(88gs?eu3<^#s<5s1eP;yI8Hbb`s zo$K$ibanPKKWIx^{b(a-q8Wi1w)rJxp-VeHB@#t1B|S2-nSDDJnL2f%%)p}#)Anl8 zu;bGgF6yDD?md6zF$U*u76-YXdIZ^B$5fB&IkA)SarkSOLsm4%p_Z(HKb9s2JAy7i zcG6+yx?(%dQ^Q~%Bv5|SpTMQ9R_?Ano5Lf(3NKKg=Hck#^cQgB$uwvt2}h+iwP{?- z>e0nHa_xkq|Fg>M75MxwycDNZkNODVt0_77;FR_;bP1DAOxGFFkRmYF!~-Em3pm%k zq(}eksJg%w`1WBN;L2cEFFEJPIox7Ez7V)I19nb)&gi7G;I_Xr+9A#|6W-%zmpb+D zdrr^!mlRl1dLdL9HZ>C3E)AJL&BCjVfsN5!E_K| zt#->0=40;+*EB*wG3BH~!R~*dLz+>H?xt|XbQP9@mD3dFgq!^DPYDRpn^nw559D(#eE#$Q^CwiuYSggs=&Q?X?gTITu% zuY{~tNaAL&sF`VA&6x$4y7V-`EDSzr~B*;vw6r?x6ECUePP7wQPnejA>Dk`jKZN zd}^sGunly}h#s2U68HO8;dowSfF{2_8%sXziajY7ndb43JMtjb%LL)92JLuP13nxe z#jC6}lj07~VkwZQEWukb*=J{;3YhrPL*~GRj0=;?BQm3aXt^5!(6P#M$|$GU*TXQ2 z7$9RbNp2<6;πK%I7}q!$y3IjN-X)7-WA>*U<@nGs4Roujs*W>PnO)CeiIj6)$* z19nR%`qA{plo%}N{?L;xaO-wc-zUNwA8X~-kD@`wt53;IbQxM6g_rf0t2RJX%VOc! z*(%QiAo~_PIT^(O90Om}=#^~L0;mvpOc++zV$2QF`PDPMY4?(qYv~O;R&gA16A9X|{H_l`+dNgQhhIx4|CQIcXmWrh@2h z@-$79dgFBf%5^Fp0J9Q8>{6{0Y)2Y}S?oH3n2v_pErAbN;L@%zRyx!DRo- z#>5&CApc%-O6zm8S;D30f>%}_!)@qcQws(z(KC zQg`$p(1|ioQ4!Gz_{ihI{C036=KeeXB~^h8z*GH0u#PT)&#BCRN`@zuK4=J6*| zVC_{IS_S9^b)cU#Q3sAgO-t}4}4Xi@eW#vpLLC=FZ;>N%$4dYNc~+7U;Mva2o=CHo{p z8qaOmwSpK^Y*NemnEDAx3V26Ani|vyC(0)M{w~n(FM5Q9lu53cA zb&Eu=dQeCIN-_X|wy(N~smdCr_G%ecWIsKMW0RqCay3jxud0oy+HZ4o>7Nc`7s4bT z!NH-cg#_VU)xq0tPF84C${QNEp#u7%U3I9N@{5U|7Pde`6OtL0bmLFw*eyu}Y%!dd zyda&Dk$aBfEJDZI64se+BXtTLa+`NmqXHo(_8xvdXG1UPLX7kjL(&d1Q)Mp3gm;Qy zKLoV^7gQufng>?w`eN<6K56pZ<%7YSvj)5*1zU}SNf6(`nGs`Ugt=vl#$0uvwLLTH zQBND<_ZZmL^u^O?zf^*(Wj~GqR!(iQLiWwrBL9)!7v_F* z4YXG)IyfbUjGm7%$H^x^J?t@=l3bMj>{9)ZO^FUa=xkVs9UEaiUT9j$JaC0~{&+cV znT@oNmh#oe<^@PQ!$oy3+81d8$tDJFDpFWjk8Rq33qN3pR$O$)!X7pNve+s!qQ;3D zz2s2dEDd!*bTKV?58P7O3i975)U{KiEsg4$NMq0Ifp1-~7DOoT#+#JPv%8#-~Eg)q2dhg>L) z+id1qrM>5x%Xy{kd*bRzA3^0TM2Rv4;NkJx6AI(dC|zY=sEOFzGT^2t{H8wA>1OV)aQ#ZJs62KbPq7dfA%=Sy zR5cpx?X(NTQly%cg*H7y9BvKiCziz+D5uiGA(75avdw9JK6Mtz7Gb^aPEU@Jkfq5; zNO|;=-3##1k7ZiOmWy;XnjNf-iRMhV5y#;>F*9$**?2#nNnT5?dO9 zg6jnL@U>#l-^^1cT{QGY`7v0Bc~am3vJKRO>k`yB?Ps3tU>L4wnvx}g(9mK{1f2F? z`$y;X!o`k$2gyp=1m=+p@|{8iWUC#~N#WTc8fldyc1)w&!X;P0izo4e*=2>J9mmD} z4#*#ybr@{6U5O@M9COFqZOM&F06_rO+a+9N7A2}haYb;MT4rI zaY(D9O>{ldKpWT4BLg=wK?@o|TSf4ZfCnowpaUI%?=XPkAOjYZIkk(Jq{hzNl$}T- zXQLqMpD}#|Z&O2(w^(bM2CBX0(4#mICVwAw#SD8c9k(g#bE>LdWGnFF0|+hrOUcnm zYE8SUM2NItty1Gm2CcKLjIs!0yu6c74WQYX`VhxoYF*}mvw}uz2xR)&TC&h#8wQ@S z`g%nytyqIPHC2v0s2i9MNP1hk&d}mWp^(!rX8)cgKLWS6BE`R_h1DvX4!`dvmt~QB z=14`UHWf65Y7kUE8o-J00Gj*{z>qvRLJs3^<=}SKryW2@XA#5G{-H?+aZkbPPKTsc zVil(Z^9hxi@j$7!q6RdIEp7@Do*GZNA8E$H4&dDz6IuCS|Bs89}#) zoW!>zQ2GsH`WRygnm{}-GYO%lZWy~w|HG?}zmxA}2y(U^T(3g80%oR$p7*Is_qtpv~p~xO&S(uV}~DGl_a_S*IHiAyDHJx%(3C{qC81ng*cWrv)ot&mHH3v z2E#x1NcwRk;`#zwbZQ<7dx8jIxJqiYyD%yGK&hFiTXd2E~RI!zUc8a*frO#bSDHBOUo!2u!JGmkNudB=Vj z%ss_~5^tyes!8c{!GZ-IljvU7@5{^q=aTYwR0!z%SljUlx$0`l_ShrFRpaQ=#oh{7 zg$3R=_J#zq+K#3TTxjk(mG!G`dR4r(7m(Fv2fc(Z<;^jz15BG%#QXM5bAVDZPu z>bB=fXC|)u1IVR>Nk=w+-h|9^y-b&C=d~Q45B!6nLqy+Rg>Gb`C!-jtriTBqe&TO9 z@BEWYYe6yvY4{0m#_3gzo7Ut3#5}t|uV2Qq!~dO@3^u^oVO>FNylxQh^jDJ;gBSwj zEoxBIm}it85fB}%a%rJg28WQ$A#pC`gCJER$-MjM1c*Kh9*qKJsve=FIWoVAlgKGd z9ftL?lF6s>#8!^@pm6UgyA!dpNvoOoGEC>^v}ROM3We{jkPh4d-EGou z@KNW#2^fpRbEyCMHjddZJcH0)yfP#Bmq z1I|2n?zh(-ATzw_I`tIs)GDoeU_9uPyDH&=io9-z^(qq==c@@iZ_awx-OaJZ&OW)V z=k7%ga$+ll=-~11s$}xeo-x zKr3mgT1qnu(29ZbS}x|b>7NuZ2uif@`El^rp^q5@F~Fgz?Dpj9aU5u=0oqU z0rEK)=woz~J$>Nsy4>avNK7lH_X1pLG(OP5H2njbPy*WgITO|D9ei4Bdda4(Tdx;9eS$xaD~ ze3*2yC-DMtU?Ss_y38g0J)>#AOVFTVL8+U0~lioD!q-=Wn2D!B~Os43mm9%*MZU~`Cy-5n{ z#{aB;=QXO#y6cLJt)}dyspB~2%QtPu?&6WA<2DmIyk5?-kfIs!u1MrO=$cA)u%g$7 z7X{zLR|n-6k~B`evKve~s{yx&M!JV5HPDMl zA!*+^cvm&iN}QHhglITX??KIEps7=+W9jC@GwD3GM_SeKYh-iXdw-z`xhVn=LbVr`kv9U$sd*X+rHv)1(^Vc0IN zX7T6CT&CsgMY66GGO=@b85_Gi_ z%~W^1pVD!S?d?imn68^ra}rq>RU??7e5Bi6xuWGZ&9$ z&H*oE5Pfn+Wl{D>rqJj$OT~^YDp|ij$DKr-LR~$KTf1btF%=r&w$^L+0hL#hpE0m2 z*p{3G`{gny52D=&&~8PEu3S+j>#)}*E!wKWI2=f9Om^QIR;(QLM;gX0v2LPTN`H)v zcgB%|5Wm}}L>7VI*McP*N8@ZBxm(NDk6DR_0ijpB6R+yj!20o;SyKJRBw_L$|K(dQ9m1TO@SAh z5ak@NUp(l1ab?aSF4rhHHq<8;C~#UbS6s*YPichj!VS%rI`jwSs9z3Fy%mE(PU>h+ zEZ{zh?1EeyP%a4^%F;t)=P>_{1`T&9`KxlYk>lp!B~Cy)@K3-tZ>H`&I=S?9;WoL+ z6tmq-D~uusU^)o3+8RqH#)L}<4M9m6)HQg(j_Oi2{>_QX=7cr+2};x zRY^dXYw7R5vn+Kf$e@y*aWU2xx<45aJ@G?>YwAS$;k;8JwI@=4;N3N|+*i5mZZ(UO z*QbCyaxC;$M0G`q{Mup%+FFPM!-@kZ#wGuTbzMJzfuMm3vYPduo=F7mgH2~K>a^)n zEgm@ou(+};+Qiadx(NM^k?y#=X{|T%(R@jwD1d}-OHLRQZiZmzd!V40*|> z3CR@gADy$Yx@`$2h@OeWqacfklk&kS$n%`H0wj8UM%5u#OvKgp)u{K z#f;idS@!GN=eG&LiEQ4iDP;o`%hTJXt>J(w!;AL*sB|BF*n#uLZ^Icw=sEGlzDI6T zB6fhm2eZzmPSi{aNwV8KX9uiXRbsBklZ@WZLa{*nKf1m-Mw95FMqxy=kz3Ze{D^`sP6_I79 z>Z;MNX~n6UU}m~AF}5w!xu7DgcL1az^HapCuf(LkPh@q%EYj#}qmG}B zRhJtJ_-#X#_l~HyQrPhDkC~rU4BIQ9=>~js@=&E? zG6k1O^K}z8tKydJ>Wamr5E^@qkzjKa0xQ{^6!JcIsK1v1*UqWx4bdbLtp!D9Nf6G# z`{Ic0;KH;;?kyBTozV5~h5Ih}^BiD6|MX=icd85!f!`&VJID&+BGS^pvXUxQVjDFp}gq`Yd0EIS27-y5&Rxy~EZGCY^V*&SO_^DK(R zVQKkvo=p%WN_yYR(Qi*XE7)<$uygCX2c(;n@Fo~~NwIykdP*(7j4o(8C1 zy2VXf0dhbH`(qh({X#Iyo>Y#;n1^`YERJpIRku2k!;inmXC8J&k3gEvc!6mi;yzFj z)Xr-_6Z&jsuCq_Zusv?jdtc5%smKI&Mrvg)0c8>((ZGJW*++(O=H8%hk_hF0xMn#2 z&j{pnoK(=A|3(wQ{y&|JBfSO_R3$w%4Riol5_43&?VLl6%u+-0o8itOif}7CuZQ>J zQP^IUZsL2sm9dw1P8zA*@Ab`a`3l@(W2fii>RCb<`g`$eQh<=(FSFd%#q3Kq!t{Fd zZx}T4#3yumDfJb9G-kSbgDwN=`P^Sp*@?wFFHdumo|KYc)haO^1pz6>m)NMXzlsdN z0r)tkKZQv9f&Y5&oIk&l9_dG=eTj3d?ax&TUu;VFBSJ0D*BGr`irGfT21?kYJP^r6 z5Vuucb;ng;Sw(3pZD3;cC(L~!wWTjNn^PnKUy#R8e27cNnaVB1A;GO608iHX?2%f0 zO?hMZ7AE6nqDux?vg*Jvv56rzlZYZlZlPR7%bMa1J@xDb|kB>k+Kr`(ihjMJM};) zBp~#-z%#R7SF=&W|*h*OU4iA}KSXS7K0C@ipv;s)AKyUwJVkZLRE#XZq zh@u++WoGrj4prx$3YRI5Nz$q|jiU7fMnUty6vVcz_n5mM4@iL(jIs8lVmUh%(A+49 zO9}Do29*ys4IrxZ(JHD@H>9pH7GQ{ehoHn%l0BsNoP)- zbzm(G$30k@N@g*HG@F`yl<3E;SM~-X&{%)n5IB z(iP*vhA@M~GnJQw4+?y>8W6mUK{i|9aOjGMM!6t4Q8RnFMw?LXm;Nz?)Y^LctkjsZmgC?+;!&oe*e}>US z@(h^A5nF_g8&h=a2Vu7}_QvL?L`a#(FUm)TT1d-G5+cze7%xLL@tPG$GBsCnWxAlNI2R>EbpC7L+6IL87 zvcADVWH6&=;wzpiLh33cA6UxI7}wW)WZWvIuv$6xeN~p@REPCaJh_2(Q}FGIgPF|J zR4%II!C%kgKPAECl^58u0@=D#U#;v)P&aDYGyeoHIzn?cCMq_n{LFOasyUKws2lsE z{cp?uH&@BuW1|H)H>HMpf&P0ma@4BDIaoiLz2^#*v1`J8p(ukT4gU;q3*!C$xvca3TLCHti#ZtVU~)F4^cz-WMZn+E!$1xFq|9FQg71e zlYgZ#(FJ~}d&%v(d&A4LTSCWb#||Urk(Mr6qITBH;tvmyxHIbhm>(sCoiu< zWcR0g?LeX^!KGF=LRB23T+e(noPxP8?4pjb;E%8z>9@@xJoDM|CU3~8)DrxxeB>V- z8Vp%BhvcO%YkJd$9 zt-gLm@>fu%U+UFbUJfGUQ;c2^N!5_cFP58@BarBy8A-u;47< z1(gUrHGN@nn?0&1P%_3=YT$roS+W`~lXTL$65}#W2-TQM;^jG~*-&&^o zM35VhwZ^{pZObf;+Uxmbw+q|!#V3~=@)fv2yC8khD7Pqr4e^>1le#F@LCJQx9@F%1g zv{Y-9nML0;87eLyl<_Lap4Eoq-ec*teUlP-Nza*=vv^%H`_QSpOz@>-Vk%B{aOUg* zdlu+uRfff+Cx}^%R4^YhO}bmT*L>=STu2iwNfSB9C{cwN{dYh5LVM2i$|m8qcsMg# z7~7s3<(e?rT()eUU6Dypa{IFQ^5N&=Z=PN+_hpB;0Vb7^U_TQ%ZosfKhm_W#gnte0?CY~(3dQXfhsfXr&Mv(H_eNY@ z4yHm5HYai_a5-hS+EV%R!s30AAINr(+nparR080p#{kh*_)TQv=q714wz4es<1$*%7*b0{9>KmgAUxrnFAZ60WgUEJE|%s`0O@8{eXM zro(5#s`-wq?*%!%!(MafecteZOW|q?sT*c96tk&1tksiId~RAiTUr)w=pI?|xoXz= z+!tM+_SIO&&MlW(|G=xgC!QEwIJ|1NvW)c9FDoWD_GbW9Rc(vDm({ZyCNltsUR>I+ z_J7#w+y#i_7qizl4u~mQgtU@O7Faty0QIG%UT5iygb6W?an)x+51=qoNq`8p`+9BU zRq;3!(6}wx=GvnrD&Hn=%~tuE6FaVHiGnsv;thMA{xgL~t!6GoIdV_eHMJ}0%W^;0)=P z9;=8rW?Ow;#Sd-cM#E?d=1iHo#rD6Uw+FJNRr@7uk$dE<#H7+iG~}%F?T-LIYE+Vu z6aqwM^ItacOpvU^#1aQWVd&YBZ1{-(QnK!)5y%QE@I2Ay1c8;LzNT5M&89^vfMo2S z9+9-v@|G@^Q;b5{C#}M`V^=|h&BC$ox{f1_kg6S`RBrfPSTuEE=^JE0>4I*MsM>+# zNLjFMkr(9%p30qEL&@=|o-73bA&447lrgD%(%c5w_g9uA(f~HHUPwWvOk`BcV1mSn z6zJkmmZwECGNAYn7e{3}(a7ipGU=Aw$YqV;9?-8wa35&4m5?%OO4BW$et-!Ufi#Sm zftOUJ>6uso1uE($M*=b~OVyTG4mU3B`frWFWJm;MD$I5!j`GaW`z+k0Qq##G^duTC zE7hUokwRd`6v*NoC7M1t;~)8;yoK$9R({DEb`fh-U=Eo!?3}5ya7V%ktVg5_wH)-4 z(z#MtG40a@QtxQ(oCKnO=O6)B#*NPr>QFE@C*VeLu*2dZ5U5?47a&9RVFe`2q!FmdmzH!#ckm3Yvr}MwX(WMLGzMz(V8$fZMrgFj}w03 z`vN{Eo~{BQ;z)TI5U15|Tx@?f!?{8i!Jx=O`vp#Z*-ag^|K;M=k=K_ZRVXmYFsPrj z1RfzD&HQ+Wz7wf}<|YN&;yW*l!rKLdvoSCLcX??ESSImMl$=}w%g2hzd^q}lR2B=* z`DtB_@F1tm#x7k-ZM61Qacu5tv0+zTC130vkmKW{FT(osV{n@bAb9e(U9n~`R)YK) z3e9_!K}h#g7=EESFEvS;30KXJmyTjY1@27-#@Yg$b>C-}YX*%|WL`uE|cC{N@(8mcR}x z?%5!y`WnRFMf(}W6xMJfJeUz1<$R6{Tc8{dG5+{jH*Y<-^i8d}S(1ZLx0 zfPBWV?Ol1g@7vyU__q4hw@@a;N4xG;ugGLcc9ur73N8iWS|Ej4_$|f;9_F=s6<>Wa zfl%_6QL=gYc2jJ>g?Bg**m<9nMwv#V%$#39=B8}-3}>!!_71!0$VMpalp=-+$lowk z=WD|AM3~+8{q2VWxgv_E%Jy?S0A?p`I7V$+-wI!9O8?&dY$DwkXZ=8yCzpJ*G`C*D z8`Ats@FAzTN`EKLc+>L)AGdSaQFju2?(4CbyMwn!|HYu$?j$rYkO5D^Kz_4&3Zn`f zR*xX+Xbjle_F`zoBurKktn5c(w3=}Za9VuYlYQ}sAq7(G_j*@ov;1pc(>qE)W&c~J z`hNxOj8ag#e}eXKDQE_8=7-39eO?lY+BQ7xOXF>^>wbRmn!id|L-ymwy(;bakblan z_XkBG^M%fhsB$|Q%j*c)ee6@w@rcmFmL^iWuSL@92ts26j#zUxS;K1&)t#Ihig38P z$`y}2gghhc(??AsST(wsT(D(;Jf*b*9vfk5Y!Nb7Zj9ou2rw+5kaI{`sv@8{i>4-g z@3B#FHXgK=W(c6Q#6AZ3*R|++W*)U@K#2paJXtAAwGl)L317&XycnmugP;Ie5=x7% z3bIu^CFQ9IRJ^;q-D%Eufg?g3jhGtjPws&+U2MQIigS>N|QD!3vwPL zSAJ=S%aWf47br&R2*55Bht*8L+qWW5LC7sV7}Fs|65;b-WPfcfDz4x{S_K(={`a&} zT2B7~3HgWIkHqJKPh9LeRwVES1o|HcJCJxX$`@tNrlsC8=F->SkPli^1}s|8 zPS%a4rLOnshDzHfilRP+&KkOr0gpoZi)a4&D;NNPtEb@JA^Bv3i&`h(q1Mob>wGMDjcD8knHmEI*M^WDg}&Y~MoL2)L)7kqn44^FdCrsi}Y; zpc&{+AUNWr4bY!)shtPHq5-MVxB;8tM*Y)b9LHrClu2^OB;VIM!y{3o=;>9V6#wQ( zr^s`nL(#6>Th2P=25*^RfxdKMV2R+X-#y&&gI_|th?)!g$0{irF>MI#b2FyrE<206 zZvPNPPd;TMoQy%Y0N>Oq>7x-vH*fSs)b7_>BpsW)PyS|{vhJ~a1p|T)T;eeDESAgM zH6FM*!VOPNQAos8xEqX|UyQ9o-2T!$7Ew8FeMOIoh1%_OVac6^w z(FV7I%W#IKwtx+ydHiK}dDdS2t&8O6`9oPL@M3(qI5K>>NR3W8a8`B8pBGbd zF?v&O=sK*9aTZLuh3o$9US9XT;#TO2`!}1nrk)#_CF`YTU(Rq{NRZIZd@L&Wso4g^8R;_ZcCsMiS>St5XHSDxWMY50WrC#VO+Q zd$yKVZ7MwCHq2-xMr~j$FZ+FAH_?=-5UDfXrKQ9Y(yM|QMr8RND5CQU0c&|)Z|$qj z)+)XEY+*_Ev^W<0JR-<%fBDIGo@+pqmz|U0Q5?99e)TMr=5ktu{A<#F9OgeBb9cShQrjGvKJqB?Eq`K)nOR37bXKV-E_RM$qK z1r{|Xo%H(^*$>FAVK6E!UcX$enuXVxRK-HkC{&nG1HYU#pxsHzspg)Kw-?3)4<6#3 zEjL8{K%$Uq62yDBkrHLglEO-$*vrTmD(Mao7*c5-Pjt{tmPuSz7`D|b-#|;-$n>oI z&FTV=5cuUAnZAtUJYfZ~RO7}rl7oH{a}RF3^dx=}bO*GW5dvwAWwuQJ-;b0y#LOb-Q{~)8Zu82R~vk6o!yS$8ZQ%7j>c(zxZ;G7 zw_9GtVg72*TVZZ26&SPGcC0%_a$?dh9S=Q97>27*@(L-&Cdw;_?5wPEKi=mwnzj>> zb}E6yF$X+Frm|uVx5gs5#ZAXe-jenpq*+VmnW(6(Z<;G@$a`GKzBiF>_jp8u!K_%T z{*%IaQC+*~P9O7l*vzbqEH13bTyM5e7q~;wrPQTZe%T~94p@F!qw7ra@jH>_$#;U^T3wF=bB5>f@$mzxX%-5n zi8LW7#9MHKM&A9F9>QP#n?ktlFl#Tywz(dD6R%wQRxS*PCZ(pXtSUxuL-gm7xqBRK zs2a$Ts>D431*Mv8FcD=^U)#EUSo{*z^=46whH}Nx67D`ps=wG0aH=3CkDTDN*dcfe zvaA#AMRPynjD(oU)D8^UU&qkOB0w2QbMS94sceuF19w6vFBjy&-xch&8(_BaM5mlV zS+{j`!zuA!1qlyH4iaVMl8WgKj};nz{O7h~v!ha!l|bztr(-AbPVO`w_O+U6%ZRxj zuLw9$Z+tNKNzJn;TOBR_Cw`78|5aer=<%)=#!bRXjh17wK(A_hNgdcWMYX^S(w8b^ zhJqwI4Z#cflVd${lm0NZ92({}4RJqqdFY&E;g%6h4exgFk2gZs>(vGsCtT$an*@Rl zYHC3#soF}^j7attW%M60^ZkU}6)G@Z(dhYV5l+=*&#D`@Ix-C_d0EG(Bkl2D^X12s zV@yBR5Pe(1wBoH`X6bEs@{`zfaMJP1`Qb8g*+qT=m9gD$IK5Gxy;0KbWOp|RB6YmV z45d}>u~_>?ButxxVROX`{OU8d=>}G}yWN5i@&$~U@+HwVuS`OVHB$Lr6G^vK_XZ$s zo{NTH)YQiPtG3x?JFqDGK_oYp4zC zeTQ+ZGdj>99dIDMa#87E*CzB#RUFrL+u_WzimP%tEX;;#y}UXZgOO+*9Y)*JVsun7 zKQRkGZo2O&2_n5>NSuXzky2%LEKRw=@Bgug6ZN3NDxxpJvY4&tjqx)p623{`{KBoY z)PYWw?|quT(g~*LQ5g6H-9xKhkrVvd`*MabY4+_OpzKp~5J~ZYg7NCsO*| z!fX2qOcqI%gQ{zHYQ*)~B zg42F4In3VKCY9j((Wk^^yWQYk!orswpP_d&(nXMH1P|& zWLiU{tTXL&-Y*yj1WIP&D!-*k5HFS2Mn9n z+{tYaGvxh!PeJ1O#WJTx1q3vI#p6eg@_KhsTOr9`19+bEXZrH_y<~J8{${hSTwnXQ z%J*W`Gh{!5t_EmX9}6mG4ZsBR|BCxTD7~M-&#DXL1nfheWbA8iwcc#PX)Xv#@0w{H zTqNZyH1*($R9CQummyf^+8jqgQDiY8KHL0MpV5KLUJQo^{R;_MtKw3?^VeDVbpc$K z*LqQ%)u+Ezf!me;P^?TPtiO|PFg zC2|r!^&?5!waejZ@}M-r(X8Jn)qvlN#Y@4!92F|Fb&;`IIq}^!?zx%r?2`Q#SF*Ri z6x6MaWrc?YL(I)0*%wq$Llbsp?@U`hO2-|1uSAYUJS*rIEbO=`Ncz-oP{seHX{~Jm z?S%nJA)B-3>rZ)Xb#DcI0|l<+8p(Np&0U+0Kp6fWLZO$=&$)StJeV=~fHh~2g%~&U zauU&pSdJtPV2!*s8G&B_xq>;Oi(Nyax}$1@_L=7%X@?$zj!zzf2`dOmWQsQ1IK8K;kthbwr(GNl23DxRa%-bDoTOTOj^kY>X z2GvGNWeduf@bO1%>IT{w$}Q%CZb8llyCM)lBwSTP5nGxjY##DNusqf7J}n77GgB3` zp_>m~-w7rIkdUIOQ3PRz;0x=v&|Usq1cBPuxjHcwxVFPUVrjX6V70;Pl+vWZ&i8n0 zbfrOMweWHsp%KDCWe_u#&%-muSbHH)Wd2p`rq!Q-t(2UM1^~$lD1^bzuZTg#!n+9XqpK6C>*^I-jw#M&MnG`Mq3cpP?S&c~J@n{n1c~{l>!FRHX*fas+$NbhN|Jg? zVX#5u1Imfkes{&zhzsHq&b36;1`G^uU)u3^38Wz-Luv2(9GVrV;U#1^iLBum}fYn{nc zbtuazV{YH=B)>Zcs8;_<8@d09$!50Q=1x)>NC7-NX`qs!RyU7$&5|!IB}F-nd)qei z*wD)7aWm;a&tgSsZ8AYgVid;K6g*;OMqE@sd}cD3?WvUC)<&ZAUd#@6>rVA)zHqvt_*+C$|KAKtTn87Q*pk3YQCka+Ysnp6iew~}7ys4f90}Na@_udtsmaBO&W%-+Vfs0*aVXHxo zXu3#GGWv(Tof+39jlyao#mAklj5gpCRSH=C6h{i1dsrovJdgeKmv2RK7-60(WIF+Wem(7^oGl{Z73MKo`hmd>&l zc$8Jt8Fbz-wVtkXT*y1%A;a$k;F^L+r*$J7hxlS!gc+oWn#i9RcZM zt*obt5XRR1c+X?X*KzpvQL0pCWUEJ2kp-X_53t0f>K0gJwk@t#(F}!$J=`-3hNh2^ zikcI7$7WWnvqFVFXBnt`OSZ#wey?lZM}o|D67m@03fTr6$U?T1FN6Fc%A#(=eI5Qc z)^=hn7w&j9du#Scvy9jfeExLCKpXc`eBZC(;)9LL0mE@X|7F*kv;4Cq{%x&uy)%6M5A9+UY~De0ogc9abYVcMf=HbQ?!|QS zuXM}3e~GRlFX-uFB;qk$MlP@LHsAZJFuNn1R2eMa-aU;Ym~d%1g!}{|xqmiquO4pc z38=Fs>orOnC@5u-kKlYRJ3HEuK-%bvD_2>m;N@ShIgi7yak;voVkwsFJ1au0ZwO7m ze3C!)=>3^7i3@}tl~{n7c>-LroIFp324+lgKz^q)Gw3Les?#ZyEvHy+qi6^d49E^L zIW4RbZ*Z5VjY%XxLg)HiuxF3eT(GVMez{%SVz*5APoe@hu(X@%aAHfgbYcj}O|zRYA>U~ zIAs2{dQ;$tNQT7%8KA+{Z@b1gF;CWwROFdyp>cFOF2m|6bSOf#>EBW;V7fu*mFa!9 zj2bTT#lkvE2{1-AkbcC0vO&`acxI`179xeXT)1&(79{8 zhX!6T4`87im-lDEq)Z`=Zlog{uI$`CuV=UMuDO|Melmq}8lTWZO4;of;D>0x>QpaD zUCTL&ieTPOu^q2a1JbE%`tOy{i&F%gvZ8lz6k8}>DXEUZhanqmg^J$NWmckpyxgi2 zX?bSQ4mEqQ%86PS<#ZK#e2dS|rN27n4~uT1Ke`uC+~nNteEna#R{wq##i*JQAy=4$I87NLo8p(E924N9siB4@2*{jm!=;7_{_jf;(PPKaC zdvWqY0kIicG;MVjQJtPJ1?jr8_n#CSaw|Yz_wD`n5x}fj(tj}j$r&Ok2c3Ma-DZPs zmD6bhd3CZz>FbT-_9^y(7B|BuH*z!R%f=*@st@lW@O8W&rX0>VB+cgL4Mci{B_6;u zFIlik%E!9J>)E4Cjshf3K!;6#+EH(p-icj z|2-t>Bn+!?m<SzfCGOK{>%H)<8r37>FxH zrMcOVec;b{7M{+l=PR^a1fZ5!p~W;BD=G|l3~>~INI=)kHr%kRgDUTi#h} zg^;}Ey!88D+!&Mh01Cm$2e@_fl%w_RzVEl;3&*>Wl4YkgJ$l_Vh{^@8H_`c^9ZoFRWeWIw=^ZF0 zUIZC{Q3>Mh)*xL$8fZaLGQiQKZxq>W<|r@PPIC`IN!2G*dAb#poV>TSl-h;bg{T)f zpBhL~O7NgEWkMWCX<_-3q6xcQ38BB4eKhS27nGu&CbI5~-=CHG;YMq- zwI1%JM9iS?-_cic;cu??0%OkKIS+{wQ6nmPPA(2oIA#b~ZNL{Zg}qtjM(D43N{%Fn z{7hey`_z7q(uVO~?F@-hQM|Xi49fv!MLTu-6h9Fx4*dM-;NM_;Xq1y{mGqR$)mU4` z9^j;zhJ)cGm`PiV#rc#&oCjkeR<_^OugES+e`C$>%ncOTpt+=3K$j#kxm(1kD7Or) z_fX!$tR8V;qkvqwUk4Ul0ki5y%cWOveBc3Lv22aClA%3c#hr@VxA z{uaT;$tJ!%vgY{qJW{5yCM(xwYjM&scQ}75?9q+qDC{Qa&@^^@<*0`z7A|1(CH;(~ zwCaudGutL?`X^=4nGW`@M!zCESiP1kUFzZ7dB3X}BMGQpr9(p0ZT-uuiCZW^f436{ zHHD3)(->@o3`>?S17#Gt9LA*miz+U$)6HBHvlEgpKVZ5pee$C>57Ae`3N|b65^ZWO z0$iXNNFs+k7@D+n1@x-+VPo>0Y26G%dZ7o&iXlEn_Axr+%;T9U{xRDG$pb|4Ly9)4 zT#vl8rvpwE?M3q2-*!<>$Nr{)=r$@!j*~-O^lX8(pI1l>!7cu4Jo+hgPVgpq`l1{g zj79obvWHO!f1pCHVIRp?Yj_2qc1=yhxo<|?;loP%+s|}NRu*mM0psbIB-6+?B^I)P z<7PbRD>nPZa#jBFXLQMTJkvk0z_4{s?f}!)%nx`Q@Bi?{eENYr?K{A8L;f6ZVc7Cj z{w)j-GMQh7*s#0XTo3(&Z%e3`E6#1kyE6d-BiwCxv*GeelNYuew&$RP%zbBZ{3L1X zhr8OHZ@)}ZhGZ*KLoL+yqPPtPwb2!qV^Zxom>(ixU@~dssSu7*8c#c2i zm`mN}gg(%NXra2ejiWs_IK8dY7sXlC$-0ohL~yXQ6!%7HqDxAV0w*1pTS?9e3_h!n zU*w5h$U3IjoEx!4OHvUmu*@9!5tUu}iwMZuoP$FiK5=H%L#P*0j<%8nR+h&$Cof?Q zg;0t(1-T%}jSp}1E1`>p*Q_cpE$D8}X<|*08yCj}Hao~-&+u)mnld(J zadE`f^`}cpjW^)ufXHNpJIsY7H{bNjMT@D-&m8ZCeZQ`*_I!C-(I(1cwN_NOzH5n zoI?^?VfQ2OZ3>_bTP}r>a-M)Z!JXKXM- z#((rUMw|;5grg9$6!l0xd7e6SG8FKqQVZ37Q+jht_>!!5z>MC5_;edpy%A@4=SlIO zlpE=b6iw0P;<2+jp~|_ke_*^N3iP~E^Ph%yDi}m>to&*cPe^AXV(bDGIgLNEqhOg; zh;GLey%EI%?wr1(LKy=$lpxvBloI`dWeP~T&rCler{M&}hbdgIvnn29v4CW2S6C@! zc*crJ0>9#9Nk&?je|Vi==$Nh2|1v)Rv+Z(A`q;yOQWOAS*$c?1$fYBCy4m!o{J~V7 z5kjAhy3@!zL_9i`w}xzzG?k?a_8z8|XBUuP>Qt2@9WVD?u(Fda<$Xtozi%6b%0uL# zxwK~{3&Q8A-vHV4xdHUCMFGAEB;6NnO`h4+z_pZGG}Ec+smVa;r9wWS<~-5*_PO!T zRpuQ%)RJ&1?6Z}j38KBS0* zK+dBQ1&hw1#SH14b#lb&h^^A+;|A<}3_~bS1Yq`Q-}(IpSqm~p;Q$8r&B=y=AC{ z)Y2E(hpZX<{+`j z&M2Cci7Gr7;BPNiJZflnowvT!tD|C&rjTCj6(LWtWLl>yZ1$Yyj)D{0><`=W z-?26F-{EHXw5=8>Cr}q`ZM9<*`CF=n$s5#XG&QC!6s)yd!i9;oBUn0ola3l@bBrIl ze0VLD;^42v9KOND0zSOb)2BhHKsnOqQ$Z>J|4i6F7e~V# z7!{C}jhp*_q;Zjzq5J0>%+DsaOyNsM(Oo@W|K*;Sd;zgyZYp ziPbn{peo>k`aARcr$NHk3+To7c&_f(>&4=YLaDf+G40piyE8&y`$wq_=eV8D%X^^9 zh^&h*^Y_=+;IQ7u9q?h%L!e-C_Ivr4WF?fMrY_ULK+Iz@{>Bng49ripY4;>*Gg^;8 zWdqZ^BZkN1JcIlmA0bQ<4x{hRuCK=sRH4)Rw~Ivv212s3qx-kINdsgOFk<;f!WE$M zx08lBwy)1-RIZV z?7`ogM-peOt{85)tRv9xp2lP|H5SL7=PFZc4)3!9oJbw)4l+B|-nAHL?WI`RVCFCV z3X2WvPK>o&biH9QNo(|23TxlNWm{$~&~LeTWp4yMoUYD0ST}|dN$;HGEcM`0d8)(< z|2PE{#L|kV0L?e2rNEOPP)%@?G;c207zN4>e}$Jp@DJQnkHGI??@2PDYxo4)hrrTl zW}%IO7;s)$os=1rbb68MthmLosX# zw?#fSOqy|!m9^{9l&!^wD(2QB7)X=2o)+@B^&y$nqWM~Q8q7DtIM$vPMM~V|=Fd*k zwM`U5@&r#i3E?V(Ym2#HBN83n_1-;v5F!!PMAuvG*`oM)j?jDj!!VdpT$qVod zbdG3UiTq}F#4F(4Vr5zk@~L!C^vjQO-PPoJ2BxR1L?=APuy9wW1wmn^Z8G+ehN%gM zN1G;h4)B7zGI(>S5iSRkLhF$7#;)`cN7x;jBZh3%!<{h z+FAVuS&b}+z1NGhHTIch@xg9!6@Q{vM10@kBSczp5n!a32|=S=`2m=lq-*NT_Kz+! z1||gF1QG;~$WeEhlM%w?#!fC+J84+#X_88K4KLtQnj$7uCk3nqIF#(p;P6a*dv&3h z4rZW)?xJE&AwS@nh8|vDI1U9)ghHFwfGamrlT}Qa(@Q&*a!8>`!2;}|wiS_yprAaJ zCHNvyS*mEQ#8=0p_l`Wcy@Fy-1Ox`cfe#9|;?qDl{%@AIn|2Rbi13kUfrtDq@tpTt zF?Rt(p9~WUaS9nH7clPDTzr5Q&! zYr6$7yY;o|+~ODj!2%Oj0zfAZP$3N8pnx=ya@Qxgy$hr)EN**tNpl#=BcVV`{#4uV zjK5NI8=712_8Ga{p!5-K27L;#UFPMH0;~e94A1ISwV$4ut|`nf`f$^Ojf4$#M;Ax0 zGqu=x1F8ix$Wc5hib{+Ym+No0CH`8S-5(-$?5IHBktQFST;+Z?6OXVzKwON@U^S}C zuMG|`v+)kPBHWF~diaqh-iX7mK-+-*!7$LifEV^#OGO)qy%t8DKDBG<1h-0vE~C;? zcynFhzW4)e;|Ao=;yy|`zqLWgf)9w#cz&iq6j;$~r~b#WBg`&DcTEpP*07VpBBik2 zv&+2c@U<7=@@Yv?bn=5dpzZkHCmc5tGflCgbf{05-88TC(7mX)1G9AXYt=LA=Br607SRp+qUJNneM+6k|}&E z6!-*4@x%qVezO*H8AqXy*+{uG;-oIC*10s6!+FleY*`57t~Y%{Cf627=a0FZ0tcIPw=+MHa_>aHTT+aT@c5z-KnZ6Vcx2JkxL4Xl*NI=P8#Y(H6 z2YJNKo!tsu<#vYu0sb`Bmn_4c7bg<1vfI|WQ~xs*l7mgzsF1iE6tT z^M_>;SNE(NOFTC&^xHpL;5eEPG5&?@^j0Yh5#^`}7lUK+(e{^#kz#pFnV^F7rj*`? zLfL>|_?Z_MdC~(|1%)z6Y7EnfN+x{FysU{snP?nuM8drkD$ufv6rGIu!M`KH4ht^w zRxC7Nj?sSut|TW8E>mYc#tJTez**&uENA}LYL7Oj^}ncj)ArR*EUmvNe3Oqru; z1TX5yj6;(#wm=dZWs4mN*L%o!&d9cOB@Q0{Iy}>M^!-CAp|C&g5zM_x=8ciI8InSc z9$#Ktx}@58kRkApGlLmX!ZaAux9Qy_O^V3E;*Z%=Q><=i!|BM2!at9hVR*+gn{w(7M2q;ae~UPx+A@d>l{t;abOwe?C1A7GR8!5& z+`0;9i@K^ZE_Q#~R8K9M`(KKCY>-jQ@mO9FWR6JnTlUvWr#MM9`Ch0}!(DWkjxm4a ziF9uW3NXC|ElXW&_j#AIr{>=XV@&xUR`^htaf9+rB4)&aUQ^xX`q^)X&V328=pv=4 z$ETFqk#a{S(j-F98;j>UsU@i)HbM!rELi*;{X(d6e)nBwf`(zv`Hei|&;w@q$Y2s2 zNXm3}RFL;_lONv1q*Ns2q$H>LBuU!6B(lZFdO#B8J>RLRC>+WUPQn`cP|>lmy3+#uL3w^Y(QwiWZ4tpM3yX!Ui|zF0x$`-R+KE zMg;xDhbW%&Ftn(%$M9SSL-_Gzy(F=4(a7a;%=tyawM_zLgCv>=m?oO%9*E=*6se+B zPGEJEOa*5^ii$$_vk$y@mB+!)7wm;S%Gup}Y*5Pnx15HA!&j7j$shNV+lIK9p{Y3y z(5Z56kcEI0z!ppjq^xpc#sS{ih?o&|i7p;hEQa#cG%d?1Z&!#z#qkaGi4`=Jmhzoy zC>waHmL6!!^CiINq?0|J_a%3++2AnS97s0(Ko`>RMS%ad;5huPW1b{zI|ILk2{s=y zv5N-n02v`S_%ySNVvH?ooBKd;jX%qfbHSUHy%qa1*d8ai^eJ9vUpdqvxSBuO{r8_H zfBw=oD_$=e$$v;da3~Q1*o6a9$LO@J4s_hAIpF$`kRp4k3jqb#n~ShqL6Q z!44tQev^CA(CfifKd0^ORkq(@?UH{nyIZfF!QEOXc(pG4o$$TuYxX8eO{J|&u`h;hSAs*aI3PK6_4kL;PXIGOwe$u zux=#sxT(!IFn48FS6DNb)!HchGR~;wZY-+=Jyx7XTcmJ7aBD-5RaLVu1)4XLdYo4l znV5KTYN;$6%j>P?i4QaBxtJ=bfluutWfb79Lb?&8JC^Jrps_)a*iJTvU`mjq6;}O1 zSxUC-F`yCjQOfJY>W$62MGqE6ijywYCn>%CuVA?g~PGAOqt&~kr`he!xS zkXxM8iYLKQMHBuwk_o=}2xeeq8ftNaDi;8n>n3H^_n4?>+RaoYmN|}!`11!z=p{QZ zp@~qp9x(!f;&;$U_Iu3q^v9tQC5-_@LLEbZdYBY#w4W(iV6#PtKraKAE67J8_gYn5}7M|{=QW6B2Y zD9COB72RPNR4G@t8n+=>MHA7XB&*<&B&$Xmjt{3EJ?R9glF(8s9vXRbr=$mblrryk zp}kmzXK?VPtmtn~GkplkERU3VIhK~iPT$mhT*no}(sgI;YR`6=Z>as`UXk?8D^P-T zy3zll>zl(XYqmFI+qT)UlTJFeZM(ycbHa{o+qP}nwrx+odw(;}b7$`Sw@=los=aF0 z*}GP)wcZy5I;nF4m>PtGB}ri)gaY_S5^*9h#{UlBKY9SB2C)A4@tt93M_HS!)zXiI$BX>xcysX z2)8;vGB>>6tCni18#dT&ZPP7KSwE0eAS1W6e;C6buvaJ>bN5MVVO+*Dyk~57wR^o8 zb5veZyc_-2^LE_>M{4tWIhjaV<49Y)d_1^n5?~(O&$89~e0bbQ;^^u4jA%(SWyd10 zjd9gHchimBY8Qzy>A1iT!;MoPHRuEM-;TPg&e>&e`bHltPx=-{vNUGT+3*3tijKfr z5DdpcIiSjcGb0z+@rqrD>LKSHpkUoMW)XJIU74q27m#pOTYb&oukXtXcYbz&=I~|z z(|&29kvJWHYV6^^SI^m;>&qkPL;lk};J@~7n58LN?T^=WQt@}WdKSK)p$SgD2_Etk zAL;_wIlTrv!}ekyNp=d>L5H!i+||DuXZu9mrq9ceNc7wlFdBQWaQC-doVoh zMt2>A>;I@YO&~vnttGDxc>MZ&9}H}@5&%s9YWNyi`{r0Z-TGPzZhtZQkx7g^B)sE9h(N>I;Q^&etD23o`BTPt5JMQ(kX(9aueOopzUrH7Lsu3s^+&Jmfk(|D^5Hw@+YoS4k7v5L;_~swN8H}=%9=CMwDRCBBvv*OI4qVm zMzEqsf$qf*>4hcL3dtKr=zI6=V8&jlRge;9cPAcV7RwHq?2dC4V|ehtcn8=O8bl zopRklB$9ghcNEu98G6{A_zl4I`~kf(O~L>8%_Zd*DK;8SY!3r|!6%mtjZblce5D`8 zVB=q@KNpTK$gr8#w>7;t#l=`em%iaVIhNRQ?NE#z0}1sDf2VyufisickZ$kFl$Za^ z$`@7IT*2FfYYF@0PU>naLmsLm*(=@LL@nIqTHg7kW( z4X&edcX~!uSN+Vjj=FgI`Z`l|qKU3>O`=?GiwucUNn`!+z+K%4?orVj1Ee&gsNyDd z?PJ%Hm{4XiO=K-4@JJ3@Xm8-U*Y4G-Eq^xXe{w|Ip^kFrgee5K6jeuVhBcapQckSX zAIr`WaUlwe+$y{DCIt9t2n1_;nvoqj-g`!}5(+QY{n#VUP#P>Qx=-$%){zau9_q5M zdEPkSO4g=F(PwhW8|7&bR!)K&B+h}e#v^{xk0x>Z7xn~!<>hs zm4>wJrP#hvfdvqr8jiEq&!)wRZHi_aoDfXxR9m8?#oC-d=3hd9Z6g!9*++h^ww~Kj zyMgmGd!pM%b?A&Ah6d4okMpDb%qm_J^CZnqEatLw9~vmNyG#R*ZLsK7ml{b64HU?eW1#mus@i-WBEpOo%py&177U zBbxTuzT4(tf#WvRRr4tRuV?}x4>t<5ra;2W)vH{BUZj~P@F8!OhXTlq-pIJDQl{{! zE4Li`^j$#Rg0U@jnteF29%j&i^E4^$uoovYZ3^|W41t~YRstcNz8H{dkXS)Agx_Wpn%bt|4>%Ra_vu(A?mxcpMXZ_q|5k8{A~!1$bQF& zu{ZG;AtrC)&}}wEv?`KHY9?p;BX-G&mr50$N*8QO5q`xX1G}jVA3R@KY~#CiN_H!) ztk_n_$;elY)nrg9PwF9xy(cgc+xZAWjt@Y-<;+vTd8M4sf!Vv{v_UV8Km|T)C9T%J z;Ly4)HLvtQrc1kYbFq8luDP6}U~s=FoxkRm3Wt#Jrd@hBJZ-CAJ?ghBH4S`+-sHy4 zkiT&~?@J8JqtqQhWw8SEt(3PdYdl6!GU2W+taYw#q0Z=FIU^}Co+6Fo8Y`o-xD`-i zU1R60o5_20xoAmx7T(l28x!YNdbBQhls-9lW~!uT!^Nq^)odC2^)kAHpW!m__M}zA z-3>!(vRuop@Ql(k6U5R?ynZe(#O~}uPFKZ2P}kS4=UJ_(7Px=pUo!FnPcGB^WuJ^9 zcX<#^oi<((|DDaF^b0q(Cj>iM*bdMp?M8et>j5Zop<^uFJ3Noh=1$VqitUj4v>P$% znw^YMDTnFM^Ex^%ySPAMOCF!bZ1k9NzZu=+{_<>1wUQ{#dp&g(+k5W|+v7VpS%@|t zolQtp&Acbz!|KJfFw?zFbM21Ls()!MY~E#T`+B!Lv0D<3f!=pbc;)ecs{?!mY@73n zkEH?Io3MK6vnZ*`TCxxl_&CN~JN zILyWO+gj9dRAv8sW6mB5S5t~>Cp~j0uj;JNpIfy)KB{A`ruDDK!wf)OmaAwF*_2fb zS!8mPk3Oh2r!L-ZGO~%#z;mm?^E@My?YPP7%3<_h9rE-(PxIjiRp->rAMM3B{^6a; z+L*72Ey!fMmYuT1yv%P{HjYRK%-uk-Xa<4*&)5QLl7qke=L^rGn0)$O>eyJWy}e>DPv|<&$!&&O zN{{3X{t{vY;*RMhW;_!GzF|vN)B>zj#5Xy8$LzeNL=%SLaPmFeD^PpeG7|$<~5%p?B3SnqDa9k}1&nCYtQ zUeHbum;tzk^oq0y9vM5p>i(HSW?(NS*RS9XaKx||Y{$iV1TH4T>6x>&hZUbh9G)TV z+*M|eydcDg9%N?NX{d_LlPluZDm0eCR1H6%6Q(#5$%$`KqtaEaCx1dCYKvu4%_E)3 z7nR2WWRy2r&@lxLFhcQ3n^5$PbZf|m$nphqwdq0ON(z8F<2A+gskN44)qt>(kmcj4 z)y}dDw1plI?uQm#AE7<769uSlxH+wRZ%#RQ{Sl_1aco8h+T%G^P0LozT@2Fo;?vg%h ztrq)}Cd3z!_^}Ssx1zHAP-?83P`U6mvxw30p@aY=O$ z#nzU*4=}Qop-0?37HTn=w|?SjPvSvaecvFA%e`juJM$H;1oNogW%naP;h7_DaBR5% zQ~9IcCVLw@<3CCiG2j*nwYZ#V8(I!kl_^-;^92DJj@uNa0ZT{+hqTpl2IYF4)g)Z9f@Kf6ozH!v>qtC@t&y>`Df|C5lbNwvHRroSeay1d z7CzL!Z)p0+144e>yxkH3lqxZV!f$j0%T1LCC++fns}&ASZp$#|UYyrxpUe-nSYu}` zg|}J{rWNsb53&H^P66sEJkh77+?Y+B?XS^3hvQ6ScpR-~OHjp+EEPS2ezvD(ybYI| z9sM*kVHRSmyTOmxg_W9rU1@P;f&*<@+TVfTVOFeH#n~0@=|C8m~bxD?8R5+Y<+6DHXUSV_+TRi6pWw zMokPFDod{%g-NF8ugQ)4uw8OdvSZ{kS}d8gkl-pcN`RWsw@P;;xesEe(Rk_dvb)yX zx5MegSDF)PK3qb8DzjP{t5vqr$|ho8`ss)BIzCP&p#znfh$Ndzsd7y7D_+mL#%)|SknjLYAJGMLNAB{@P9G)m68g8L8t+2T&(};?bXqU!fS#5m$w&KyX+0f59o2Z zZVDQ1AChbZ-p|=*;~hZ6Ev`eZs`g-RI1~cOqGNnULhc<)RXYBg?!A3)C+cDMF^N&G zi(lm1+Gp~9Tbs)QxV)Kd+o~4TzuaXU^bYL5V*ozy_vi)QAHUtbhyt~1Q(rIzt`qYU z_KthfY3j3bCC9_x6ik21Ex3QH%i<7N>S9=pBIXn#{*&@o=SEn^u{+@Wv1Z&D~Ei1bUnf%m-=3U=GiK+&i}P{GIyku0NvBJ znvCb**pTu(1(=m-I7Cn3GfgC-jN6&>;pLs<=I5FAN9daB=IFkAXiJvsn7^vCRqSh? zNn;hN~{CnWW&LXi2D~j$aU(puns9 zyN2ri@e|5fW$TnQ2i*L&^RF2VDCNB9$j>NWe*~XXuC;ol-j}zBvL`haA!DK;aB}@Y zY(u)Lxjfbr*e;E-h6FQFL<5?oiRS}{t<>2r)Qn{2+9$o)4-pAR^Qx^Fi;Q&YaQhAA zn{HksE`aGG^Hk0Xg@Ly#gl_t8yGtJ~@=0=wNt@ZC7s%O?k@WOitKljKU8EGPE@)dV zo48TZdKv13OF5LC5**gyG_gqiwE4}HITjeUO6u&oty7>5Kg4onff-Ddbp^zqDzQT~XqpXWg& z+OgNM_JyaQ!{BP@3`*Rr)9Bj=a6)<1++CEIeNA56SCsgui!@3+QD_dpR)=QTvU-`5;3!4Ft!Ycw64m>Qh9uWQG z1B1kdYx-ee#*oNs4}n$-J)tXVPwMZLi1xLsIOsvi28|(2>Yw*&P$2eRy_szp3fOJ) zObKz`=ww&oL-9sDN3u45u3`{jY&2Mlc$~SYdqp`^FooJWtBrVRlJgy{Z5j}kBg!b({;V!3zYBKOhjy_sNhQW}Q9 zBM?bdRVd3WrPM(6e6N-CJ`4vt&I8b}ICbMz5^6e0X3TA5co=dCCJnLg?FNs(Tmlb5 z6JpET%t<1i;f`7|w{=2U-_a<{@UT$^Sv_*FxWxE(J3gjHc}*D3}6^%dw7`I7mXIA<9uT6KK-S$6z+Ix-xXvFULMpHd`3QVeB1cxKXoPPAK2H-6O^Pgx(X zG4_o0oufSu!AyK7%vDB482b+;A#d0}+8gA2w5l=cEIsa<(T`iWYoNPoB~dj6NklorUjFm^`*4alYxSWGmK0{2JvXNId3qTits2pwAa_FB z7$-G9n_f7m6U|dQJdaC)982PU=Z%^PjGCol&3WgI(szu!R*jpAX(Kio0RdsA)&TaF zN}W~>*5+w|M~e!VF93vGf7VyK7}db33U%uZTb98*z%htB(}Q+Pc2Ir?@|dt(H_gzXq}`ay)3_ilLm69(RVMb2@?8UejoCOz%PImzJlM)3#Y+-X)ceUi zjE&lm5(uVqr#ShN?2y>GyfP65CtqKw_oTRml;Rf7V>N#$h|$d{)HceBF**mw|N1n= zvcJ!{8o#aA%?Hd6xsO0lmKjjk@2r$@-!x2(DaXRq+UQ!v9CI=bp}|)`j`0zqH)Q=< za9UyU^0aJ$vstj}*KnxA`>6A$LNIbTq5~DBBDQaDHkad12;YT{y zzGrp!-Foz@hgois-cf@PLfbqzqSYR{)HpMkvX|*4HDy)26zgJose82(4m++BS&Zzq zb(k6D#*9VP#Taq<6c%&44`13|l7HHT=K_!^iwkz`(w=@m{?ZrI?Qp$Ax4Cyk ziitI+n&dKV#-J2#_YR`cn@(K^Zd=z$Vg#Oz$n^QlzA|L;yOJihMoX>YJ%Cq0N+=7$72)uL;%xC^hAxGTV=4G6woJfKx>DZspew6} z+XLJ}Fy3x$##Pid7<2_|E1RN%%B>te`iC zHb@b1@LgG)FI>GgCGe+Dhtn*rhR8HoO6A{LT15#K{*j&hN7fPLeD*GT#y7phYUu1v z_S8pJY*Sf_hhipGAux7gf$g?sRVkE z0<&ng0*fq682aRM+-HoY$nuUnFtbK(7{B0)A3sshqvsyyg#yKy!u`r>nr|bkXHd0; zog487#7o`Pm-wpC=IZtU-d~KJfyVtA3{>i~_`tv#K116vi1`E-4WCfr=8Xg%$42P^ zw61^itkJ(2H-AemBGZzK0hLm6gxL~W{1I~pLg5_~Or8;$wnh7S>#JP?Eu2{zG8BDu zeO@{mrtW_WVv`D5mZ?rtW;WFE*|8-$dX(U#hdy0{p4ICJTvUAzs1lz?re2VguJz`l z&|pqw^NkSsDcPG}L}v8b$WM=oE?68IYD>!pm!b2#%=Lr$G;-O8p;0iG3?D_~IK9+M zw-7{_@NINjr{uh*7+c*MR8T{nDAw+uj}j$Wx9rxG8AyyQ*d4{Nc@ETXqKq&B83RAD z(6U7W@-M|0B5xwV53EBL=n}D3GQD7=n^$b^!{u11Fq;&mfS>q4tl7bhqquR-{fZ;N zKX692o>y~~T4)aW^OvX#pL^sx2%ob?vId7DG`WClHM z*h~ftQ;9`7$Xt?Lvsc-B@+QJ-?V+^GMlWyH8GOK?pe&1w31JV7)my z!=6sdpi2CCYajOhry+CG_QRTyn}&k=7ohSf;H7CX2ewLIx5k#ld^KzC2AgeW1O zk~~5@uXaoTBPFi9k|&UikK?l;GS%{Y0=`L4leQJz6zS5NbnOd_9#!3hwom zqkGL(br+twfG{xdU!FrD{;=Cfn?|HhO_z&n5=HS5g$bRbpke5%R z#CMV=nHM1YHIHmHH|ij7gu)yn&1fcG*qek}u`y{Y`Rfk;>8q}+`Qu`2Y>Ls>usJwD z@AKw%NnrhRuO#gI1@hs&_q(=x^7qb^o_BLW7(mb4{pAtz&)Z3tH`-*q0mqO`JIt>S ztRV!no|daD2`|yf@ZVskmg*N1y~ZcKa*vNUw-;?kDq+xHD{DhhjP0lWwuE}Rs(ZNO z>fUe9Zx>PFOfN-iLtVO^Usxv{LcbqQzqkkMO{Cl3&f2;TKc74VswJEXZmVGHR0uAr zoB@}($2s_J&YvbZa`BN`opyr}u!{X54G|pky>w5(#SWxTcCbqXDjGb`JN4KzD$nR* zqpHRA3f>~+k6%mdbWZ9~!cOT|Au)G_I=LD>e^>|Bz59jN!nUPT5yk^wM-k>r}>+yp}o?|wI^U3cvVHI{ILq4)KN zB=aQ?T!FFyalx#jXL7Lp*Hyb3kIa1bih zV${}16CizXoy?X@enHNn;!%a7NVuBqU@RJu@(SBmT~5<)i|q8!rR#EX%i#F?#|>cM zgOxzB)QC5JiwA~4S0n(k9@uX<9Easbe%<=o2me03QnGxg)g7*^lIBE#)rY+pGeyCu zuyQrjNF(m7q`-c5nTEggUa=ie+cBxlg0Fn?f}lBg&TX#R{+y?&`80kiI{E0Hd%B$_ zBHb|Z3Z{J&F4vWDCuSP8Ajgn6&v;psxQJUf8dKMiSd-UOzp#k()M{S+eucM(D_c-$`s%ZW!I&l@dAJi(4)IWaj8HjD@Df#ip5~o3YD$#wME^RFI-A7K{AV2oNZJkvcUnVwu1wyV;MDGCLf7uLdRp+UsPU`-9M2Yn zn`>d!kmcI0EzVL8CMRY$~;>e(Gj%K6I*!k&7Bf9NguRgIh2ELp4#4V zOL6|x_U@_wwKcCrA;(tDB{Ncy(e=gY=49cgUg$4sjxAi&K4`~?u3ISG{YbFM9F~(1 z4nR?Fv|R^5BUS|Fo`yIkVX+(s^dtMJ#XOu*lCauxQSAtWO%L0QIPv`ziYRIJZ6a9R zGT%l1OuWlN7(Dgm1O3!WLvVWhLjjY?Bd{B;S)`PF^2iG(vgYBzoOa`z*JcyeWh*w!Jn5I?aFfO&}$z|}|| zo{gLn#`|E26O6PKYS-nv9}Y$nNT=kl)eDR>n+R!m?2e1>ZgecEOHhJJdmdHAOhiV1OE`*}lRUyvunn|?qR8}3L(LJ%Mi@h=(1Z)vW| z-O}6I(w!UCP_kcr>LEcbWPwzR#I?|3(m+YXjt7x@-yluObPU$IfZaAHai-viIM-s@ zL&{8M-5ce6WD}J@sWm2R;tjLK!a}g?$kAkpJLiG#`_SY^w=g!V+2v{F4=(38Q3`l` z(63BcMg^tp8hONC{fm)hU<(mmKj9i!_2)t+#v=T|WCfLvvP~ts zx#Ddn9gpGmI!rLY!hUzcCx5!x>UZetVO*nC$$c-IviskJrJHHzUF`7=#0(;vCdDMj zK+r8%@1dQHYLCqwmmQWnr@Fv<@X#7q)Xs3LPO6v>Mwwzp`CD979(P&Rr>t6e)Z@3{ zCCN%A&5lr-3JY&OT6%R`tPuxzm8!xjb9bdOotgW>Ozi*w`}#AGo)acmvnAX;oY2u5 zu^~~dKLxk>C>#X2O@usy^sDDCYIyXZQNjJ<%U{QFby7kG1qQHYbudTO7tT*Rhm;4? zus@Q`4XeKM^Y{iMJXRRi3;b;NiLN?s&XnhItlE}>%REfrHg<(%p6QG^s}8UIPv60y z({s^!%N_WD)b){SH2yNu-dXYfVn)d1TAGXkx!>r6ZGQBMRh3NY?h{l?6gfHLe)rJ) zV>Gio84`dFD#CyS4^H@!;cCY?EZL?iU|0%Jgcdw90%b@PN+qx}E^2J$sqwytkZG>Y zC_cMv2&tjx5d337GG1KD^nplkdfD=*@-X2{$zCcz!wAyP=WKWUjhGMwV?#knVGSO> z27)y13^r6j3r=)wgj`IS49()5=Q~Lm!QBReZFJg{jhycz39875t|#I!xwADjbcZ@L zXPnGZNY#0u!IuP`XB1-xlcjc+JV%oxg3ysuB-oa&S8J?SbV_TjQs zv9x0VjkBg&)0%I)@d}B9-$2mu*#_hONon~*0F5wDKc>c>Gf@c|{zT88WzL(MHV$X= z&v8Vubfx%Nk%Nzg%Hc7bQ52EG!xF3ssey<+@0%G0YTwJ|n!@F;zde1e#Ow6^p8?X6J_UTg4T>odzla`0>-UKbN0;84*M&H2bPt%75t65Eee} zJcQ(+4IYBY>AW2kbzeQaT3smRx5P;qhE5C~Q5F^+BX)8SdERIl-<_sxtG5%BTGI z(DpWN&3kzUB6q}Ua3BBLi~TMbUXaB{4ob*2WP!d8{zh+M!ni`f2TsmWxZ}9EN9N~V z&vO>TSTgkc0y$Sn4EO+m@YC}0ABG`BCkGP)8<_9Q--ebj%q&T(^dRAoY@94aY|I>S z29PvKNem!PuxuPZ{wW~(u86aTCP`w%1cpzFAOxZQf4oI`n83P8;zZv&dnPuPAOEql zU(j5$U1vw~+Nzp%1ZHX1^U3w;XuMlD^!5Ik+Dx?zV*f>WET2zhuNFj0lSUM>CyW!5 zzGHVdE`kDDl*J?X)l3wGSQW$=BwiyF8Ss6OAppSsB&TsS#Y_9_x|0p>8$belx(ein zH6``6J$V9LU!qizdtrE7U(wf>o9Bz{FT`Vn#Q9?uAz_d;ge|K*Gbc#voCL>NpIE1H z`KfY9zBuWS{T-6}IThhHDO2O#{V>iC{75gXJD6=VTL(#I(pAoCwUPFQ9f7S@ho7wl zshs$nBSZ>gO4UqS$Y#Zvur#36XHfRs|6KtXxVpbP&}Y>s4j+7SmtP+Yb9!@YMfYRD zzS^5UHN|;;Lf4v1e6!*F{Vnzl|hQG3ESVdmn94=z=c- zAY?-SDy-Noj;V|y)rny>-d|0GJoF`ay~+6@9am=|Fy#(W=W3XT?c%pCG&RO`-#ra* z;J#4^r;S~i+QqJ6XsltS&DZd=Fg%}VH%)wVNTfz_#|W50rH7iAZXM9c!nrg;u>tGr1knto^K9)!1^Y7U!PugC>qn?oMM zdknJM4XnBeqKu?4_b`?N6M)BpWj3;BXjxL<1M6e`$&&GwPkBR4sSltLnGS+CrcOOF zgw=N0o$iHgY7P3+;5Bs_BSbX76>8-Nq7P$!^Lpo0;XtOX8!`18>mKZcUGf-UQSSq^tVvRgPMX!IhAq1To}S&ra9t zYQ9hZaU$_IYC=AMYq__8@*CE%#r@?D60JXmiCD>2EZDpHmnTr}jamJ#V)x_tpXBn3 zn?L~#GhUk&&8bcf@ z^);Sd4SrCMYD;8B&*~#Ar{M`jY{OV8JYW@RH^f2Qg9KdtDaW{t8jMc>U?(dqYSr~< zPS5LF5kGYM@0XBHvq+v>(as)<;J34vk-n2AWO&Np@TE-v3 zOl5SYinZQ&HVWBZ-eH#oKs`IHXRWOytfxAL#N^E3u@@d{10`8aQTz=JI=0Ezp@i1o zRu^XLyrCJj)hWD=y|C7d;9<&9Cq?&YMC;U;#*n6jtkySesWiUwTw8QMFnckN6W5#g zB>W(Qy*ww4oaS!4DWk)?avWpt+#!H5bd1Dj|6*3g!c!EWWjBxkx?7l zGEf~huoy^%&|JmXm+n!`%(Ep&K7=O5$2KHR`pt=w2jviXYiR_^*J;}9%0Q@Vx~x>+@>%d{=-_E@oHO@C_I&29HqdzH-l4KFkcD$VffY8!`cdc*QCmH1cno-Kj z8x?ei@o4lsc6?b`Y@C-{i2RbVBfq}hurpC!A|1_t?E!BYi6p_ez+Yj!c2d{04N5(g z@`b1*aXMw#vxREhSbJWvJ1ZP!ItX6t^6o2Jz(NBnSlO)p$#2?)5oipL+O}#g$Su$B z?=wDBBZx0xID)&7yfWPvqT^_ldhHG1Y^MQM9LLC)e)%%+;J?ViIAteY9%@L|6%67;o8&wcw6j)#ujv*{(JG zm_?gNph#5|Rw`sI;5c~6xz&~YjYA+cm!6`4w5P=;Rz)7Uezuog zmPJkuAiinXjvj|2rC99#%367Wt@YdW@a$Dq49rSQ)|)MNwW@}->HcIv^_c_Rn|#jD zBY=8RW|oX)N3uLOJWF!WGXgv!z<Da=5z6<|s~26l}B%=%8t{wZhGnbN(3wOH{8_19{7ir>Ue zOk8MX;Y{Ukp-^#?fw^*SNOhx+tbpe%SZR)lY-{5enq8b1oA+K28~#&SNm#rvmY!k3 z?nN=wqmp@$H55NKL57h}6$Dmz4&$lhjl9DFQQIJPaO_-!>wx1w7(h9>D7=J=U(E^67Dmz^tG`)Zd^F5P%F z3*yW#keMzOzP2{9pHm{f56@a2al3lR)`Aek7R_q%EB!BzG}8~6fd(b=DJzQcp}L)Q z=BN<#EW44-iV^mmWVUxc4q@(;Qj~jGUyhPfhD5x^qg#b_)S+oU)~A>DrAc+07L?P zzL}L6F#aRvGdSVA#(4;?)T^3}U}=hcZq-Zzs4d*0$X`}PaFSz-ZiEhAuhD}4KyZiB z(PK}64#n4%aGGC>cLPT8BO(0GxgsI4sJ3lq|!dY%=q9B$JHDHKe>d4}^xnG;|s4T^8Rga4y6ci6|I8PWr426e?x z<4g#m$QKk68I~rc4L-Q;YWP4|Z>!!f7_cgnxOF z8*tzR9@QUFtyyiBJy->B!)B3V1yugH?rTj(LpA?BzDSm+d1+im?u<{Y%^ehi+E_jr ztotVNN$nKC;^>sGcfJfm^xJKZJXzHE2OvuqI`O=XHRF(M+BMl^OF!XO_0sl-A^Bza zP!Spf(HSpgL3$x?iSM7c0P=At7^r8530GM`6< z!$9R-wzD#jjV!UE%DqpMc`+wPY!Y5OPhyGJh|(;mfd5oK41ak|;z{YjO5ic=^^HKx zG`=>v6fhZHsv?plLvpAop09m+AgpUvGz|bkMaKR|bz<^2g!kKe3DU%7d5p>MAKi}cgjBWOx)A6N z;=ZR~9E(UN{4lsT z=wc$?$S?I5m#d4TTqMKQP%sWmIN=t;pm$Fv2|y#AxLqKz6u{D8aL2?PR$!DAE^(^W zOjdE~Avg}og7E8y&e>xNN{`yS1PvNWJ7G!L)wmUszM`ieH`&8v( z^cm4glDTynm&0ZZHo+RO?QXq8ruybCj=llshR6ZiS2WY|t^>>L85e0oX1)KWvNkfT zz+C9Zyz4-<@gOB=v{v&x+>mLf{t9r^J#$;!awI6>xNwP8$rf(m!fYdaj9fciBYkPp z7jk_lEtUgs6+Cj6b82I$v{^L__hSlm6Q%wwLqZio4D`EYNe-m6-Uit#K!bef<;?CY z*dsa8#2J56b*hDv@ZhbEW~)GpX~&{T;exntzotHv17@@(&6rn@PdMk1-;oFDZ~A)J z*;}wG#Q;LB&VE`D6)gH=ZR2@yMD;O5O6|)oG0d+(Na6ySm;sN!M4_`JFbmEkiV3)23xeY2bD+mcp!M#^1(H?F zdq(Avy;R3Q*2dYjNfF)L!>P4->_5+3DfxR(iOA|tfZ<%0#r`E*R9kNtz92}o=WGnC zPb)iB{DN5I{p5Hud&qWM4-O9EwTl`!6WA>q<<^TM;+u_33xH+`I=G_G3 z@woE$t>D)=a`s|t`}N^!tplUJAhfz`LIk7e=uK3L{Z%8KZy2tnJ(Y7**|~35f?-=A z=87JtD});?%3t@wsjJGblS7InJ&8^qSH()$3sqtAr7)W0??405Z$jZTSldbSzaCR# zzuJ@$X9)sohVrwG&YvDm7EUu-q^JSRx|3BIe)z^u-qaa5hWT0($y3b9vzMJ5CAUbF z*JHn&7)M2QG6UE0_d`??R^F_(85*_MUmO9^cT*5`uh$vOhCDB^0*hQ$OKP&@eVd6md zE5v&e+D{KsFo+MDW>#y-;OZNWYX~s1VsaYI7cJC~2R%%z-H5aD_qmhok8DP*11&{9 zESP>hFa|EAO%*Lo?C?M-xw2rNJ3oVwu{fSvTRkfMGcja{6N_nT>tw2{;pxmL2Vr=MI$7rJ_my4z?i|*;ctzDbx(OP7m_j#G!xZ1Amr7!B z;w`GN!5d3)!39Dy%xreX(dKfllBPm`DQc!o^&tPm7L> z)rJ)^7gK`JVpKdRMWQJR6{cvtgV}$Qq+r~}7deZPP$GFXCnDNKp==4LnXx{8;1TcR z?K8ih)gg(S7Dm@{y>aFtUaFgiw-+Alh|D#_wg2Ws z9ICmian(fh>ydu=S}S@76ONhA=q85f*Tw0Y4D;~yCE+%UuRQbC8mWmRmiRmF>wAYY&?gyW=14(|Wmp{;Xap%EiK& zloJB-Z(1|$m@%DVD(Almt90vhI?ridueaas<0X}}f857OgnF*P1GakJ-Zy`}_i*F> zBLn&6b|VRsy1Xl5Z9|3|y&RDvL}=idA1aTcOQL!ZhJ837hKL2{OjN_VI?mbI>}i|l z^aAgnpH*=&jc6%P;H-cqqXi<#3O172=pOwqr@~B}KwU>WJyOuP4(r2G!NvKE4bXCS z>(f#}(dF4TMplm3QcUE(a1c`bPxDmqo=*RllUm z-n13MrIoRMZPJ7`+i+@YorlkYF1zCb(Kp}U$p&UBuGc~s)Gv2`7uustoB+W(7d=`j z3doglm5%ZXo;I;s?qSo)Q^p#sq-Hs&8IW2Tij#xff# zeBG7>h2NI}^c`KEcT+AC8Mpcs-IK04sbDn5c$jEvxP)`-jG)0)q6&II*J zL)l)4qrrj9*doo7Q2vTa>Y*x<0Iz#H|B27J=h_l?x8o09uOa?|t6aTyX`bds=Ep=Q zLmgm14m_+v-%M7{gc85XC1un)g&@JPpD>o~ z*uJl;4(t{mFu%MQ?A9;Us?V#r7xCRwEQdmHpL3ew%AcYQmCY#3v105G0RMeKA=&om zYl>bwEeb>+Ea%g+1o0Sd1cFO7F~Zaoo*Mu3?mn@@DCKdmToIbwKYF4M33$5!>XYB! z%g|rbh#{Puz3a5&m3O`#-!L^XXdVfFKlOJQwd)*X$S?J$=zN!TA~sZ(73vrn2N1#) z4Ze`_rkhcu~5ABLBbdkoI3EU^pNoT3O|h)V<`dc>%hqtKS{L6d=P+hg_P7Gk+4Z{ zp9TLC`4&zmi6bHlwug4_HXT^v^XCVQfWCi+a@O$7M3c7bZu=Ng06>e@&?7s;Po*>r z%+553n;b&f!v;0S>v&k}gyEC#1cVgN6ka78LYM2?jW`o5X2*Cu~1E3RLi=6*qv z7>xzi^k4`OQ4`(>EZ;V0T_~4t_#V8O=*DNn3KP4^YNw5|J1RgvrF5N*S^pKw62V?+ zkq)VpR$j1zmLV|JH9P2)3K8$8EU@ipDtI>364a05`6a0s3YcX6`J3$JnHI9IkBO<}bS* zbe?OTL+XBxeY=pR4`9vjETqp0NdL7vLbMP39}Gev&uLU9+s_#rjMX)NhajzrvE8%2 z_&nEWWvlVVJ#f@i7tzMHyWbs@wbyhSBbe+$lu(^~CblfiNK?fVN7Du|@GFqiaG|Ga&3mi)gUj*KERNxVd4?HWGOn#wL&F*sfOFx9@JsdN+-lkz8``2Re-$!Ig z?Nx*MESyC=g0F#PAGjejW?GyIwx&j|8+(Bk8|zJ70b6#_u(=eM@`j)zBJZSw#@68KblN2nK|gX+N_;6H~md^AQh6f z^#9YKRn8iy$~=voa?%Kks{52ezh?khVskVpY@pUc$qu2s-5GsS(e>QPXPi>Qs>yH+ zIEC>{s2WT(Nm=||eA>AMqm#LsgRRsxJP+zU3cH2QG|re-NMf8B(DRNgN55YbJ0WjO zqcuDY_ZY}PPqD>vQcsa8;)9QDNl!LYzKM|*w4xy=+$Un;&mX%fOo`)6TK64I%Wku*3|eT$sJctae!jNdS8|p)N- z4^<{j4NW ztVq7V(KJLEWt>-#nU({1N!iXs#0p14{i%6=!O}Pw$jfV|H@Kuq*HJaY z9BLmOri`PS5&Qc>IKRx7Lb*@SJ5TlCQvv}3{Ixsy$f9X(MRQ^%>En3vd@6h~Vs&@G z@*mzyGZT~Fxcx;M&9#dZJO8?H^s0-Ea{DvLZWK|9sEwMx>?$N}ZO5H_JiY(&c(w_b zbbYoL!GEK%|HQq+L-ik`^|i7da}~gjIX8^*Mvppu6ObjCz5)c_FPKR3;VR^QP7DF= zx<+o8UEaBta@tU5K7Q8w$kwCI-{qd-G^w&UeB`9YsD>*~-;RqGdc$Jw3?>P$N}XmD zGL`%eYpxh+{vL3OTJv%0+`a&-@pfXmvt)*}Lw>w+;fMO1lU%VF+?OVfkFsco|CF#n zrHWkATxXrqUDCalQVtB!03}?ZXomx8UG-;`tzP=5rM~AhGnGl8*0b zg<8$s)fjZ_54Jt45m{Tx-GaXOPY)m+jzyV3qFBnM_v1sS^msyUW8;v!xNNX7n^{Ag z;jD%^{P~b&KqqVITVX2~ZcNEe2%&7RWUyhnkSJb1FOvJ_WkZost~rJo5E9O}O@g6R zl|6J6i$P|vFLlKLcq_>KIgAzX;XnbrbPJB-+_IQ(UIMVC02+M3BF<)lS~BXKhO-!e zJVHns0cUpepmfixOUBQ=S|LKF{0MEsIB@POIoWRHBgOg&zeGs=up{pqs-jpj2YLSp6Akw}GU9uf z@l?vI@ozntO?(yw+Vp2yQS|tx)q3!EwRP%%;^ifSn?zKrZUNL;?m-EnP&;^Oihl`E zG|%E|d6x&e9kp;s8}pYN>e&3&MA>e(@?7nBY%EIvOjKJX>?Q}^nJfpNRIn-$5}A+HxC)g&pVx0srB3c(ffI}8BPmf#=AX8ADK`f$Q1eNBy5xQr<6*N8zMgf0%* z&HJT7rmpdaN%Nzqp$ja~F$;ni&@(X=H@}XUu_d-PCVWVYSJ;BiS@Yckya(hRTv3oZ zT@*Qyfb9O)Q&pogVFk$D&%AO$d||45NDgWozH6nZOS~u9HbR4{_`!-erV!kqCPJe` zQ~T1&A;PA*Blw@s(OS_*Oz)p$!1jN>T7lvT>WaRQYF6qX@8nDFBb?sLOpYt7QpUAa ze1Gb7dq;BMwy&ZORBehNK}a`MFG*zzZO#PAD-KAzuuOrF8u|+Sf8hq>4R2Rqu}2E> z{8?zRAVUbt!N&e_q?CH&#q7tdgQ7un)f`Yhr2OGd^_A=Woi4=}(DwsG)@bv7t^tO$ zdo@{B2FMeH@nizQ`BGGy0~H0O9z}-v9N_Ot`V2qD(lI~C-YrbzdPFncYz~EpK3!k# zugg&L?C&e&HmH)<7;%`2t74BA%!>xy*fGzRR&9_yy46+uQ90^grNa2ios%dkDnhS9Lsnvg?G}2iB9ozz z8!>DT5%`y*rpl2)=s6yUnDtk?UzcB#^)nIwK;-B%mH6q;)ob*9iP4r|SwqY|x*)#b z*_@}X+{|bZv)Z(o(v;~Dqd0tUT7O-^zv4x+b6K{~ASJb<#UF}}`zkdoM>GP8VPVwosl5IH@MRv} zC%zS*Kz;!mDL)~@jrm83d>$wm^#F4eAah5h^XVHyTAZ$%gVkF}4KW=FU8E~>GAV2K zJ!TApLmkH13WPGwgG-afXTeaLL z7dRa%xas{642A2nU{}U)Fn-d-0ED* zu!3a>B*m??!ElY868EnPS83|VNr#a%pj1Oc-%5BwVZ*!e`}gJ?rd~o%o&hJg9+`N)|)*M{7C=Yf4LQy7P6yx2P zOoRONQwjB#o!0(Ui(n3b%Vg7ldLC4dDO7+mt+%o|LOVls%YVAe6k8w{zugB%d{B$> zzm7B7#4nMpX&d6@&DbHsvXSgs7# z-qT$5;0wFS3;xI;0rGS?r92(ds5;R4$*e_CyQ)Jgx4P!F7%(QOKE7_NL7zXZ)x=ac zOsuRB8W_?6)xn#MzRRm5o9psWN|O>ljouK+BPfMgDYIpsY%=Ats?pBVBe`f*7)#YPX4Vjp%%kn=7|o)fR{7l`nD&KwhYm8;X4bdx_TEi@wJow;HJ< z`Lt^3^dn;!$rOoca}a(akIaSJSVSWaJxrDEmDcscgQfMSTT{2TkbgLo956rifev_n zV?&pDWIL;Up?<7!<3=k_#lRZCCp>^G7&T%_*<~-reE4;xK{-_L+4~)>RUj?11hhZh zOgXLsjFVd45539EUUj98M^-LF3Ml)=j(Sow(ykUBxCaXC1UhBeOU@HQ0#(dC5XV6h zp{)38n_4E$WWim{0t$|ny75;@a#nog#`!6y4qu#Q#m?Oam74O_YUsC0&Ygn9{%sMK zGOHx;kR?-Bn1gXO8;GG>S({_O8SUcH@d4|gZHZiU9Yq?O+AIpGmB0W7ob{?FKf;Hp z!gwFIiW9oplXEKjhQYQsYU4N+kM0VR_81u0e#>r!LHTw;LfV;k-H)br93$0s^*~w zUM19|X+%}Uwv?lEb;R$q%)cHnBlcpPS>BW-&61OcQ&SvQ8e{U6Z%MG{QvvDKrs4odt|6#bHupG5o3WVtlp8__Ou%Tz=# z*8Qi9uMo7r!FNvXcb>~_*R6Pd6Bww!#+(?FFs-r;&Z?eJ)L?Q)xwB-&bM}rA+{!!k|D$*Z7=g6+xDR^vr9@lU{t+C zX-8;X&K0RmsF0SdA*Wl-OZ)C_gV>s}bvYUNYc#)8Z42+JzKdgh5c^S z(Wy?Q<9hAoa2Xw76AYO|1$a=~tzey-xyJ0lJ)oo>wK&x=YZ&+k8H@m04+34GOc?MB z;J1E>AHVb__`eGDT$l9Fk6)2{E!GCvJ5RJ_xU!xa?1VM(gSbe>QDSA#Px7{t7T$~z zs=C_D=~~-TzWpRfvup1Qz&gl0iJVJK3eMtYbM%<$8=5rpkrfY`q~K#+fK=56YBN8X zdEJ+fugv&)Y*u9^?I8nJy*zAK8g%tDU`sqx$8ZF=4SM4%b?X?; z!{0rbYUn;<3C}usHxRGUe$TQmU+YV8pI7Y$xJg}~y!w6HoU_v;3Dw+Ju=HEhm@oJg zvy5J~K|wX+7Xz(7G{<=Y^PIl#9-ha+8${cepF3T4*1hBdE*uuix1zy~n3V?$nS)|! z5Nt0H8c>_0c^ie#c5Ab5QBwmP5`oQAzUo?$pxe zK`f3`=8eDoh-2Z_uAV|y$RhY*g~>3stKE{x4s2gm$)+HWQ+Laesg1FU4VzWZE-K-2 zpNP&Ulm$UmsFA#p`wzORo${)M1v`6own4=i>ETxY=Lf(t{D57m_Aq&3nPh<;H|LIg z%mA0s{gFkUdnGAx#fV3E0$?tcv@dcL$>3&VTH9u;z}+v*oR^d~XOvpZdDfLVyQidO z>QCae;b4^~!l0`!@^wo$;`-lW!*>)KTX5_3wKa7uJAI-2(RcK5=Xg~9S@d5oM&Rzs z%vlfW&yfKCpN4{e|E_sy_R!}@+U7gYa{_HvedqVB~WkL3CDkdW8<^`tkO)1?$LGL>LruL_vCgYfW|uQirYBK1$QsH*HyWi2YgXdCn-8JcQ=6nYzB1Ge-{Gh(FsVLgznsNAxFo<)_ z!!sjizt>Bem2mfGrh}Qg!bs}7lk;>o0AMzurjn-Q>CtbeuZDiCrC{S^9CEmE83->_ zjl+&1{e`4XQp$b;qdS=T`81LH%>{Dj2gaSr7XjBVU#{M6HbVKZRs?9wS^d}E6P7o@ z&sIVuwhqDCAh5X^Tpb@ik0p!WGV-5qZCcbRM& ztX}IU&)f;OI1smb-K6&3QIlgrRDj4C|F3xIbp`|-1PeQ`paNtDN>@NNj07#%uY-HI z6sBM{G~A=%`haL1A0H_qcx8>uPm>x6`C8PVKz4=*1;c+CjLghPGmaOa_O zw7&LI8-HHDeq{WqUKF~+7c`?qH-pVYka>-GV89$#zSWjBoi7#IK9iNY1qA z@g+x+lY}@&=clzEwop(%{{YuHsU5bR{_}ZyJa3kSCr;QV27LyE1}ic@q#@G;@2T8r zB8QxW93;?ZqScmvv2n6Rx&z8`*qUzm+hSd;RbF^P)i~>4z%{o7cXG8c+IgoDxty!*1Pxr7W}vX~ zj*X3D;@MUvodQnLh=|&wutScl9$gi&x!EOc8XSxZ-M4dC&}L+qrX>u@-9esk+C{a@ zQmSZGTzQc{0O_51Cc(Pu7dj7Aq z0*Am??%HQub1=8rJRjr|E`)8pDi-x)VaHlazSk7{dvFjEPd4cs`D()>`Ye`WhC~TrAC$@HOEuDwSX!(T0EogAq)btGODfQ zh&woXfls>d`@LE(VKq>EQ|Zv;)>8>;Do_B@iPW+RPwhJ1?neFJW&H%Ofu8Ll(0`j~ z^e1m4P@mJQSOh|W8=NS0Y`jv^J{&2TBmM_!Y#SdPy<;^sO+;PTHG}EmQ#3zGq*)ZK zGNjP#;J#+#92I|A9MY?B!8mGs#a?UF5l@~W-b7Oc@7L1g<%@BvhvLCGZ#6kIS(*S$ zn7B^Tevy9-aukzOCxkTMcs1nzebaADEZd)o25bOdFRz~{EMG-a4J;~G4tU#3bb#8V zA*jwEdI4cmj#;?E`|R?Jb|*Cch@n&b^S-3icGk^1k_?WEs6GPOroN5hR$JqOeI{%e zWs{HgC7)_6rOXRg)s_zToP7{eAEy${hiHSoGHK5>cVhw{g#t|Ctl5iky_@pp2)?uuI$-rx@ChEYue&= zB!j_6i5c?kQ5@<7Osc7;)qA zJX5gpAi4870`a>9$d^;R_m`p*kygeg*`+)L11I}_o&r) zUVu$_>1W;X?&=IqkWbsq4=g*tb}#f{S%d zKgIN=O!KTFW-t9O)xn;w!seLgHGilSx*79+n&2HP?%93VW57tXYEWR>wJqnI;9KnQ zs1oC2wjf*=3$4m>Y8m!1JNi-tL_69Nck$CT90y;dcy1NN{?b|Oon*NH^tw7G>dr~l zw0Uwz!Xl3$?fIA|q;N5up##&(QpIu`I&Aks5j?tEFY=MKJrAkHj|i_a=Nboo{VNag^gF?&9NvYrsi^|R8#xre4ZRtvJ37jq-E zcTyp?VVy1b0Hr@HTptC{{Y8tCpGfM5bD+B)y80ZuRd2-LCJvkm#X! zdw$GkcDeFd?ceaS00Knza`+C&%s8AIJXxdG`kYmw)Qs>+a6k)rQ(14?77Lh727qkqaJo{~Sw7 zS(+ujLphB|JohOfD>-xGO=2GF2(SD4We&gO?D&PcSWB<-)n{7B{kVqeHa-~qemKIV zakpxU3^|j@Tu-K3c2F7lw}mvfr=<$Yu54>y|MNtnNGbm`0Jfyyej;nW}ULMvl(? ziCQN&Dc4iyFfWDDyxeK_-`*5>XKF;VoXsNUClG%ww-b_Na``An@kGnTZ%c6-wtkuZ zFF9N~bqu#+_20%N-<}YK+_J$^WLoDuDO&^PP_94wFXJ3sJ%B@{ZoeT11c2^cy_E}3 z*%x)KX79NsbMQ|*YoSOZi8c`=a_j^WftzeBa0ji&%?hA>69g6<7s-WImw@UTu(k;T zn^qrvrK`c6&phQq-QKI>+i&ES^9;LxDe4IIl4oxGt!#eiBk?U8Y_U5)JCHmw*B8u4 zF_6|BeLHKnK*uHs3_!A1J5lDNWA)k@qOsIMSot!s4$cm|Csc+-Wr4fuY$AA_&ksM68nWR*-AmuW@z4f^4-n-g*vtzO{?1QUFn*9`Z z5Sc|?+pf!LJc~EjuRZy#Tk^yNtWjd}$6p=H$+k+?yD+ed3INRYEuC=K@hSJ~@+9?Q z*wYE-NPEt5%Ow&rQ35d=aQHyPD}h?^j+t1N347DxwAy~$)6DE>&Wlu-DuG7vu9k+*_Qu=b8{wU(csMwqEPTHVduSgh68yfd1tH~!qlOMsD@ z7Xo-PK?pl+5+DFFG`3LmTwRqUPyIj&Oyay?r2R*A3>dgrhs>TRYg}!|Kjr53s1wEL(x(Ogm~K7Wk< zP5wLC+XVpJTqBdlYd5(JA75yDS8Z032wPW*anvn>58tpV0fc1skAGE6*x9|4mC3** zAl3}$2wVLd5LYTD+DFdF!CfSgxmI7Ww&*O%D=jW7D6JdK5~ z-U>p~iFA;8wJ%!p-3myzldrF{CQh2z3_JST0PnkRX2-R#RzCbP!@B1!_({JS2zoH* z{*Bk^u3+Eg-{$bVY|i9x;A=RcLV)RL?W!XV7@A!~g;M^IrjoBy__48=h5bq}s9YVM z4$VHIqQBr1IHT|cc+I3>h-_5V-x)(6Dm4p)-2s z?+TZA#H4bD?}FWsJOP*2Q^3IgjTb8hyfaf@kW@cuTDI=WxgJEY)K7Tw^W%(kWi)Ox z`2chiu4?oBtXWw3%y%CFj)uhBXtFZ z(ySII4d~Nq3lPadhfK0!ZX;}jYB*=Z)6f)m|7{{6qzs$zHP};Ms|Ag%?9HRYiA-aDh-)tPj%*4R*a)=-QgW$)t0%V-Af^u0a zAP9gD?GU~IZY(72{h&>5CXwGDP8~Z;URl&$wh9eu>Kdf?@E?g*8Ncz&=}&*n<$kjr zLf<4+M5xBkXc*4@wM_W1=LVTJ<_5{svU+Q2%z8chab2gl8NrOf`SEc$uCX*L%#%S) zy`HG`nD-=!J#u$Ax%lKj$msNTyN}Lv7q->=tlggiD5FQr`*?r+KEnPaH27)xIfSh` z@!8EnskckF4_Fb}>iv6udI#jY)ZK2KC0~(sgd1YR+#D-80aB|8rc~vX6%vQom#8sX z5wN4cS^7xn?o!Ryw(2xg*Q^#2DiAA=DmD7&R@U8*cv~)I$Z0i`q5chsmJ=$d_Lk41 zLCkvt03Hw?3{;8Ec>GG=EzU};&ym;JPMi8oWFQNJfvKvS? zzTfa3tMHvH{}?3VJNs1vp5VTC6SECmk( z9*pC;o_(r)QhQEk?b0ErqHAJzqjRLAHlE@|M?k_XtqLpZec0*b~38XU+4Q-3yS?{!$hQ(ybMvcb^mw z59T9r%uLkYpV9P|d)|x`g(t^3m!5oJf4n~rwg}u$N39VGbszM-e11ZWPtu!B8i-Ez z?bsMtPQ~XL_WC2%Mr<5k8+cx_Up(@-f|mvz0Meb>Wt6i3Q4}mSg0SfcwKiKiSQIfdXpS!r;L|7~?cY@B##Je{J?}ju+km!Y)%pRolYVd-1FL zff{p`ua>$^{ntwb<9gS#_{c)0e--EF0dVHHu=S7>7WjHx$iA2j^*pTT?POENwc;yc z2{Fyw?P&(LxF2-T1KLO`6@n4)L5N!-Azn6EP*pJTZs6>DfAm6WdVZKh&1Mr7z_}RD z0lSE93EVBqLJ+Ss+7}3L+Q%G=GVvVZw*yA2g0%_L&?~PKNqzF;f43^h7lj4!0)QA7 z3F~}h=kh@N_PH@*mc2kJtwQ#}2}Q8#&1ArY^$`5-t2F<55|+GD$EBA4u?4S~ma zF-35()#7MfJwiEWI{p20Qhd&m)MNV>8~1cnafv0RX(Z8Drb52C_|GtJqO#jR-$F&DEcgt9uP6FGjlWw)?~sgDT8x zBdsx1-!m;{4a;w&YpM7sIAHmw<}H>)Q5chGID@58_MU0Sh)!>1o_lA7031Iq^mIDg z_lbMDq_v-8y%x^JJ%QuAh7;!c)s9OKW}35b$rNXMi#lf2jw&kKNLeh( zX8LW{U#sxcis_0bN9r0fQwN+O>K6kiMcN>27TiF0fYlY*M=lqWcjJH~RYL0&MLCAJjOJPF)nt0^gVr{Rn?B{Sx6)l)#NX8&t7dlt-{ z*OBK$!$`if_TmiZx7!j!LuN_{7g>Nvi?EHFaxD@gBGrnP{DdVB#M*h|q%x@g|7bjB zK(+O?N?F>A4Gdcyu^Hyu=|npLgYRYo0-NI|_fKRiG$+7!9qc@bW^J8BCuUqFGG5E`L??%ji9TIJ|%gzDEc@P z`nP8#xIvM!QNTQ#Q&N0;EIxNxcZu;7dK9X-^Dhi= zL9JF~z#5;#j%_|h4m$XueOThCFExG_7RXDYZFfjI{^X)u;W92kV{Md+fvQ&~oGj6^ zj?I*ycvI6Wxo?ShHCTW}xR9dh0nWLKq7#DY;W!3hPf8FTkuE4q_%fye0*~TPaHA#k zKmj`r?z6clUgp7!G-3TJEP(@$rgA@CYG5ZmQ1#YBO5)UJVaoTIm|E1+{wrB2)I{jf z`!XHnIa|D%Rm^7zg)}MRz;iFV=6grFgBkkJV^gHDg>4Wq#@9gVWUZjM(wur8Ut-|i zS&|;$&jA7K{9Gy__xLxRtw5LxNR&koge|eAc+v~;RVds`spx&Lub3#L9z;JzTHsid zUP8o3PCX7r-PKbT)KqV8QH&65Ia(M$ZI@|9LbTfVNrqs!R^5!@m-i`^Gd&i>k$AZz z69{++1^3H`m9apzC}7nLiJDLK;uKfr^8OuwN`qNrM+6R=%tY;3oRFc1nDtjH(491N zQzg;c(4Itj+!Z{XI2DYN7y@Cuv1dCfoanEb*sU@F(|)3gBHx*xH!$rMe{_(pbE^xy zAt8Zt%V3(k=tY50rJH;KUh5kQHh+>#xt!r~QaBn^G2zzLR!V-d71af@P_i<*{{!uiptf|i>O)T<|9 zLV60<=ymM?Ha_Y;%&w$~^5KWZ)nC#!TtW3jSMh3+SAc zd5Y#43%a3%#X)N+=(DU_Pf6V5eElQpI4a(AqhLDRKR zRTi+L+$L_Lq5}9pLW5a`s8g2cVC|gR!mZIBKR$RifMxu?^|eO&SE_*k^xwEn3Z3Mn z+cHJu*h*-Fe{XTeU)+6?HY$>nUj_|;`U;@yMU6~7-ZGDTr)ie4AT0<7%XNNpluKz! z0;hjWF*?Pjp@-z4=y67~bp31rNg{yYu1wq`=}rN&U;0=_rNUc{e7%K4S88s3b&jll{fvY4ydrEjc4} zhi3n(>JOveuf39nUFAcs#}qt#mQ$HjFFpubypliHJIA+AdqSIROWGV`H_Zpn-AEc0#x!(k zrq|w6%#VmHPiPpRb7`g^G7h;1^3mO4knuHwOSzGJh7uyVsp<^&+302hMWPy0r&N|+ zc!v`0*3V{uZ2DHm|x6*rs<^#M7y z*3$joEm06u69gLYkO6`f*v$xm3asCU5I|sIWhG`~<{)NaOBO*O`v*FP1mqZnp!q+o z86*~v{i;IDB*{X|$qvjN1=*?0JY4@BcT7(=9z;s({~uD?y%R~zoGZf3tD@?+wJ3>Zay|6=`Ik^ z{r-U3_UU={!>u~2w{KU*68-E>_xWuSwe5Z%2*}&+eGlC7f3537HpFq^8l8@1GyJu4 zKI(ZV{Ew)n*h!+-xs=q6qq^BVQ2TW^qX+OGT3Tbwe}FaqzWWl??r+bxt+<9-9esDB zI}QL-IdAu~f%KIRllRe=#@jrqJFIs=ZY`}&HQt%PhwIz(>c$gMcss(7POF^zG@wIf z`ck1x^D%NI$i&9$=|?wJ1H0mnvp+Y5G{|WDyZcG)1qv8j{SKcs64pe5Ur3YBXt8`o z84S~#&cb|CV_n-EFJbkzd9D5-5Etpbnj?>f; z$pmg+3i0j=U-NSl8L=G1H>q9n0WO^Z^jIL4nk#f);h9Tl+|Tb<1jo^BNJp-2>R$;w zi559dzU|ooQxS*VtSpsoRG{0mcA=QKn4wX7sIRM1Y(}l8zd`918{{O)LqC$kBohXI z*BAm<6os~YXZPBK@z`(j=t74Sc8$hAw(^N`PMJsh;WQ;fmsPM%Ffl2Y3+P5K3B%we zhwT_a{D=2vFySmR+itOMd!DE0WD!e1JWD9d7l)fPm(gHLklwTZxJOmc*PW(&*Mtv`HZcF%l4Uc zMhjb12q+0fb5nM-+& zA*LkH*A%ft6M5OR`)x@$FO=f{@#VK;1qKS`JlrMke)<~pRs}AW%Z&=U5%WmR&}cml zcI+_6=5u5~+-5_r0j61wFE8#Zr{~8t*H*mpoZnw#&POp$-0&PJ+?@n7cmn$E^Vu%V zA63z4txKm&))8o6#6LuIzw#_jM>+mNz}up*_AUzPwH*(YJEy*!8{TZYvxcKOwe?z2 z&C?ToYgvUag7uxTKu?am`@1IE$PbpCo=LKlXCy+|4xBbA2DHp%_Dk#XW-pDqn{#v2 zY31@EPFmphYG<%9J58d>*BfY=zuAY;8Lp;XRw&eMtSr=W^}fz*7k}MN)c0&mi%7d; zU|BlI&5#nOTT7!ht*zkZRQ%~Ui`-x%XnH`=uS;u7V09YD5PLNn7ENlp`PHP3!sfu< zvR_j9t9^w0Ip7PBJcbnN!b;7;8&fZ)WaDecTGZxTfNVZ;$p%{13K^qxisw+Er$FqP z+^DEmGLcLhNmypj7z2Y-WOIS5K!csY-d71}F8qkq`LUUMdS7zx6nohvYdU8!NX9_U z6nimSo%nWg`uI{@`o*jh88lXT%vJd~g3AT@X~ z7gh=XzrC1(;JbHb1|2?gwK~A#vZO)=7Nw%S1Z32dRS!KgeGo%x! zleYj!79+m7i8S`o)clLd)8b>5N>k6+4PPZ*oj$8vR1 zX87#bS!}p6!9RuS`>r&);AHfZ*nzw>%OV88y%14#VLaO!qEBj+LhgcVdjqrgp*B94 z%p!Z8sKfRTudms0Lewul%j77nE+&%)S%MJtCKL!3pJv&gIBh%@B>Wwxu!r<$T?Zs! zQCh;;_2!1X7+m+*9euH*_2`5{21hJX7fD=Tzmu}&BIKdfKuO_@p-5XJ&6N#j${#iW zx8T>nD_*vh4ewhYIEGv+cn*I6?9MJc>{|>U?-6J9FQVQHINKYX4-a?j74_``nx8tF zukh0cw%B!1LesB);R8;N?*w)S>2*@5eKLmBhF`#Cdj|@E5zj`UrH%wzzwv47IY<2D zlqMgc*ew%&dQmJ(Ud$Lx zTh%sMuuo>y{uSWTi9`wH8NtEmj`hU2Nep3bmhouc{OTBlCZy2F>f>msB>DgI&xx8d zHg{ZjSQwbJ#Kt3CK25+wqd|%2B|i#Jk(Pz6S~KpM6_i4ve%knSHOmDy#sLzG;x+8_ z3guWvyNeJ#349KON(x6h-$@|F?gc8HPt`=pG=f&gT@3$Cm-^k{0>nu)Cn>NfMeSPK z7qqnKdMI595zsUN`!`KUM2e>M1+1Ej%Ll-eXN*eM-k$NGqTSARG-Vk`WDXE6r=+f)W<2~w^ABjOGYvkp;bQa%9UwqL-Y4el!mc>{zP9Z5qt}Ot(~;ef!pN zB-208k>LotXv4Yz^-hHSE*p~6Hstl@ni#bPSTl4R6-;5Hn^q6lZ~3lM8`pQUE}%bp z=oGr~n}ZIo(P`{QuFuqkrULTfm(9V_Z=2$f>1rK~qDWV0Bm7acgu|p`1i%k)RJ}b^ z>_|ReJtx2*X3Txhu-QhLSfdW5jy4s`UhPc2tyxsN`+SCpkU(}0=Zqqb7u$yH`)*E5 z^4dZDpJu_|?L$QX!fwtbXm$DF&V^NL{5^-C&K@Ah(dcR7zXBoggWr`j&xXs~_LT{e z4(7OY9}rO$G@cJX6rU-3TCwGRSgaM>_uO{@xik> z*sM$RWRw+bS!tlnZpk*PfmLGVb-!y>?(w&UNx%HXo2v5LBl??G4XG}X=R@>lAQGdr zxzXj?A7{Y?Kn})*kY+TSqyx(QiP^WoW3jylXtaLDi7G2U12o08D#u3hE2wIZ0Xpt9 zf>u#kb1o`d*y*FU(lH-9^H2S?5_E7NvD zqIV0SJ68|zd(xYh>k2diezR;JQ~eR&?Av${#NDg?7h&p}Z!eUW>OO)Bn?~JH6=c#T z-8FbQ0A*I1L)0=+OT|r&^6E6^cq5uL^jDld;bW2})JS(32E`9wCI>urridDPXY+}@ zu@wR>g_gait5m=F@??2yWOQvf{$`r7J#|dgh6AutrJ3A^zNGD5Vzmv2V&QNe-U<$> z>J=gwJ;LL-Yegbwe8Xz)bTm+7v_$=`iJyx_Csb9rnC3mB`;KsTr^%-rMQy8)^6|m^ zn@6BVjm&by`wl)n{#Gn#+^}2JMe`8j-1a!;uqK#eF~R2p6@QOK1&Fl#e+5iHc7-bN zdift;2`d-df3q$w_3Rw*xR5@s40mTCE2EOiv5c_My5xl%;OdF$YoK9V`#V2T<#>B? z?Q-KSxa3y`Rc5mu9{( zDM#2sB>sY9YuG|2cq4|fkwVw|@w1oZw|=J{4{LA6xX1r1015y0klKIRKmECXQ-D!8 zAtd?a2c?0g2e@{V0TElAQSBxzrwibOv(~sU>z$@lhxfuDm?)0cQ{|pkpbt)g>sM^P zVuVuYr0*9F(}nj>s|05Z&Lvl-(!0ke*!1NV4y|MO&D1CV>JLSr*JQM*x=D#PA zxpL1;_`|NHU3TT($NV$j{VY3w55hX{b>ELkB{)k^LC@E)NdoSs-l56Qbops4+FP`G zlE-1tc-#LTWi+)XIbo4!={w3dk5@Dkg|y5Howba!2UI6&_uf?*3BV{g+sYgC2ik%X8qke3RzDnd#C?PpRe^9B$J z{XJgCHENgB++@}KfXZs?Uad(iYFhOwXA`D_*CTtb1XwIHoU9!|U?go8uPVVJ>!BA9)k>7~KE`m@HJ81OwoUqy zn|sloX(i~|VCJBIyNQl$Wb(PUX-rDjSkV-qf2dTWkP?^tYjFUsI0)OF0_rOL5)hR5 za=Nd^lIhy95Sti>8yNzu@WVrdbpb1h=z)wXDC;FVJTPNe%0TG_E@*R&xzBBY!gi7Z z66>Sa!Ic#4h8DbFS^TA)#SUl}u5Ni4Np(rjN+|__=(I3@nPC|@kj(0+L=1TW$0d;4 z#YSsVg|JL24r2k;_08C%^WPr9NwKd)S3HH+P2fz&sVfrW#y4mu65|tOm)P`Df;`2e zmDpM*AV%NeR25=#XVA zH}uxE_u5QwAU8#01}&*hS|@k>I-_ z0UzPHE2KxVE&RU}6hFR58j;i#Eak1q)C_R5hCoDXw8K2er6UE(rLm6=_(3>HRM=A* zu;JWkj>9=Sx3CHr=V_Ar0S0xXLgp0MVf6h3NzpxjiXM{Giahx`@g*E(**3EG%nOHR-VN z3A|D>M3`gJCPcf5ncL3Huhyw$%v6U|XO=3;#@eymo~V&2nQJSB$5fGVBAW{eOQqr2 zS<0p4Egf$%6AturUtpyc6|HmEaLuNF*D`(Y=32K!XI*Fdhwhh?-cDS+ycN`V_{ilC z-G7@g!W<&cd{#T;TniVdF4#d7nwEnE9;n0s|G1*-?>Vf!*!Lzj9&obK_d3_ByPJYM zcN2AV4W=tRwnRh?1xv-(j5flcaxRmpc1~ZDAFhmHYKTdNirb3Jm)`_hWOwX;Jx?at zUMtDHwGwE(9SSe${Pj`|C57zy%>hCv&l5v;!@UqHvrCP+aV)<~&K8O&8{%se(ObY+ z(!@SgBy$4GX)yM90BGbiWjI{Lx8 z#3y8{TRkng$>j{W<`sPT#N20paLrnt%9#5=qj%_$|GRQXKqbxKZAMcKBy zXeHR)9*aE`0xz8M3RcYQTh|S<1Ef0_e5|zw z>E{}`NuMvcrk~^YzX^{50z;Qk;{qO$5O3Nkkx9JY!@s zG&5#1G-P5jGGQ`dIALXCGchw_GBh`1HDWVkFg`qEWHK}}W-~NoVlpyeGGRDjWnwci zGh#9{H)AzoGh;A5T_8R_3UhRFWnpa!c${Nm00AaOMvIlS(yIqHtqbhVB!oDp76SmScN_4NGXk-f H9rpqiIR>3q From 0cf869e56a8c3421f0710acf090158add82adf70 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 5 Jan 2017 18:30:01 -0800 Subject: [PATCH 3/6] add multiple shared memory blocks, to allow multiple simultaneous connections. At the moment, MAX_SHARED_MEMORY_BLOCKS = 2 Note that the amount of shared memory is limited on many systems, 32MB, while one block is already over 1MB at the moment... You can connect to SHARED_MEMORY using the current key, and key+1. There are a few commands that cannot currently be executed in parallel among multiple connections, since the implementation of the server caches some data: rendering image (getCameraData), getting contact point data and getting debug lines. --- .../SharedMemory/PhysicsServerExample.cpp | 18 +- .../PhysicsServerSharedMemory.cpp | 258 ++++++++++-------- 2 files changed, 138 insertions(+), 138 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index ca4d9e204..889c3a5b8 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -1439,23 +1439,7 @@ void PhysicsServerExample::stepSimulation(float deltaTime) - #if 0 - if (m_options == PHYSICS_SERVER_USE_RTC_CLOCK) - { - btClock rtc; - btScalar endTime = rtc.getTimeMilliseconds() + deltaTime*btScalar(800); - - while (rtc.getTimeMilliseconds()m_childGuiHelper->getRenderInterface()) { diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.cpp b/examples/SharedMemory/PhysicsServerSharedMemory.cpp index 5c967c9c4..004bc048c 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsServerSharedMemory.cpp @@ -14,7 +14,8 @@ #include "PhysicsServerCommandProcessor.h" - +//number of shared memory blocks == number of simultaneous connections +#define MAX_SHARED_MEMORY_BLOCKS 2 struct PhysicsServerSharedMemoryInternalData { @@ -25,7 +26,7 @@ struct PhysicsServerSharedMemoryInternalData SharedMemoryInterface* m_sharedMemory; bool m_ownsSharedMemory; - SharedMemoryBlock* m_testBlock1; + SharedMemoryBlock* m_testBlocks[MAX_SHARED_MEMORY_BLOCKS]; int m_sharedMemoryKey; bool m_isConnected; bool m_verboseOutput; @@ -34,27 +35,31 @@ struct PhysicsServerSharedMemoryInternalData PhysicsServerSharedMemoryInternalData() :m_sharedMemory(0), m_ownsSharedMemory(false), - m_testBlock1(0), - m_sharedMemoryKey(SHARED_MEMORY_KEY), + m_sharedMemoryKey(SHARED_MEMORY_KEY), m_isConnected(false), m_verboseOutput(false), m_commandProcessor(0) { - + + for (int i=0;im_serverCommands[0]; + SharedMemoryStatus& serverCmd =m_testBlocks[blockIndex]->m_serverCommands[0]; serverCmd .m_type = statusType; serverCmd.m_sequenceNumber = sequenceNumber; serverCmd.m_timeStamp = timeStamp; return serverCmd; } - void submitServerStatus(SharedMemoryStatus& status) + void submitServerStatus(SharedMemoryStatus& status,int blockIndex) { - m_testBlock1->m_numServerCommands++; + m_testBlocks[blockIndex]->m_numServerCommands++; } }; @@ -117,39 +122,41 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface* int counter = 0; - do - { - - m_data->m_testBlock1 = (SharedMemoryBlock*)m_data->m_sharedMemory->allocateSharedMemory(m_data->m_sharedMemoryKey, SHARED_MEMORY_SIZE,allowCreation); - if (m_data->m_testBlock1) - { - int magicId =m_data->m_testBlock1->m_magicId; - if (m_data->m_verboseOutput) - { - b3Printf("magicId = %d\n", magicId); - } - - if (m_data->m_testBlock1->m_magicId !=SHARED_MEMORY_MAGIC_NUMBER) - { - InitSharedMemoryBlock(m_data->m_testBlock1); - if (m_data->m_verboseOutput) - { - b3Printf("Created and initialized shared memory block\n"); - } - m_data->m_isConnected = true; - } else - { - m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey, SHARED_MEMORY_SIZE); - m_data->m_testBlock1 = 0; - m_data->m_isConnected = false; - } - } else - { - b3Error("Cannot connect to shared memory"); - m_data->m_isConnected = false; - } - } while (counter++ < 10 && !m_data->m_isConnected); + for (int block=0;blockm_testBlocks[block] = (SharedMemoryBlock*)m_data->m_sharedMemory->allocateSharedMemory(m_data->m_sharedMemoryKey+block, SHARED_MEMORY_SIZE,allowCreation); + if (m_data->m_testBlocks[block]) + { + int magicId =m_data->m_testBlocks[block]->m_magicId; + if (m_data->m_verboseOutput) + { + b3Printf("magicId = %d\n", magicId); + } + + if (m_data->m_testBlocks[block]->m_magicId !=SHARED_MEMORY_MAGIC_NUMBER) + { + InitSharedMemoryBlock(m_data->m_testBlocks[block]); + if (m_data->m_verboseOutput) + { + b3Printf("Created and initialized shared memory block\n"); + } + m_data->m_isConnected = true; + } else + { + m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey+block, SHARED_MEMORY_SIZE); + m_data->m_testBlocks[block] = 0; + m_data->m_isConnected = false; + } + } else + { + b3Error("Cannot connect to shared memory"); + m_data->m_isConnected = false; + } + } while (counter++ < 10 && !m_data->m_isConnected); + } if (!m_data->m_isConnected) { b3Error("Server cannot connect to shared memory.\n"); @@ -167,71 +174,77 @@ void PhysicsServerSharedMemory::disconnectSharedMemory(bool deInitializeSharedMe { b3Printf("releaseSharedMemory1\n"); } - if (m_data->m_testBlock1) - { - if (m_data->m_verboseOutput) - { - b3Printf("m_testBlock1\n"); - } - if (deInitializeSharedMemory) - { - m_data->m_testBlock1->m_magicId = 0; - if (m_data->m_verboseOutput) - { - b3Printf("De-initialized shared memory, magic id = %d\n",m_data->m_testBlock1->m_magicId); - } - } - btAssert(m_data->m_sharedMemory); - m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey, SHARED_MEMORY_SIZE); - } - if (m_data->m_sharedMemory) - { - if (m_data->m_verboseOutput) - { - b3Printf("m_sharedMemory\n"); - } - if (m_data->m_ownsSharedMemory) - { - delete m_data->m_sharedMemory; - } - m_data->m_sharedMemory = 0; - m_data->m_testBlock1 = 0; - } + for (int block = 0;blockm_testBlocks[block]) + { + if (m_data->m_verboseOutput) + { + b3Printf("m_testBlock1\n"); + } + if (deInitializeSharedMemory) + { + m_data->m_testBlocks[block]->m_magicId = 0; + if (m_data->m_verboseOutput) + { + b3Printf("De-initialized shared memory, magic id = %d\n",m_data->m_testBlocks[block]->m_magicId); + } + } + btAssert(m_data->m_sharedMemory); + m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey+block, SHARED_MEMORY_SIZE); + } + if (m_data->m_sharedMemory) + { + if (m_data->m_verboseOutput) + { + b3Printf("m_sharedMemory\n"); + } + if (m_data->m_ownsSharedMemory) + { + delete m_data->m_sharedMemory; + } + m_data->m_sharedMemory = 0; + m_data->m_testBlocks[block] = 0; + } + } } void PhysicsServerSharedMemory::releaseSharedMemory() { - if (m_data->m_verboseOutput) - { - b3Printf("releaseSharedMemory1\n"); - } - if (m_data->m_testBlock1) + for (int block = 0;blockm_verboseOutput) - { - b3Printf("m_testBlock1\n"); - } - m_data->m_testBlock1->m_magicId = 0; - if (m_data->m_verboseOutput) - { - b3Printf("magic id = %d\n",m_data->m_testBlock1->m_magicId); - } - btAssert(m_data->m_sharedMemory); - m_data->m_sharedMemory->releaseSharedMemory( m_data->m_sharedMemoryKey -, SHARED_MEMORY_SIZE); - } - if (m_data->m_sharedMemory) - { - if (m_data->m_verboseOutput) - { - b3Printf("m_sharedMemory\n"); - } - if (m_data->m_ownsSharedMemory) - { - delete m_data->m_sharedMemory; - } - m_data->m_sharedMemory = 0; - m_data->m_testBlock1 = 0; + if (m_data->m_verboseOutput) + { + b3Printf("releaseSharedMemory1\n"); + } + if (m_data->m_testBlocks[block]) + { + if (m_data->m_verboseOutput) + { + b3Printf("m_testBlock1\n"); + } + m_data->m_testBlocks[block]->m_magicId = 0; + if (m_data->m_verboseOutput) + { + b3Printf("magic id = %d\n",m_data->m_testBlocks[block]->m_magicId); + } + btAssert(m_data->m_sharedMemory); + m_data->m_sharedMemory->releaseSharedMemory( m_data->m_sharedMemoryKey+block + , SHARED_MEMORY_SIZE); + } + if (m_data->m_sharedMemory) + { + if (m_data->m_verboseOutput) + { + b3Printf("m_sharedMemory\n"); + } + if (m_data->m_ownsSharedMemory) + { + delete m_data->m_sharedMemory; + } + m_data->m_sharedMemory = 0; + m_data->m_testBlocks[block] = 0; + } } } @@ -250,30 +263,33 @@ void PhysicsServerSharedMemory::enableRealTimeSimulation(bool enableRealTimeSim) void PhysicsServerSharedMemory::processClientCommands() { - if (m_data->m_isConnected && m_data->m_testBlock1) + for (int block = 0;blockm_commandProcessor->replayLogCommand(&m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); - - ///we ignore overflow of integer for now - if (m_data->m_testBlock1->m_numClientCommands> m_data->m_testBlock1->m_numProcessedClientCommands) + if (m_data->m_isConnected && m_data->m_testBlocks[block]) { - - - //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands - btAssert(m_data->m_testBlock1->m_numClientCommands==m_data->m_testBlock1->m_numProcessedClientCommands+1); + m_data->m_commandProcessor->replayLogCommand(&m_data->m_testBlocks[block]->m_bulletStreamDataServerToClientRefactor[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); - const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0]; + ///we ignore overflow of integer for now + if (m_data->m_testBlocks[block]->m_numClientCommands> m_data->m_testBlocks[block]->m_numProcessedClientCommands) + { + - m_data->m_testBlock1->m_numProcessedClientCommands++; - //todo, timeStamp - int timeStamp = 0; - SharedMemoryStatus& serverStatusOut = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp); - bool hasStatus = m_data->m_commandProcessor->processCommand(clientCmd, serverStatusOut,&m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); - if (hasStatus) - { - m_data->submitServerStatus(serverStatusOut); - } - + //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands + btAssert(m_data->m_testBlocks[block]->m_numClientCommands==m_data->m_testBlocks[block]->m_numProcessedClientCommands+1); + + const SharedMemoryCommand& clientCmd =m_data->m_testBlocks[block]->m_clientCommands[0]; + + m_data->m_testBlocks[block]->m_numProcessedClientCommands++; + //todo, timeStamp + int timeStamp = 0; + SharedMemoryStatus& serverStatusOut = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp,block); + bool hasStatus = m_data->m_commandProcessor->processCommand(clientCmd, serverStatusOut,&m_data->m_testBlocks[block]->m_bulletStreamDataServerToClientRefactor[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); + if (hasStatus) + { + m_data->submitServerStatus(serverStatusOut,block); + } + + } } } } From 8e554a0c1b3a7f1907015140f306fe0b68de8c8f Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 6 Jan 2017 09:49:03 -0800 Subject: [PATCH 4/6] allow creation of multiple shared memory segments --- .../PhysicsServerSharedMemory.cpp | 112 +++++++----------- examples/SharedMemory/PosixSharedMemory.cpp | 74 +++++++++--- src/LinearMath/btAlignedObjectArray.h | 15 ++- 3 files changed, 109 insertions(+), 92 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.cpp b/examples/SharedMemory/PhysicsServerSharedMemory.cpp index 004bc048c..f19620cbd 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsServerSharedMemory.cpp @@ -28,7 +28,7 @@ struct PhysicsServerSharedMemoryInternalData SharedMemoryBlock* m_testBlocks[MAX_SHARED_MEMORY_BLOCKS]; int m_sharedMemoryKey; - bool m_isConnected; + bool m_areConnected[MAX_SHARED_MEMORY_BLOCKS]; bool m_verboseOutput; PhysicsServerCommandProcessor* m_commandProcessor; @@ -36,8 +36,7 @@ struct PhysicsServerSharedMemoryInternalData :m_sharedMemory(0), m_ownsSharedMemory(false), m_sharedMemoryKey(SHARED_MEMORY_KEY), - m_isConnected(false), - m_verboseOutput(false), + m_verboseOutput(false), m_commandProcessor(0) { @@ -45,7 +44,7 @@ struct PhysicsServerSharedMemoryInternalData for (int i=0;im_commandProcessor->deleteDynamicsWorld(); delete m_data->m_commandProcessor; - delete m_data; + + if (m_data->m_sharedMemory) + { + if (m_data->m_verboseOutput) + { + b3Printf("m_sharedMemory\n"); + } + if (m_data->m_ownsSharedMemory) + { + delete m_data->m_sharedMemory; + } + m_data->m_sharedMemory = 0; + } + + + delete m_data; } void PhysicsServerSharedMemory::resetDynamicsWorld() @@ -112,18 +127,22 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface* bool allowCreation = true; + bool allConnected = false; + - if (m_data->m_isConnected) - { - b3Warning("connectSharedMemory, while already connected"); - return m_data->m_isConnected; - } + int counter = 0; for (int block=0;blockm_areConnected[block]) + { + allConnected = true; + b3Warning("connectSharedMemory, while already connected"); + continue; + } do { @@ -143,26 +162,26 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface* { b3Printf("Created and initialized shared memory block\n"); } - m_data->m_isConnected = true; + m_data->m_areConnected[block] = true; } else { m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey+block, SHARED_MEMORY_SIZE); m_data->m_testBlocks[block] = 0; - m_data->m_isConnected = false; + m_data->m_areConnected[block] = false; } } else { b3Error("Cannot connect to shared memory"); - m_data->m_isConnected = false; + m_data->m_areConnected[block] = false; } - } while (counter++ < 10 && !m_data->m_isConnected); + } while (counter++ < 10 && !m_data->m_areConnected[block]); + if (!m_data->m_areConnected[block]) + { + b3Error("Server cannot connect to shared memory.\n"); + } } - if (!m_data->m_isConnected) - { - b3Error("Server cannot connect to shared memory.\n"); - } - return m_data->m_isConnected; + return allConnected; } @@ -193,59 +212,15 @@ void PhysicsServerSharedMemory::disconnectSharedMemory(bool deInitializeSharedMe btAssert(m_data->m_sharedMemory); m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey+block, SHARED_MEMORY_SIZE); } - if (m_data->m_sharedMemory) - { - if (m_data->m_verboseOutput) - { - b3Printf("m_sharedMemory\n"); - } - if (m_data->m_ownsSharedMemory) - { - delete m_data->m_sharedMemory; - } - m_data->m_sharedMemory = 0; - m_data->m_testBlocks[block] = 0; - } + m_data->m_testBlocks[block] = 0; + m_data->m_areConnected[block] = false; + } } void PhysicsServerSharedMemory::releaseSharedMemory() { - for (int block = 0;blockm_verboseOutput) - { - b3Printf("releaseSharedMemory1\n"); - } - if (m_data->m_testBlocks[block]) - { - if (m_data->m_verboseOutput) - { - b3Printf("m_testBlock1\n"); - } - m_data->m_testBlocks[block]->m_magicId = 0; - if (m_data->m_verboseOutput) - { - b3Printf("magic id = %d\n",m_data->m_testBlocks[block]->m_magicId); - } - btAssert(m_data->m_sharedMemory); - m_data->m_sharedMemory->releaseSharedMemory( m_data->m_sharedMemoryKey+block - , SHARED_MEMORY_SIZE); - } - if (m_data->m_sharedMemory) - { - if (m_data->m_verboseOutput) - { - b3Printf("m_sharedMemory\n"); - } - if (m_data->m_ownsSharedMemory) - { - delete m_data->m_sharedMemory; - } - m_data->m_sharedMemory = 0; - m_data->m_testBlocks[block] = 0; - } - } + disconnectSharedMemory(true); } @@ -265,7 +240,8 @@ void PhysicsServerSharedMemory::processClientCommands() { for (int block = 0;blockm_isConnected && m_data->m_testBlocks[block]) + + if (m_data->m_areConnected[block] && m_data->m_testBlocks[block]) { m_data->m_commandProcessor->replayLogCommand(&m_data->m_testBlocks[block]->m_bulletStreamDataServerToClientRefactor[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); diff --git a/examples/SharedMemory/PosixSharedMemory.cpp b/examples/SharedMemory/PosixSharedMemory.cpp index 0297d43e2..16c439d48 100644 --- a/examples/SharedMemory/PosixSharedMemory.cpp +++ b/examples/SharedMemory/PosixSharedMemory.cpp @@ -1,6 +1,7 @@ #include "PosixSharedMemory.h" #include "Bullet3Common/b3Logging.h" #include "LinearMath/btScalar.h" //for btAssert +#include "LinearMath/btAlignedObjectArray.h" //Windows implementation is in Win32SharedMemory.cpp #ifndef _WIN32 @@ -16,16 +17,28 @@ #endif +struct btSharedMemorySegment +{ + int m_key; + int m_sharedMemoryId; + void* m_sharedMemoryPtr; + bool m_createdSharedMemory; + + btSharedMemorySegment() + : m_sharedMemoryId(-1), + m_sharedMemoryPtr(0), + m_createdSharedMemory(true) + { + } + +}; + struct PosixSharedMemoryInteralData { - bool m_createdSharedMemory; - int m_sharedMemoryId; - void* m_sharedMemoryPtr; - + btAlignedObjectArray m_segments; + + PosixSharedMemoryInteralData() - :m_createdSharedMemory(false), - m_sharedMemoryId(-1), - m_sharedMemoryPtr(0) { } }; @@ -67,9 +80,12 @@ void* PosixSharedMemory::allocateSharedMemory(int key, int size, bool allowCr b3Error("shmat returned -1"); } else { - m_internalData->m_createdSharedMemory = allowCreation; - m_internalData->m_sharedMemoryId = id; - m_internalData->m_sharedMemoryPtr = result.ptr; + btSharedMemorySegment seg; + seg.m_key = key; + seg.m_createdSharedMemory = allowCreation; + seg.m_sharedMemoryId = id; + seg.m_sharedMemoryPtr = result.ptr; + m_internalData->m_segments.push_back(seg); return result.ptr; } } @@ -82,14 +98,33 @@ void* PosixSharedMemory::allocateSharedMemory(int key, int size, bool allowCr void PosixSharedMemory::releaseSharedMemory(int key, int size) { #ifdef TEST_SHARED_MEMORY - if (m_internalData->m_sharedMemoryId < 0) + + btSharedMemorySegment* seg = 0; + int i=0; + + for (i=0;im_segments.size();i++) + { + if (m_internalData->m_segments[i].m_key == key) + { + seg = &m_internalData->m_segments[i]; + break; + } + } + + if (0==seg) + { + b3Error("PosixSharedMemory::releaseSharedMemory: shared memory key not found"); + return; + } + + if (seg->m_sharedMemoryId < 0) { b3Error("PosixSharedMemory::releaseSharedMemory: shared memory id is not set"); } else { - if (m_internalData->m_createdSharedMemory) + if (seg->m_createdSharedMemory) { - int result = shmctl(m_internalData->m_sharedMemoryId,IPC_RMID,0); + int result = shmctl(seg->m_sharedMemoryId,IPC_RMID,0); if (result == -1) { b3Error("PosixSharedMemory::releaseSharedMemory: shmat returned -1"); @@ -97,15 +132,18 @@ void PosixSharedMemory::releaseSharedMemory(int key, int size) { b3Printf("PosixSharedMemory::releaseSharedMemory removed shared memory"); } - m_internalData->m_createdSharedMemory = false; - m_internalData->m_sharedMemoryId = -1; + seg->m_createdSharedMemory = false; + seg->m_sharedMemoryId = -1; } - if (m_internalData->m_sharedMemoryPtr) + if (seg->m_sharedMemoryPtr) { - shmdt(m_internalData->m_sharedMemoryPtr); - m_internalData->m_sharedMemoryPtr = 0; + shmdt(seg->m_sharedMemoryPtr); + seg->m_sharedMemoryPtr = 0; b3Printf("PosixSharedMemory::releaseSharedMemory detached shared memory\n"); } } + + m_internalData->m_segments.removeAtIndex(i); + #endif } diff --git a/src/LinearMath/btAlignedObjectArray.h b/src/LinearMath/btAlignedObjectArray.h index 146ae72e8..56f8189c1 100644 --- a/src/LinearMath/btAlignedObjectArray.h +++ b/src/LinearMath/btAlignedObjectArray.h @@ -476,15 +476,18 @@ protected: return index; } + void removeAtIndex(int index) + { + if (index Date: Fri, 6 Jan 2017 09:55:22 -0800 Subject: [PATCH 5/6] avoid creating shared memory segments with same key multiple times --- examples/SharedMemory/PosixSharedMemory.cpp | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/examples/SharedMemory/PosixSharedMemory.cpp b/examples/SharedMemory/PosixSharedMemory.cpp index 16c439d48..9c16b3fe7 100644 --- a/examples/SharedMemory/PosixSharedMemory.cpp +++ b/examples/SharedMemory/PosixSharedMemory.cpp @@ -66,6 +66,27 @@ struct btPointerCaster void* PosixSharedMemory::allocateSharedMemory(int key, int size, bool allowCreation) { #ifdef TEST_SHARED_MEMORY + + { + btSharedMemorySegment* seg = 0; + int i=0; + + for (i=0;im_segments.size();i++) + { + if (m_internalData->m_segments[i].m_key == key) + { + seg = &m_internalData->m_segments[i]; + break; + } + } + if (seg) + { + b3Error("already created shared memory segment using same key"); + return seg->m_sharedMemoryPtr; + } + + } + int flags = (allowCreation ? IPC_CREAT : 0) | 0666; int id = shmget((key_t) key, (size_t) size,flags); if (id < 0) From 4fc697f6464117d397c3f18ecf16658891e85c24 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 6 Jan 2017 10:19:19 -0800 Subject: [PATCH 6/6] fix _WIN32 lacking #include allow creation of multiple shared memory segments on win32. fix pybullet compilation on Visual Studio 2010 (old compiler) --- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 16 ++- examples/SharedMemory/Win32SharedMemory.cpp | 100 ++++++++++++++---- examples/pybullet/pybullet.c | 7 +- 3 files changed, 96 insertions(+), 27 deletions(-) diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index b5af22122..3fe496020 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -162,7 +162,12 @@ FILE* gTimingFile = 0; #ifndef __STDC_FORMAT_MACROS #define __STDC_FORMAT_MACROS #endif //__STDC_FORMAT_MACROS + +//see http://stackoverflow.com/questions/18107426/printf-format-for-unsigned-int64-on-windows +#ifndef _WIN32 #include +#endif + #define BT_TIMING_CAPACITY 16*65536 static bool m_firstTiming = true; @@ -246,12 +251,21 @@ struct btTimings char newname[1024]; static int counter2=0; - sprintf(newname,"%s%d",name,counter2++); + +#ifdef _WIN32 + + fprintf(gTimingFile,"{\"cat\":\"timing\",\"pid\":1,\"tid\":%d,\"ts\":%I64d.%s ,\"ph\":\"B\",\"name\":\"%s\",\"args\":{}},\n", + threadId, startTimeDiv1000,startTimeRem1000Str, newname); + fprintf(gTimingFile,"{\"cat\":\"timing\",\"pid\":1,\"tid\":%d,\"ts\":%I64d.%s ,\"ph\":\"E\",\"name\":\"%s\",\"args\":{}}", + threadId, endTimeDiv1000,endTimeRem1000Str,newname); + +#else fprintf(gTimingFile,"{\"cat\":\"timing\",\"pid\":1,\"tid\":%d,\"ts\":%" PRIu64 ".%s ,\"ph\":\"B\",\"name\":\"%s\",\"args\":{}},\n", threadId, startTimeDiv1000,startTimeRem1000Str, newname); fprintf(gTimingFile,"{\"cat\":\"timing\",\"pid\":1,\"tid\":%d,\"ts\":%" PRIu64 ".%s ,\"ph\":\"E\",\"name\":\"%s\",\"args\":{}}", threadId, endTimeDiv1000,endTimeRem1000Str,newname); +#endif #endif } diff --git a/examples/SharedMemory/Win32SharedMemory.cpp b/examples/SharedMemory/Win32SharedMemory.cpp index 5e95f9be0..7a2c688ea 100644 --- a/examples/SharedMemory/Win32SharedMemory.cpp +++ b/examples/SharedMemory/Win32SharedMemory.cpp @@ -2,22 +2,36 @@ #include "Win32SharedMemory.h" #include "Bullet3Common/b3Logging.h" #include "Bullet3Common/b3Scalar.h" +#include "LinearMath/btAlignedObjectArray.h" #include #include //see also https://msdn.microsoft.com/en-us/library/windows/desktop/aa366551%28v=vs.85%29.aspx -struct Win32SharedMemoryInteralData +struct Win32SharedMemorySegment { + int m_key; HANDLE m_hMapFile; - void* m_buf; TCHAR m_szName[1024]; + + Win32SharedMemorySegment() + :m_hMapFile(0), + m_buf(0), + m_key(-1) + { + m_szName[0] = 0; + } + +}; + +struct Win32SharedMemoryInteralData +{ + btAlignedObjectArray m_segments; + Win32SharedMemoryInteralData() - :m_hMapFile(0), - m_buf(0) { } }; @@ -33,32 +47,53 @@ Win32SharedMemory::~Win32SharedMemory() void* Win32SharedMemory::allocateSharedMemory(int key, int size, bool allowCreation) { - b3Assert(m_internalData->m_buf==0); + { + + Win32SharedMemorySegment* seg = 0; + int i=0; + + for (i=0;im_segments.size();i++) + { + if (m_internalData->m_segments[i].m_key == key) + { + seg = &m_internalData->m_segments[i]; + break; + } + } + if (seg) + { + b3Error("already created shared memory segment using same key"); + return seg->m_buf; + } + } + + Win32SharedMemorySegment seg; + seg.m_key = key; #ifdef UNICODE - swprintf_s (m_internalData->m_szName,TEXT("MyFileMappingObject%d"),key); + swprintf_s (seg.m_szName,TEXT("MyFileMappingObject%d"),key); #else - sprintf(m_internalData->m_szName,"MyFileMappingObject%d",key); + sprintf(seg.m_szName,"MyFileMappingObject%d",key); #endif - m_internalData->m_hMapFile = OpenFileMapping( + seg.m_hMapFile = OpenFileMapping( FILE_MAP_ALL_ACCESS, // read/write access FALSE, // do not inherit the name - m_internalData->m_szName); // name of mapping object + seg.m_szName); // name of mapping object - if (m_internalData->m_hMapFile==NULL) + if (seg.m_hMapFile==NULL) { if (allowCreation) { - m_internalData->m_hMapFile = CreateFileMapping( + seg.m_hMapFile = CreateFileMapping( INVALID_HANDLE_VALUE, // use paging file NULL, // default security PAGE_READWRITE, // read/write access 0, // maximum object size (high-order DWORD) size, // maximum object size (low-order DWORD) - m_internalData->m_szName); // name of mapping object + seg.m_szName); // name of mapping object } else { b3Warning("Could not create file mapping object (%d).\n",GetLastError()); @@ -67,37 +102,56 @@ void* Win32SharedMemory::allocateSharedMemory(int key, int size, bool allowCre } - m_internalData->m_buf = MapViewOfFile(m_internalData->m_hMapFile, // handle to map object + seg.m_buf = MapViewOfFile(seg.m_hMapFile, // handle to map object FILE_MAP_ALL_ACCESS, // read/write permission 0, 0, size); - if (m_internalData->m_buf == NULL) + if (seg.m_buf == NULL) { b3Warning("Could not map view of file (%d).\n",GetLastError()); - CloseHandle(m_internalData->m_hMapFile); + CloseHandle(seg.m_hMapFile); return 0; } - return m_internalData->m_buf; + m_internalData->m_segments.push_back(seg); + return seg.m_buf; } void Win32SharedMemory::releaseSharedMemory(int key, int size) { - if (m_internalData->m_buf) - { + Win32SharedMemorySegment* seg = 0; + int i=0; + + for (i=0;im_segments.size();i++) + { + if (m_internalData->m_segments[i].m_key == key) + { + seg = &m_internalData->m_segments[i]; + break; + } + } - UnmapViewOfFile(m_internalData->m_buf); - m_internalData->m_buf=0; + if (seg==0) + { + b3Error("Couldn't find shared memory segment"); + return; } - if (m_internalData->m_hMapFile) + if (seg->m_buf) { - CloseHandle(m_internalData->m_hMapFile); - m_internalData->m_hMapFile = 0; + UnmapViewOfFile(seg->m_buf); + seg->m_buf=0; } + if (seg->m_hMapFile) + { + CloseHandle(seg->m_hMapFile); + seg->m_hMapFile = 0; + } + + m_internalData->m_segments.removeAtIndex(i); } Win32SharedMemoryServer::Win32SharedMemoryServer() diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 2fce9796f..4fed9e3a5 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1174,6 +1174,8 @@ static PyObject* pybullet_setGravity(PyObject* self, PyObject* args, PyObject* k double gravZ = -10.0; int ret; b3PhysicsClientHandle sm = 0; + b3SharedMemoryCommandHandle command; + b3SharedMemoryStatusHandle statusHandle; int physicsClientId = 0; static char *kwlist[] = { "gravX", "gravY", "gravZ", "physicsClientId", NULL }; @@ -1189,9 +1191,8 @@ static PyObject* pybullet_setGravity(PyObject* self, PyObject* args, PyObject* k } - b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); - b3SharedMemoryStatusHandle statusHandle; - + command = b3InitPhysicsParamCommand(sm); + ret = b3PhysicsParamSetGravity(command, gravX, gravY, gravZ); // ret = b3PhysicsParamSetTimeStep(command, timeStep); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);